diff --git a/examples/Atlas/Project.toml b/examples/Atlas/Project.toml new file mode 100644 index 0000000..0f84fdd --- /dev/null +++ b/examples/Atlas/Project.toml @@ -0,0 +1,15 @@ +[deps] +ForwardDiff = "f6369f11-7733-5829-9624-2563aa707210" +HSL_jll = "017b0a0e-03f4-516a-9b91-836bbd1904dd" +Ipopt = "b6b21f68-93f8-5de0-b562-5493be1d77c9" +JLD2 = "033835bb-8acc-5ee8-8aae-3f567f8a3819" +JuMP = "4076af6c-e467-56ae-b986-b466b2749572" +MathOptInterface = "b8f27783-ece8-5eb3-8dc8-9495eed66fee" +MathProgIncidence = "892fab00-3092-4bd0-9c46-66676a93f84e" +MeshCat = "283c5d60-a78f-5afe-a0af-af636b173e11" +MeshCatMechanisms = "6ad125db-dd91-5488-b820-c1df6aab299d" +Revise = "295af30f-e4ad-537b-8983-00126c2a3abe" +RigidBodyDynamics = "366cf18f-59d5-5db9-a4de-86a9f6786172" +Rotations = "6038ab10-8711-5258-84ad-4b1120ba62dc" +SparseArrays = "2f01184e-e22b-5df5-ae63-d93ebab69eaf" +StaticArrays = "90137ffa-7385-5640-81b9-e52037218182" diff --git a/examples/Atlas/atlas_balancing.jl b/examples/Atlas/atlas_balancing.jl new file mode 100644 index 0000000..2f24177 --- /dev/null +++ b/examples/Atlas/atlas_balancing.jl @@ -0,0 +1,411 @@ +using Revise +using JLD2 +using SparseArrays +using MathOptInterface.Nonlinear.SymbolicAD +import MathOptInterface as MOI +using JuMP, Ipopt, HSL_jll +using LinearAlgebra + +# include(joinpath(@__DIR__, "../mpc_utils.jl")) +include(joinpath(@__DIR__, "atlas_utils.jl")) + +# Setup model and visualizer +atlas = Atlas(); +vis = Visualizer(); +mvis = init_visualizer(atlas, vis) + +# Load balanced reference +@load joinpath(@__DIR__, "atlas_ref.jld2") x_ref u_ref; +visualize!(atlas, mvis, x_ref) + +# Calculate discrete dynamics for a balanced position +# h = 0.01; +# Ad = FD.jacobian(x->rk4(atlas, x, u_ref, h), x_ref); +# Bd = FD.jacobian(u->rk4(atlas, x_ref, u, h), u_ref); + +h = 0.01 +@time rk4(atlas, x_ref, u_ref, h) + +# # Simulate +N = 300; +X = [zeros(atlas.nx) for _ = 1:N]; +U = zeros(atlas.nu) +X[1] = deepcopy(x_ref); +X[1][atlas.nq + 5] = 1.3; # Perturb i.c. + +# Run simulation +@time for k = 1:N - 1 + # Integrate + global X[k + 1] = rk4(atlas, X[k], u_ref, h) +end + +animate!(atlas, mvis, X, Δt=h); + + +""" + memoize_dynamics_and_jacobian(foo, n_in, n_out) + +Returns an array of length `n_out`, where each element is a tuple +`(scalar_fun, grad_fun!)`. + +- `scalar_fun(x...)` returns the i-th component of `foo(x...)` in normal calls (Float64). +- In Dual/AD mode, it returns the i-th component but triggers a single Jacobian evaluation and caches it. + +- `grad_fun!(g, x...)` writes into `g` the partial derivatives of that i-th component w.r.t. x. + +All `n_out` scalar functions share the same cached value of the *entire* vector `foo(x...)` +and the *entire* Jacobian for the last input `x...`. +""" +function memoize_dynamics_and_jacobian(foo::Function, n_in::Int, n_out::Int) + # Cache for normal (Float64) evaluation + last_x_f = nothing + last_f = nothing # Vector{Float64} from foo(x) + + # Cache for AD (Dual) evaluation + last_x_J = nothing + last_f_J = nothing # Vector{Dual} from foo(x) + last_J = nothing # Matrix of partials (size n_out x n_in) + + # Optional: pre-make a JacobianConfig if you like: + # x0 = zeros(n_in) + # jac_cfg = ForwardDiff.JacobianConfig(foo, x0) + + # This local function returns the i-th scalar output for the given x... + # In normal Float64 calls, it returns last_f[i]. + # In AD calls (Dual etc.), it ensures last_J is computed and returns last_f_J[i]. + function f_i(i, x::Vararg{T}) where {T<:Real} + if T == Float64 + # Normal evaluation mode + if x !== last_x_f + last_x_f = x + last_f = foo(x...) + end + return last_f[i] + else + # Dual/AD evaluation mode + if x !== last_x_J + last_x_J = x + # Evaluate all outputs + local x_vec = collect(x) + last_f_J = foo(x_vec...) + + # Evaluate the entire Jacobian in one pass + # last_J = ForwardDiff.jacobian(z -> foo(z...), x_vec, jac_cfg) + last_J = ForwardDiff.jacobian(z -> foo(z...), x_vec) + end + # Return the i-th output (primal part). + return last_f_J[i] + end + end + + # Now build an array of (scalar_fun, gradient_callback!) for each output dimension + result = Vector{Tuple{Function, Function}}(undef, n_out) + for i in 1:n_out + # 1) The scalar function to pass to JuMP + scalar_fun = (args...) -> f_i(i, args...) + + # 2) The gradient callback that JuMP/Ipopt calls: we fill `g` with partial derivatives + # grad_fun! = (g, args...) -> begin + # # Make sure last_J is up to date for this x... + # _ = f_i(i, args...) # triggers AD if needed + # # Now fill g with row i of last_J + # @inbounds for col in 1:length(args) + # g[col] = last_J[i, col] + # end + # return + # end + grad_fun! = (g, args...) -> begin + if last_J === nothing + # We haven't computed the Jacobian yet, or we are in reverse mode. + # Manually call ForwardDiff now with `args` to get it: + xvec = collect(args) + # Evaluate the function for the primal: + last_f_J = foo(xvec...) # store if needed + last_J = ForwardDiff.jacobian(z -> foo(z...), xvec) + end + # Now fill g with row i of last_J + @inbounds for col in 1:length(args) + g[col] = last_J[i, col] + end + return + end + + result[i] = (scalar_fun, grad_fun!) + end + return result +end + + +function atlas_dynamics(xu::T...) where {T<:Real} + h = 0.01 + x = collect(xu[1:atlas.nx]) + u = collect(xu[atlas.nx+1:end]) + #return rk4(atlas, x, u, h) + return explicit_euler(atlas, x, u, h) +end + +# Lets define a jump model that solves the MPC problem +# min ∑_t ||x_t - x_ref||_2^2 +# s.t. x_{t+1} = rk4(x_t, u_t) : this needs to be a jump operator for which we will need to define a method to calculate the jacobian and hessian +# u_min <= u_t <= u_max + +function build_and_solve_mpc(atlas_obj::Atlas, x_ref::Vector{Float64}, X_start::Vector{Float64}, N::Int; optimizer=optimizer_with_attributes(Ipopt.Optimizer, + # "print_level" => 0, + "hsllib" => HSL_jll.libhsl_path, + "linear_solver" => "MA27", + "max_iter" => 20, + ) +) + model = Model() + set_optimizer(model, optimizer) + + # For demonstration, let's define: + # x[t=1:N, 1:atlas.nx] + # u[t=1:N-1, 1:atlas.nu] + @variable(model, x[1:N, 1:atlas_obj.nx]) + @variable(model, -atlas_obj.torque_limits[i] <= u[t=1:N-1,i=1:atlas.nu] <= atlas.torque_limits[i]) + # ^ adapt the indexing if torque_limits is an array of length nu, etc. + + # Objective: sum of squared error from x_ref + @objective(model, Min, sum( (x[t,j] - x_ref[j])^2 for t in 2:N for j in 1:atlas_obj.nx ) ) + + # Build the memoized function array for the multi-output dynamics + # so we can call the i-th dimension of next state individually + #dyn_ops = memoize_dynamics_and_jacobian(atlas_dynamics, + # atlas_obj.nx + atlas_obj.nu, + # atlas_obj.nx) + + VNO_dim = 2*atlas_obj.nx + atlas_obj.nu + # The input variable to this function: + # [ x[t+1,:], x[t,:], u[t,:] ] + jacobian_structure = Tuple{Int,Int}[] + append!(jacobian_structure, map(i -> (i,i), 1:atlas_obj.nx)) + for i in 1:atlas_obj.nx, j in 1:(atlas_obj.nx + atlas_obj.nu) + push!(jacobian_structure, (i, j + atlas_obj.nx)) + end + hessian_lagrangian_structure = [ + (i, j) + for i in atlas_obj.nx+1:VNO_dim + for j in atlas_obj.nx+1:VNO_dim + ] + VNO = MOI.VectorNonlinearOracle(; + dimension = VNO_dim, + l = zeros(atlas_obj.nx), + u = zeros(atlas_obj.nx), + eval_f = (ret, x) -> begin + ret[1:atlas_obj.nx] .= x[1:atlas_obj.nx] - atlas_dynamics(x[atlas_obj.nx + 1:VNO_dim]...) + return + end, + jacobian_structure, + eval_jacobian = (ret, x) -> begin + dyn_jac = ForwardDiff.jacobian(x -> atlas_dynamics(x...), x[atlas_obj.nx + 1:VNO_dim]) + jnnz = length(jacobian_structure) + ret[1:atlas_obj.nx] .= ones(atlas_obj.nx) + nx = atlas_obj.nx; nu = atlas_obj.nu + ret[atlas_obj.nx+1:jnnz] .= - reshape(dyn_jac', nx * (nx + nu)) + return + end, + hessian_lagrangian_structure, + eval_hessian_lagrangian = (ret, x, λ) -> begin + hess = ForwardDiff.hessian(x -> dot(λ, atlas_dynamics(x...)), x[atlas_obj.nx + 1:VNO_dim]) + hnnz = length(hessian_lagrangian_structure) + ret[1:hnnz] .= - reshape(hess, hnnz) + return + end + ) + for t in 1:(N-1) + vars = vcat(x[t+1,:], x[t, :], u[t, :]) + JuMP.@constraint(model, vars in VNO) + end + + # Add constraints: x[t+1] = f(x[t], u[t]) for t=1 to N-1 + #for t in 1:(N-1), i in 1:atlas_obj.nx + # scalar_fun, grad_fun! = dyn_ops[i] + # op = add_nonlinear_operator( + # model, + # atlas_obj.nx + atlas_obj.nu, # number of inputs + # scalar_fun, # f_i + # grad_fun!, # gradient callback + # name = Symbol("dyn_$(t)_$(i)") + # ) + # # Bind the operator to the constraint x[t+1, i] == f_i( [x[t,:]; u[t,:]]... ) + # @constraint(model, x[t+1,i] == op( [x[t, :]; u[t, :]]... )) + #end + + # Possibly set an initial condition constraint: x[1, :] = x_ref + @constraint(model, [j in 1:atlas_obj.nx], x[1,j] == X_start[j]) + + # Solve + optimize!(model) + return model, value.(x), value.(u) +end + +N = 10 +X_start = deepcopy(x_ref) +X_start[atlas.nq + 5] = 1.3 +model, X_solve, U_solve = build_and_solve_mpc(atlas, x_ref, X_start, N; optimizer=optimizer_with_attributes(Ipopt.Optimizer, + # "print_level" => 0, + "linear_solver" => "ma97", + #"hessian_approximation" => "limited-memory", + #"max_iter" => 20, + "mu_target" => 1e-8, + "print_user_options" => "yes", + ) +) +termination_status(model) + +# Now we can simulate the system with the controls U_solve +X = [zeros(atlas.nx) for _ = 1:N]; +X[1] = deepcopy(x_ref); +X[1][atlas.nq + 5] = 1.3; # Perturb i.c. + +for k = 1:N - 1 + X[k + 1] = rk4(atlas, X[k], U_solve[k, :], h) +end + +animate!(atlas, mvis, X, Δt=h); + +error = sum( norm(X_solve[t,:] .- X[t]) for t in 1:N ) + +# # Set up cost matrices (hand-tuned) +# Q = spdiagm([1e3*ones(12); repeat([1e1; 1e1; 1e3], 3); 1e1*ones(8); 1e2*ones(12); repeat([1; 1; 1e2], 3); 1*ones(8)]); +# R = spdiagm(1e-3*ones(atlas.nu)); + +# # Calculate infinite-horizon LQR cost-to-go and gain matrices +# K, Qf = ihlqr(Ad, Bd, Q, R, Q, max_iters = 1000); + +# # Define additional constraints for the QP (just torques for Atlas) +# horizon = 2; +# A_torque = kron(I(horizon), [I(atlas.nu) zeros(atlas.nu, atlas.nx)]); +# l_torque = repeat(-atlas.torque_limits - u_ref, horizon); +# u_torque = repeat(atlas.torque_limits - u_ref, horizon); + +# # Setup QP +# H, g, A, l, u, g_x0, lu_x0 = gen_condensed_mpc_qp(Ad, Bd, Q, R, Qf, horizon, A_torque, l_torque, u_torque, K); + +# # Setup solver +# m = ReLUQP.setup(H, g, A, l, u, verbose = false, eps_primal=1e-2, eps_dual=1e-2, max_iters=10, iters_btw_checks=1); + +# # Simulate +# N = 300; +# X = [zeros(atlas.nx) for _ = 1:N]; +# U = [zeros(atlas.nu) for _ = 1:N]; +# X[1] = deepcopy(x_ref); +# X[1][atlas.nq + 5] = 1.3; # Perturb i.c. + +# # Warmstart solver +# Δx = X[1] - x_ref; +# ReLUQP.update!(m, g = g + g_x0*Δx, l = l + lu_x0*Δx, u = u + lu_x0*Δx); +# m.opts.max_iters = 4000; +# m.opts.check_convergence = false; +# ReLUQP.solve(m); +# m.opts.max_iters = 10; + +# Run simulation +# for k = 1:N - 1 + # Get error + # global Δx = X[k] - x_ref + + # Update solver + # ReLUQP.update!(m, g = g + g_x0*Δx, l = l + lu_x0*Δx, u = u + lu_x0*Δx) + + # Solve and get controls + # results = ReLUQP.solve(m) + # global U[k] = results.x[1:atlas.nu] - K*Δx + + # Integrate + # global X[k + 1] = rk4(atlas, X[k], clamp.(u_ref + U[k], -atlas.torque_limits, atlas.torque_limits), h) +# end + +#X = [value.(x[t,:]) for t=1:N] +#X = [X_solve[t, :] for t=1:N] +# +#animate!(atlas, mvis, X, Δt=h); +#readline() +# +# +################ +#include(joinpath(@__DIR__, "rigidbodyutils.jl")) +#include(joinpath(@__DIR__, "atlas_utils.jl")) +# +#model = Model() +#optimizer=optimizer_with_attributes(Ipopt.Optimizer, +# # "print_level" => 0, +# "hsllib" => HSL_jll.libhsl_path, +# "linear_solver" => "MA27" +#) +#set_optimizer(model, optimizer) +# +#@variable(model, x[1:N, 1:atlas.nx]) +#@variable(model, -atlas.torque_limits[i] <= u[t=1:N-1,i=1:atlas.nu] <= atlas.torque_limits[i]) +# +#dyn_result = dynamics(atlas, convert.(NonlinearExpr, x[1, :]), convert.(NonlinearExpr,u[1, :])) +# +#function atlas_dynamics(x, u) +# h = 0.01 +# return rk4(atlas, x, u, h) +#end +# +##function build_and_solve_mpc(atlas_obj::Atlas, x_ref::Vector{Float64}, X_start::Vector{Float64}, N::Int; optimizer=optimizer_with_attributes(Ipopt.Optimizer, +## # "print_level" => 0, +## "hsllib" => HSL_jll.libhsl_path, +## "linear_solver" => "MA27" +## ) +##) +## model = Model() +## set_optimizer(model, optimizer) +## +## # For demonstration, let's define: +## # x[t=1:N, 1:atlas.nx] +## # u[t=1:N-1, 1:atlas.nu] +## @variable(model, x[1:N, 1:atlas_obj.nx]) +## @variable(model, -atlas_obj.torque_limits[i] <= u[t=1:N-1,i=1:atlas.nu] <= atlas_obj.torque_limits[i]) +## # ^ adapt the indexing if torque_limits is an array of length nu, etc. +## +## # Objective: sum of squared error from x_ref +## @objective(model, Min, sum( (x[t,j] - x_ref[j])^2 for t in 2:N for j in 1:atlas_obj.nx ) ) +## +## for t in 1:(N-1) +## # Bindconstraint x[t+1, i] == f_i( [x[t,:]; u[t,:]]... ) +## @constraint(model, x[t+1, :] == atlas_dynamics( convert.(NonlinearExpr, x[t, :]), convert.(NonlinearExpr,u[t, :]))) +## end +## +## # Possibly set an initial condition constraint: x[1, :] = x_ref +## @constraint(model, [j in 1:atlas_obj.nx], x[1,j] == X_start[j]) +## +## # Solve +## optimize!(model) +## return model, value.(x), value.(u) +##end +# +#N = 2 +#X_start = deepcopy(x_ref) +#X_start[atlas.nq + 5] = 1.3 +#model, X_solve, U_solve = build_and_solve_mpc(atlas, x_ref, X_start, N; optimizer=optimizer_with_attributes(Ipopt.Optimizer, +# # "print_level" => 0, +# "linear_solver" => "ma97", +# "hessian_approximation" => "limited-memory", +# "max_iter" => 300, +# "mu_target" => 1e-8, +# "print_info_string" => "yes", +# ) +#) +#termination_status(model) +# +## Now we can simulate the system with the controls U_solve +#X = [zeros(atlas.nx) for _ = 1:N]; +#X[1] = deepcopy(x_ref); +#X[1][atlas.nq + 5] = 1.3; # Perturb i.c. +# +#for k = 1:N - 1 +# X[k + 1] = rk4(atlas, X[k], U_solve[k, :], h) +#end +# +#animate!(atlas, mvis, X, Δt=h); +# +#error = sum( norm(X_solve[t,:] .- X[t]) for t in 1:N ) +# +# +#function foo!(q::AbstractVector{T}) where {T} +# q .= zero(T) +#end diff --git a/examples/Atlas/atlas_ref.jld2 b/examples/Atlas/atlas_ref.jld2 new file mode 100644 index 0000000..72cc873 Binary files /dev/null and b/examples/Atlas/atlas_ref.jld2 differ diff --git a/examples/Atlas/atlas_utils.jl b/examples/Atlas/atlas_utils.jl new file mode 100644 index 0000000..3370b9e --- /dev/null +++ b/examples/Atlas/atlas_utils.jl @@ -0,0 +1,143 @@ +# Setup the dynamics and visualization for the Atlas model +using RigidBodyDynamics +using MeshCat +using MeshCatMechanisms +using Random +using StaticArrays +using Rotations +using LinearAlgebra +using ForwardDiff +import ForwardDiff as FD + +const URDFPATH = joinpath(@__DIR__, "urdf", "atlas_all.urdf") + +struct Atlas + mech::Mechanism{Float64} + statecache::StateCache + dynrescache::DynamicsResultCache + nq::Int + nv::Int + nx::Int + nu::Int + joint_names + torque_limits::Vector{Float64} + function Atlas() + # Create the Mechanism (defaults to floating base) + mech = parse_urdf(URDFPATH, floating=true, remove_fixed_tree_joints=true) + + ### Pin the left foot to the ground + foot_frame = findbody(mech, "l_foot") + pelvis_frame = findbody(mech, "pelvis") + world_frame = findbody(mech, "world") + + state = MechanismState(mech) + pelvis_to_foot = translation(relative_transform(state, + default_frame(pelvis_frame), default_frame(foot_frame))) + + foot_location = @SVector [pelvis_to_foot[1], pelvis_to_foot[2], -0.08] + + # add fixed joint to ground + foot_joint = Joint("foot_joint", Fixed{Float64}()) + world_to_joint = Transform3D(frame_before(foot_joint), + default_frame(world_frame), + -foot_location) + + attach!(mech, world_frame, foot_frame, foot_joint, joint_pose=world_to_joint) + + remove_joint!(mech, findjoint(mech, "pelvis_to_world")) + + ## Get mechanism details + nq = num_positions(mech) + nv = num_velocities(mech) + nx = nq + nv + nu = nq + + joint_names = [joint.name for joint in joints(mech)[2:end]] # Exclude foot joint + limits_dict = Dict( # Torque TODO: lower, upper + "l_leg_akx" => [360.], + "l_leg_aky" => [740.], + "l_leg_kny" => [890.], + "l_leg_hpy" => [840.], + "l_leg_hpx" => [530.], + "l_leg_hpz" => [275.], + "back_bkz" => [106.], + "r_leg_hpz" => [275.], + "back_bky" => [445.], + "r_leg_hpx" => [530.], + "back_bkx" => [300.], + "r_leg_hpy" => [840.], + "l_arm_shz" => [87.], + "r_arm_shz" => [87.], + "r_leg_kny" => [890.], + "l_arm_shx" => [99.], + "r_arm_shx" => [99.], + "r_leg_aky" => [740.], + "l_arm_ely" => [63.], + "r_arm_ely" => [63.], + "r_leg_akx" => [360.], + "l_arm_elx" => [112.], + "r_arm_elx" => [112.], + "l_arm_uwy" => [25.], + "r_arm_uwy" => [25.], + "l_arm_mwx" => [25.], + "r_arm_mwx" => [25.], + "l_arm_lwy" => [25.], + "r_arm_lwy" => [25.] + ) + torque_limits = [limits_dict[name][1] for name in joint_names] + + new(mech, StateCache(mech), DynamicsResultCache(mech), + nq, nv, nx, nu, + joint_names, torque_limits) + end +end + +function dynamics(model::Atlas, x::AbstractVector{T1}, u::AbstractVector{T2}) where {T1, T2} + T = promote_type(T1, T2) + state = model.statecache[T] + dyn_result = model.dynrescache[T] + #println("dyn_result.M: ", dyn_result.massmatrix) + + # Set the mechanism state + copyto!(state, x) + + # # Perform forward dynamics + dynamics!(dyn_result, state, u) + + return [dyn_result.q̇; dyn_result.v̇] +end + +function explicit_euler(model::Atlas, x, u, h) + return x + h * dynamics(model, x, u) +end + +function rk4(model::Atlas, x, u, h) + k1 = dynamics(model, x, u) + k2 = dynamics(model, x + h/2*k1, u) + k3 = dynamics(model, x + h/2*k2, u) + k4 = dynamics(model, x + h*k3, u) + return x + h/6*(k1 + 2*k2 + 2*k3 + k4) +end + +function init_visualizer(model::Atlas, vis::Visualizer) + delete!(vis) + meshes_path = joinpath(@__DIR__, "urdf") + mvis = MechanismVisualizer(model.mech, URDFVisuals(URDFPATH, package_path=[meshes_path]), vis) + return mvis +end + +function visualize!(model::Atlas, mvis::MechanismVisualizer, q) + set_configuration!(mvis, q[1:model.nq]) +end + +function animate!(model::Atlas, mvis::MechanismVisualizer, qs; Δt=0.001) + anim = MeshCat.Animation(mvis.visualizer; fps=convert(Int, floor(1.0 / Δt))) + for (t, q) in enumerate(qs) + MeshCat.atframe(anim, t) do + set_configuration!(mvis, q[1:model.nq]) + end + end + MeshCat.setanimation!(mvis, anim) + + return anim +end diff --git a/examples/Atlas/rigidbodyutils.jl b/examples/Atlas/rigidbodyutils.jl new file mode 100644 index 0000000..42fa594 --- /dev/null +++ b/examples/Atlas/rigidbodyutils.jl @@ -0,0 +1,42 @@ +using JuMP +using Ipopt, HSL_jll +import Base: sincos, promote_type +import RigidBodyDynamics: dynamics_solve! + +sincos(x::NonlinearExpr) = (sin(x), cos(x)) +promote_type(::Type{<:NonlinearExpr}, ::Type{<:NonlinearExpr}) = NonlinearExpr +promote_type(::Type{<:NonlinearExpr}, ::Type{<:Real}) = NonlinearExpr +NonlinearExpr(x::Int64) = convert(NonlinearExpr, x * AffExpr(1.0)) # Dummy conversion for NonlinearExpr +Base.:*(x::NonlinearExpr, y::UniformScaling{Bool}) = convert(NonlinearExpr, x * AffExpr(y.λ)) # Dummy conversion for UniformScaling + +""" + function dynamics_solve!(v̇::AbstractVector, λ::AbstractVector, + G::Matrix{NonlinearExpr}, r::Vector{NonlinearExpr} + ) + +Creates JuMP Constraints equivalent to the linear system. +""" +function RigidBodyDynamics.dynamics_solve!(_v̇::AbstractVector, λ::AbstractVector, + G::Matrix{NonlinearExpr}, _c::AbstractVector, k::AbstractVector, nv::Int, nl::Int, τ::AbstractVector +) + println("Solving dynamics with nl = $nl, nv = $nv") + println("c: ", _c) + println("k: ", k) + println("τ: ", τ) + println("v̇: ", _v̇) + println("Λ: ", λ) + c = parent(_c) + r = [τ - c; -k] + v̇ = parent(_v̇) + model = owner_model(r[1]) + + if nl == 0 + aux_v̇ = @variable(model, [1:nv]) + con = @constraint(model, G * aux_v̇ .== r) + println("Constraint: ", con) + v̇ .= aux_v̇ + else + @constraint(model, G * [v̇; λ] .== r) + end + nothing +end diff --git a/examples/Atlas/test.jl b/examples/Atlas/test.jl new file mode 100644 index 0000000..fc4228a --- /dev/null +++ b/examples/Atlas/test.jl @@ -0,0 +1,62 @@ +using RigidBodyDynamics +using LinearAlgebra +using StaticArrays + +g = -9.81 # gravitational acceleration in z-direction +world = RigidBody{Float64}("world") +doublependulum = Mechanism(world; gravity = SVector(0, 0, g)) + +axis = SVector(0., 1., 0.) # joint axis +I_1 = 0.333 # moment of inertia about joint axis +c_1 = -0.5 # center of mass location with respect to joint axis +m_1 = 1. # mass +frame1 = CartesianFrame3D("upper_link") # the reference frame in which the spatial inertia will be expressed +inertia1 = SpatialInertia(frame1, + moment=I_1 * axis * axis', + com=SVector(0, 0, c_1), + mass=m_1 +) + +upperlink = RigidBody(inertia1) + +shoulder = Joint("shoulder", Revolute(axis)) + +before_shoulder_to_world = one(Transform3D, + frame_before(shoulder), default_frame(world) +) + +attach!(doublependulum, world, upperlink, shoulder, + joint_pose = before_shoulder_to_world +) + +l_1 = -1. # length of the upper link +I_2 = 0.333 # moment of inertia about joint axis +c_2 = -0.5 # center of mass location with respect to joint axis +m_2 = 1. # mass +inertia2 = SpatialInertia(CartesianFrame3D("lower_link"), + moment=I_2 * axis * axis', + com=SVector(0, 0, c_2), + mass=m_2) +lowerlink = RigidBody(inertia2) +elbow = Joint("elbow", Revolute(axis)) +before_elbow_to_after_shoulder = Transform3D( + frame_before(elbow), frame_after(shoulder), SVector(0, 0, l_1)) +attach!(doublependulum, upperlink, lowerlink, elbow, + joint_pose = before_elbow_to_after_shoulder) + +# Now we can compute the dynamics of the system +state = MechanismState(doublependulum) + +set_configuration!(state, shoulder, 0.3) +set_configuration!(state, elbow, 0.4) +set_velocity!(state, shoulder, 1.) +set_velocity!(state, elbow, 2.); + +q = configuration(state) +v = velocity(state) + +ts, qs, vs = simulate(state, 5., Δt = 1e-3); + +open_loop_dynamics = Dynamics(doublependulum) + +dynamics!(open_loop_dynamics.resultcache, state, open_loop_dynamics.τcache) \ No newline at end of file diff --git a/examples/Atlas/urdf/atlas.urdf b/examples/Atlas/urdf/atlas.urdf new file mode 100644 index 0000000..6620a6d --- /dev/null +++ b/examples/Atlas/urdf/atlas.urdf @@ -0,0 +1,840 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/Atlas/urdf/atlas_all.urdf b/examples/Atlas/urdf/atlas_all.urdf new file mode 100644 index 0000000..ffcf5c5 --- /dev/null +++ b/examples/Atlas/urdf/atlas_all.urdf @@ -0,0 +1,761 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/Atlas/urdf/atlas_arms_legs_only.urdf b/examples/Atlas/urdf/atlas_arms_legs_only.urdf new file mode 100644 index 0000000..aee65a9 --- /dev/null +++ b/examples/Atlas/urdf/atlas_arms_legs_only.urdf @@ -0,0 +1,761 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/Atlas/urdf/mesh/GRIPPER_OPEN_chull.obj b/examples/Atlas/urdf/mesh/GRIPPER_OPEN_chull.obj new file mode 100644 index 0000000..afb2832 --- /dev/null +++ b/examples/Atlas/urdf/mesh/GRIPPER_OPEN_chull.obj @@ -0,0 +1,60 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object GRIPPER_OPEN_chull.obj +# +# Vertices: 12 +# Faces: 20 +# +#### +vn 0.786797 -0.050764 0.615120 +v -0.059683 0.006619 -0.157520 +vn 0.785453 -0.607880 0.116389 +v -0.109043 0.052411 0.020638 +vn 0.465018 0.835991 -0.291337 +v -0.116677 -0.053183 0.056221 +vn 0.296204 -0.897864 0.325735 +v -0.052370 0.064205 -0.102480 +vn -0.041855 -0.734235 -0.677604 +v -0.091363 0.047651 0.059568 +vn 0.353793 0.857416 0.373723 +v -0.035825 -0.060884 -0.145542 +vn -0.281046 0.957985 -0.057255 +v 0.046467 -0.063704 -0.096671 +vn -0.804412 -0.583963 -0.109122 +v 0.121674 0.009207 0.054709 +vn -0.190676 0.712072 -0.675719 +v 0.097004 -0.013613 0.058171 +vn -0.197864 -0.974292 -0.107723 +v 0.043548 0.063666 -0.094146 +vn -0.572674 -0.513503 0.639030 +v 0.047817 0.041121 -0.153120 +vn -0.694394 0.279935 0.662913 +v 0.050376 -0.029320 -0.156672 +# 12 vertices, 0 vertices normals + +f 2//2 3//3 1//1 +f 4//4 10//10 2//2 +f 6//6 3//3 7//7 +f 2//2 10//10 5//5 +f 2//2 1//1 4//4 +f 3//3 6//6 1//1 +f 7//7 3//3 9//9 +f 9//9 3//3 5//5 +f 10//10 8//8 5//5 +f 9//9 8//8 7//7 +f 11//11 8//8 10//10 +f 8//8 9//9 5//5 +f 7//7 8//8 12//12 +f 4//4 11//11 10//10 +f 5//5 3//3 2//2 +f 12//12 8//8 11//11 +f 4//4 1//1 11//11 +f 12//12 6//6 7//7 +f 1//1 6//6 12//12 +f 1//1 12//12 11//11 +# 20 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/head.obj b/examples/Atlas/urdf/mesh/head.obj new file mode 100644 index 0000000..d8309a6 --- /dev/null +++ b/examples/Atlas/urdf/mesh/head.obj @@ -0,0 +1,4589 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object head.obj +# +# Vertices: 1737 +# Faces: 1099 +# +#### +vn 0.000000 0.740144 0.672448 +v -0.109743 -0.011587 0.016418 +vn 0.000000 0.987469 0.157815 +v -0.126043 -0.008087 0.009118 +vn 0.000000 0.491760 0.870731 +v -0.126043 -0.011587 0.016418 +vn 0.000000 0.987469 -0.157815 +v -0.109743 -0.008087 0.009118 +vn 0.000000 0.222154 0.975011 +v -0.109743 -0.019487 0.018218 +vn 0.000000 0.222154 0.975011 +v -0.126043 -0.019487 0.018218 +vn 0.000000 -0.820720 0.571330 +v -0.109743 -0.025787 0.013218 +vn 0.000000 -0.621658 0.783289 +v -0.126043 -0.019487 0.018218 +vn 0.000000 -0.958570 0.284858 +v -0.126043 -0.025787 0.013218 +vn 0.000000 -0.621658 0.783289 +v -0.109743 -0.019487 0.018218 +vn 0.000000 -0.958934 -0.283628 +v -0.109743 -0.025787 0.005118 +vn 0.000000 -0.823648 -0.567102 +v -0.126043 -0.025787 0.005118 +vn 0.000000 -0.379160 -0.925331 +v -0.109743 -0.019487 0.000018 +vn 0.000000 -0.067717 -0.997705 +v -0.126043 -0.019487 0.000018 +vn 0.000000 0.491760 -0.870731 +v -0.109743 -0.011587 0.001818 +vn 0.000000 0.740144 -0.672448 +v -0.126043 -0.011587 0.001818 +vn -0.057970 0.900845 0.430254 +v -0.132143 -0.009687 0.011618 +vn -0.057970 0.900845 0.430254 +v -0.126043 -0.011587 0.016418 +vn -0.059227 0.900133 0.431571 +v -0.126043 -0.008087 0.009118 +vn -0.056462 0.901693 0.428674 +v -0.132143 -0.012587 0.017718 +vn 0.170253 0.220115 0.960502 +v -0.132143 -0.012587 0.017718 +vn 0.170253 0.220115 0.960502 +v -0.126043 -0.019487 0.018218 +vn 0.168908 0.218962 0.961002 +v -0.126043 -0.011587 0.016418 +vn 0.171884 0.221513 0.959890 +v -0.132143 -0.019087 0.019218 +vn 0.087798 -0.618995 0.780472 +v -0.132143 -0.019087 0.019218 +vn 0.087798 -0.618995 0.780472 +v -0.126043 -0.025787 0.013218 +vn 0.087309 -0.619284 0.780298 +v -0.126043 -0.019487 0.018218 +vn 0.088379 -0.618651 0.780679 +v -0.132143 -0.024387 0.015018 +vn -0.223692 -0.974660 0.000000 +v -0.132143 -0.024387 0.015018 +vn -0.223692 -0.974660 0.000000 +v -0.126043 -0.025787 0.005118 +vn -0.223692 -0.974660 0.000000 +v -0.126043 -0.025787 0.013218 +vn -0.223692 -0.974660 0.000000 +v -0.132143 -0.024387 0.008318 +vn -0.488030 -0.545966 -0.680990 +v -0.132143 -0.024387 0.008318 +vn -0.488030 -0.545966 -0.680990 +v -0.126043 -0.019487 0.000018 +vn -0.483357 -0.550815 -0.680418 +v -0.126043 -0.025787 0.005118 +vn -0.493566 -0.540160 -0.681631 +v -0.132143 -0.019087 0.004118 +vn -0.540345 0.187958 -0.820182 +v -0.132143 -0.019087 0.004118 +vn -0.540345 0.187958 -0.820182 +v -0.126043 -0.011587 0.001818 +vn -0.539512 0.187049 -0.820938 +v -0.126043 -0.019487 0.000018 +vn -0.541354 0.189061 -0.819263 +v -0.132143 -0.012587 0.005618 +vn -0.384053 0.831995 -0.400359 +v -0.132143 -0.012587 0.005618 +vn -0.384053 0.831995 -0.400359 +v -0.126043 -0.008087 0.009118 +vn -0.384989 0.832212 -0.399006 +v -0.126043 -0.011587 0.001818 +vn -0.382913 0.831728 -0.402002 +v -0.132143 -0.009687 0.011618 +vn 0.076242 0.874237 0.479475 +v -0.139243 -0.010487 0.015018 +vn 0.076242 0.874237 0.479475 +v -0.135843 -0.013087 0.019218 +vn 0.076242 0.874237 0.479475 +v -0.132143 -0.012587 0.017718 +vn 0.103291 0.898303 0.427062 +v -0.132143 -0.012587 0.017718 +vn 0.103291 0.898303 0.427062 +v -0.132143 -0.009687 0.011618 +vn 0.103291 0.898303 0.427062 +v -0.139243 -0.010487 0.015018 +vn 0.342383 0.211136 0.915530 +v -0.135843 -0.013087 0.019218 +vn 0.342383 0.211136 0.915530 +v -0.132143 -0.019087 0.019218 +vn 0.342574 0.211253 0.915432 +v -0.132143 -0.012587 0.017718 +vn 0.342098 0.210960 0.915677 +v -0.134943 -0.018887 0.020218 +vn 0.239967 -0.599639 0.763446 +v -0.134943 -0.018887 0.020218 +vn 0.239967 -0.599639 0.763446 +v -0.132143 -0.024387 0.015018 +vn 0.229273 -0.604537 0.762869 +v -0.132143 -0.019087 0.019218 +vn 0.245979 -0.596841 0.763724 +v -0.137343 -0.023587 0.017318 +vn -0.095501 -0.994874 0.033255 +v -0.137343 -0.023587 0.017318 +vn -0.061336 -0.996701 0.053157 +v -0.141243 -0.023587 0.012818 +vn -0.095501 -0.994874 0.033255 +v -0.132143 -0.024387 0.008318 +vn -0.152057 -0.988372 0.000000 +v -0.132143 -0.024387 0.015018 +vn -0.382603 -0.594164 -0.707520 +v -0.141243 -0.023587 0.012818 +vn -0.363084 -0.616488 -0.698650 +v -0.143643 -0.018887 0.009918 +vn -0.382603 -0.594164 -0.707520 +v -0.132143 -0.019087 0.004118 +vn -0.404399 -0.568030 -0.716800 +v -0.132143 -0.024387 0.008318 +vn -0.441128 0.209639 -0.872616 +v -0.143643 -0.018887 0.009918 +vn -0.441128 0.209639 -0.872616 +v -0.132143 -0.012587 0.005618 +vn -0.438218 0.202119 -0.875850 +v -0.132143 -0.019087 0.004118 +vn -0.444618 0.218751 -0.868598 +v -0.142743 -0.013087 0.010918 +vn -0.266136 0.900514 -0.343869 +v -0.142743 -0.013087 0.010918 +vn -0.266136 0.900514 -0.343869 +v -0.139243 -0.010487 0.015018 +vn -0.266136 0.900514 -0.343869 +v -0.132143 -0.009687 0.011618 +vn -0.251682 0.871367 -0.421160 +v -0.132143 -0.009687 0.011618 +vn -0.251682 0.871367 -0.421160 +v -0.132143 -0.012587 0.005618 +vn -0.251682 0.871367 -0.421160 +v -0.142743 -0.013087 0.010918 +vn 0.351224 0.872192 0.340474 +v -0.142743 -0.011987 0.023518 +vn 0.401781 0.803563 0.439156 +v -0.138543 -0.014087 0.023518 +vn 0.351224 0.872192 0.340474 +v -0.135843 -0.013087 0.019218 +vn 0.325773 0.898971 0.292784 +v -0.139243 -0.010487 0.015018 +vn 0.794476 0.202152 0.572662 +v -0.138543 -0.014087 0.023518 +vn 0.781176 0.173595 0.599691 +v -0.137543 -0.018587 0.023518 +vn 0.794476 0.202152 0.572662 +v -0.134943 -0.018887 0.020218 +vn 0.802235 0.220162 0.554930 +v -0.135843 -0.013087 0.019218 +vn 0.651758 -0.579959 0.488732 +v -0.137543 -0.018587 0.023518 +vn 0.697467 -0.546664 0.463356 +v -0.140443 -0.022287 0.023518 +vn 0.651758 -0.579959 0.488732 +v -0.137343 -0.023587 0.017318 +vn 0.587584 -0.620497 0.519354 +v -0.134943 -0.018887 0.020218 +vn -0.066296 -0.989911 0.125226 +v -0.140443 -0.022287 0.023518 +vn 0.000000 -0.992700 0.120608 +v -0.145043 -0.022287 0.023518 +vn -0.066296 -0.989911 0.125226 +v -0.141243 -0.023587 0.012818 +vn -0.150355 -0.980007 0.130308 +v -0.137343 -0.023587 0.017318 +vn -0.787256 -0.574265 -0.224607 +v -0.145043 -0.022287 0.023518 +vn -0.766142 -0.600491 -0.228990 +v -0.147943 -0.018587 0.023518 +vn -0.787256 -0.574265 -0.224607 +v -0.143643 -0.018887 0.009918 +vn -0.807077 -0.547907 -0.220058 +v -0.141243 -0.023587 0.012818 +vn -0.933336 0.201046 -0.297428 +v -0.147943 -0.018587 0.023518 +vn -0.933336 0.201046 -0.297428 +v -0.142743 -0.013087 0.010918 +vn -0.933630 0.196516 -0.299527 +v -0.143643 -0.018887 0.009918 +vn -0.932891 0.207310 -0.294510 +v -0.146943 -0.014087 0.023518 +vn -0.489776 0.868545 -0.075825 +v -0.146943 -0.014087 0.023518 +vn -0.447059 0.894118 -0.026298 +v -0.142743 -0.011987 0.023518 +vn -0.489776 0.868545 -0.075825 +v -0.139243 -0.010487 0.015018 +vn -0.512446 0.852501 -0.103156 +v -0.142743 -0.013087 0.010918 +vn 0.436470 0.897883 0.057437 +v -0.142743 -0.013587 0.047618 +vn 0.436470 0.897883 0.057437 +v -0.138543 -0.014087 0.023518 +vn 0.446426 0.892855 0.059277 +v -0.142743 -0.011987 0.023518 +vn 0.422249 0.904821 0.054815 +v -0.139743 -0.014987 0.047618 +vn 0.975459 0.212600 0.057289 +v -0.139743 -0.014987 0.047618 +vn 0.975459 0.212600 0.057289 +v -0.137543 -0.018587 0.023518 +vn 0.974621 0.216583 0.056617 +v -0.138543 -0.014087 0.023518 +vn 0.976576 0.207152 0.058204 +v -0.139043 -0.018287 0.047618 +vn 0.788115 -0.612979 0.055957 +v -0.139043 -0.018287 0.047618 +vn 0.788115 -0.612979 0.055957 +v -0.140443 -0.022287 0.023518 +vn 0.785795 -0.615894 0.056575 +v -0.137543 -0.018587 0.023518 +vn 0.791421 -0.608786 0.055069 +v -0.141043 -0.020887 0.047618 +vn 0.000000 -0.998317 0.057993 +v -0.141043 -0.020887 0.047618 +vn 0.000000 -0.998317 0.057993 +v -0.145043 -0.022287 0.023518 +vn 0.000000 -0.998317 0.057993 +v -0.140443 -0.022287 0.023518 +vn 0.000000 -0.998317 0.057993 +v -0.144443 -0.020887 0.047618 +vn -0.788116 -0.612978 0.055957 +v -0.144443 -0.020887 0.047618 +vn -0.788116 -0.612978 0.055957 +v -0.147943 -0.018587 0.023518 +vn -0.785849 -0.615937 0.055345 +v -0.145043 -0.022287 0.023518 +vn -0.791345 -0.608723 0.056832 +v -0.146443 -0.018287 0.047618 +vn -0.975459 0.212600 0.057289 +v -0.146443 -0.018287 0.047618 +vn -0.975459 0.212600 0.057289 +v -0.146943 -0.014087 0.023518 +vn -0.974546 0.216566 0.057961 +v -0.147943 -0.018587 0.023518 +vn -0.976679 0.207173 0.056368 +v -0.145743 -0.014987 0.047618 +vn -0.436472 0.897883 0.057437 +v -0.145743 -0.014987 0.047618 +vn -0.436472 0.897883 0.057437 +v -0.142743 -0.011987 0.023518 +vn -0.446523 0.893044 0.055584 +v -0.146943 -0.014087 0.023518 +vn -0.422123 0.904547 0.060053 +v -0.142743 -0.013587 0.047618 +vn 0.422885 0.906183 0.000000 +v -0.142743 -0.013587 0.062518 +vn 0.422885 0.906183 0.000000 +v -0.139743 -0.014987 0.047618 +vn 0.422885 0.906183 0.000000 +v -0.142743 -0.013587 0.047618 +vn 0.422885 0.906183 0.000000 +v -0.139743 -0.014987 0.062518 +vn 0.978234 0.207503 0.000000 +v -0.139743 -0.014987 0.062518 +vn 0.978234 0.207503 0.000000 +v -0.139043 -0.018287 0.047618 +vn 0.978234 0.207503 0.000000 +v -0.139743 -0.014987 0.047618 +vn 0.978234 0.207503 0.000000 +v -0.139043 -0.018287 0.062518 +vn 0.792624 -0.609711 0.000000 +v -0.139043 -0.018287 0.062518 +vn 0.792624 -0.609711 0.000000 +v -0.141043 -0.020887 0.047618 +vn 0.792624 -0.609711 0.000000 +v -0.139043 -0.018287 0.047618 +vn 0.792624 -0.609711 0.000000 +v -0.141043 -0.020887 0.062518 +vn 0.000000 -1.000000 0.000000 +v -0.141043 -0.020887 0.062518 +vn 0.000000 -1.000000 0.000000 +v -0.144443 -0.020887 0.047618 +vn 0.000000 -1.000000 0.000000 +v -0.141043 -0.020887 0.047618 +vn 0.000000 -1.000000 0.000000 +v -0.144443 -0.020887 0.062518 +vn -0.792626 -0.609708 0.000000 +v -0.144443 -0.020887 0.062518 +vn -0.792626 -0.609708 0.000000 +v -0.146443 -0.018287 0.047618 +vn -0.792626 -0.609708 0.000000 +v -0.144443 -0.020887 0.047618 +vn -0.792626 -0.609708 0.000000 +v -0.146443 -0.018287 0.062518 +vn -0.978234 0.207503 0.000000 +v -0.146443 -0.018287 0.062518 +vn -0.978234 0.207503 0.000000 +v -0.145743 -0.014987 0.047618 +vn -0.978234 0.207503 0.000000 +v -0.146443 -0.018287 0.047618 +vn -0.978234 0.207503 0.000000 +v -0.145743 -0.014987 0.062518 +vn -0.422887 0.906183 0.000000 +v -0.145743 -0.014987 0.062518 +vn -0.422887 0.906183 0.000000 +v -0.142743 -0.013587 0.047618 +vn -0.422887 0.906183 0.000000 +v -0.145743 -0.014987 0.047618 +vn -0.422887 0.906183 0.000000 +v -0.142743 -0.013587 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.144443 -0.020887 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.145743 -0.014987 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.146443 -0.018287 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.141043 -0.020887 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.142743 -0.013587 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.139043 -0.018287 0.062518 +vn 0.000000 0.000000 1.000000 +v -0.139743 -0.014987 0.062518 +vn 0.367623 -0.641635 0.673170 +v -0.000143 0.062013 0.059818 +vn 0.491384 -0.856509 0.157905 +v -0.013443 0.046313 0.045218 +vn 0.491296 -0.856357 -0.158998 +v 0.003257 0.055913 0.045218 +vn 0.243686 -0.426451 0.871066 +v -0.016943 0.052413 0.059818 +vn 0.110124 -0.192717 0.975055 +v -0.008043 0.075713 0.063418 +vn 0.110124 -0.192717 0.975055 +v -0.024843 0.066113 0.063418 +vn -0.407121 0.712461 0.571535 +v -0.014343 0.086713 0.053318 +vn -0.309168 0.541044 0.782104 +v -0.008043 0.075713 0.063418 +vn -0.475441 0.832022 0.285824 +v -0.031143 0.077113 0.053318 +vn -0.475441 0.832022 -0.285824 +v -0.014343 0.086713 0.037118 +vn -0.407121 0.712461 -0.571535 +v -0.031143 0.077113 0.037118 +vn -0.309168 0.541044 -0.782104 +v -0.008043 0.075713 0.027018 +vn -0.309168 0.541044 -0.782104 +v -0.024843 0.066113 0.027018 +vn 0.243924 -0.426866 -0.870796 +v -0.000143 0.062013 0.030618 +vn 0.110124 -0.192717 -0.975055 +v -0.024843 0.066113 0.027018 +vn 0.110124 -0.192717 -0.975055 +v -0.008043 0.075713 0.027018 +vn 0.367623 -0.641635 -0.673170 +v -0.016943 0.052413 0.030618 +vn -0.866623 -0.498964 0.000000 +v -0.016943 0.052413 0.059818 +vn -0.866469 -0.499231 0.000000 +v -0.016943 0.052413 0.030618 +vn -0.867367 -0.497669 0.000000 +v -0.013443 0.046313 0.045218 +vn -0.866743 -0.498755 0.000000 +v -0.024843 0.066113 0.063418 +vn -0.867079 -0.498171 0.000000 +v -0.024843 0.066113 0.027018 +vn -0.867757 -0.496988 0.000000 +v -0.031143 0.077113 0.053318 +vn -0.867757 -0.496988 0.000000 +v -0.031143 0.077113 0.037118 +vn 0.868857 0.495062 0.000876 +v -0.012343 0.072513 0.029918 +vn 0.868476 0.495730 0.001313 +v -0.002843 0.055813 0.045218 +vn 0.871119 0.491048 -0.004911 +v -0.005843 0.061013 0.033018 +vn 0.868202 0.496207 0.001749 +v -0.017643 0.081713 0.038418 +vn 0.868574 0.495560 -0.000468 +v -0.005843 0.061013 0.057518 +vn 0.869037 0.494741 -0.002456 +v -0.017643 0.081713 0.052018 +vn 0.869642 0.493618 -0.007979 +v -0.012343 0.072513 0.060518 +vn 0.872097 0.489301 0.005660 +v 0.001857 0.058513 0.045218 +vn 0.867294 0.497766 -0.005500 +v -0.001143 0.063613 0.057518 +vn 0.872589 0.488449 -0.002439 +v 0.003257 0.055913 0.045218 +vn 0.867290 0.497773 0.005434 +v -0.000143 0.062013 0.030618 +vn 0.859674 0.510532 0.017844 +v -0.001143 0.063613 0.033018 +vn 0.860390 0.509251 -0.019822 +v -0.000143 0.062013 0.059818 +vn 0.866352 0.499398 -0.005947 +v -0.008043 0.075713 0.063418 +vn 0.865533 0.500736 0.010754 +v -0.007743 0.075213 0.060518 +vn 0.860291 0.509729 0.008707 +v -0.014343 0.086713 0.053318 +vn 0.856142 0.516680 0.007873 +v -0.012943 0.084413 0.052018 +vn 0.858909 0.512085 -0.006708 +v -0.014343 0.086713 0.037118 +vn 0.857269 0.514716 -0.012561 +v -0.012943 0.084413 0.038418 +vn 0.865031 0.501717 -0.001180 +v -0.007743 0.075213 0.029918 +vn 0.866530 0.499111 -0.003587 +v -0.008043 0.075713 0.027018 +vn -0.441994 0.783914 -0.436027 +v -0.005843 0.061013 0.057518 +vn -0.441994 0.783914 -0.436027 +v 0.001857 0.058513 0.045218 +vn -0.447651 0.779244 -0.438620 +v -0.002843 0.055813 0.045218 +vn -0.436242 0.788592 -0.433377 +v -0.001143 0.063613 0.057518 +vn -0.109119 0.191473 -0.975413 +v -0.012343 0.072513 0.060518 +vn -0.109119 0.191473 -0.975413 +v -0.001143 0.063613 0.057518 +vn -0.107206 0.193796 -0.975167 +v -0.005843 0.061013 0.057518 +vn -0.111025 0.189154 -0.975651 +v -0.007743 0.075213 0.060518 +vn 0.314272 -0.541245 -0.779927 +v -0.017643 0.081713 0.052018 +vn 0.314272 -0.541245 -0.779927 +v -0.007743 0.075213 0.060518 +vn 0.316365 -0.538991 -0.780642 +v -0.012343 0.072513 0.060518 +vn 0.312203 -0.543464 -0.779215 +v -0.012943 0.084413 0.052018 +vn 0.498125 -0.867105 0.000000 +v -0.017643 0.081713 0.038418 +vn 0.498125 -0.867105 0.000000 +v -0.012943 0.084413 0.052018 +vn 0.498125 -0.867105 0.000000 +v -0.017643 0.081713 0.052018 +vn 0.498125 -0.867105 0.000000 +v -0.012943 0.084413 0.038418 +vn 0.314272 -0.541245 0.779927 +v -0.012343 0.072513 0.029918 +vn 0.314272 -0.541245 0.779927 +v -0.012943 0.084413 0.038418 +vn 0.311311 -0.541912 0.780652 +v -0.017643 0.081713 0.038418 +vn 0.317286 -0.540561 0.779182 +v -0.007743 0.075213 0.029918 +vn -0.112571 0.197530 0.973812 +v -0.005843 0.061013 0.033018 +vn -0.112571 0.197530 0.973812 +v -0.007743 0.075213 0.029918 +vn -0.115665 0.197058 0.973545 +v -0.012343 0.072513 0.029918 +vn -0.109528 0.197993 0.974065 +v -0.001143 0.063613 0.033018 +vn -0.441304 0.782690 0.438915 +v -0.002843 0.055813 0.045218 +vn -0.441304 0.782690 0.438915 +v -0.001143 0.063613 0.033018 +vn -0.434339 0.785152 0.441460 +v -0.005843 0.061013 0.033018 +vn -0.448199 0.780197 0.436361 +v 0.001857 0.058513 0.045218 +vn 0.000000 0.000000 -1.000000 +v -0.112043 0.052113 0.020518 +vn 0.000000 0.000000 -1.000000 +v -0.061843 0.064613 0.020518 +vn 0.000000 0.000000 -1.000000 +v -0.061843 0.052113 0.020518 +vn 0.000000 0.000000 -1.000000 +v -0.112043 0.064613 0.020518 +vn 0.000000 0.000000 1.000000 +v -0.112043 0.052113 0.052118 +vn 0.000000 0.000000 1.000000 +v -0.061843 0.064613 0.052118 +vn 0.000000 0.000000 1.000000 +v -0.112043 0.064613 0.052118 +vn 0.000000 0.000000 1.000000 +v -0.061843 0.052113 0.052118 +vn 0.000000 -1.000000 0.000000 +v -0.015843 0.052113 0.047818 +vn 0.000000 -1.000000 0.000000 +v -0.112043 0.052113 0.020518 +vn 0.000000 -1.000000 0.000000 +v -0.061843 0.052113 0.020518 +vn 0.000000 -1.000000 0.000000 +v -0.061843 0.052113 0.052118 +vn 0.000000 -1.000000 0.000000 +v -0.112043 0.052113 0.052118 +vn 0.000000 -1.000000 0.000000 +v -0.015843 0.052113 0.059618 +vn -1.000000 0.000000 0.000000 +v -0.112043 0.064613 0.052118 +vn -1.000000 0.000000 0.000000 +v -0.112043 0.052113 0.020518 +vn -1.000000 0.000000 0.000000 +v -0.112043 0.052113 0.052118 +vn -1.000000 0.000000 0.000000 +v -0.112043 0.064613 0.020518 +vn 0.000000 1.000000 0.000000 +v -0.112043 0.064613 0.020518 +vn 0.000000 1.000000 0.000000 +v -0.023343 0.064613 0.047818 +vn 0.000000 1.000000 0.000000 +v -0.061843 0.064613 0.020518 +vn 0.000000 1.000000 0.000000 +v -0.061843 0.064613 0.052118 +vn 0.000000 1.000000 0.000000 +v -0.023343 0.064613 0.059618 +vn 0.000000 1.000000 0.000000 +v -0.112043 0.064613 0.052118 +vn 0.535662 0.160699 -0.829001 +v -0.015843 0.052113 0.047818 +vn 0.510366 0.000000 -0.859957 +v -0.061843 0.052113 0.020518 +vn 0.535662 0.160699 -0.829001 +v -0.061843 0.064613 0.020518 +vn 0.546454 0.327873 -0.770641 +v -0.023343 0.064613 0.047818 +vn -0.174543 -0.052363 0.983256 +v -0.023343 0.064613 0.059618 +vn -0.191211 0.000000 0.981549 +v -0.061843 0.064613 0.052118 +vn -0.174543 -0.052363 0.983256 +v -0.061843 0.052113 0.052118 +vn -0.160174 -0.096104 0.982399 +v -0.015843 0.052113 0.059618 +vn 0.367623 0.641635 0.673170 +v -0.000143 -0.062187 0.059818 +vn 0.491384 0.856509 0.157905 +v -0.013443 -0.046487 0.045218 +vn 0.243686 0.426451 0.871066 +v -0.016943 -0.052587 0.059818 +vn 0.491296 0.856357 -0.158998 +v 0.003257 -0.056087 0.045218 +vn 0.110124 0.192717 0.975055 +v -0.008043 -0.075887 0.063418 +vn 0.110124 0.192717 0.975055 +v -0.024843 -0.066287 0.063418 +vn -0.407121 -0.712461 0.571535 +v -0.014343 -0.086887 0.053318 +vn -0.309168 -0.541044 0.782104 +v -0.024843 -0.066287 0.063418 +vn -0.475441 -0.832022 0.285824 +v -0.031143 -0.077287 0.053318 +vn -0.309168 -0.541044 0.782104 +v -0.008043 -0.075887 0.063418 +vn -0.475441 -0.832022 -0.285824 +v -0.014343 -0.086887 0.037118 +vn -0.407121 -0.712461 -0.571535 +v -0.031143 -0.077287 0.037118 +vn -0.309168 -0.541044 -0.782104 +v -0.008043 -0.075887 0.027018 +vn -0.309168 -0.541044 -0.782104 +v -0.024843 -0.066287 0.027018 +vn 0.243924 0.426866 -0.870796 +v -0.000143 -0.062187 0.030618 +vn 0.110124 0.192717 -0.975055 +v -0.024843 -0.066287 0.027018 +vn 0.367623 0.641635 -0.673170 +v -0.016943 -0.052587 0.030618 +vn 0.110124 0.192717 -0.975055 +v -0.008043 -0.075887 0.027018 +vn -0.866872 0.498530 0.000630 +v -0.024843 -0.066287 0.027018 +vn -0.866960 0.498377 0.000475 +v -0.013443 -0.046487 0.045218 +vn -0.866158 0.499770 -0.001167 +v -0.016943 -0.052587 0.030618 +vn -0.867065 0.498195 0.000554 +v -0.031143 -0.077287 0.037118 +vn -0.866944 0.498405 -0.000338 +v -0.016943 -0.052587 0.059818 +vn -0.866843 0.498580 -0.000885 +v -0.031143 -0.077287 0.053318 +vn -0.866614 0.498971 -0.002873 +v -0.024843 -0.066287 0.063418 +vn 0.869202 -0.494456 0.000000 +v -0.005843 -0.061087 0.057518 +vn 0.870679 -0.491851 0.000000 +v -0.005843 -0.061087 0.033018 +vn 0.861934 -0.507020 0.000000 +v -0.002843 -0.055987 0.045218 +vn 0.870585 -0.492018 0.000000 +v -0.012343 -0.072687 0.060518 +vn 0.869244 -0.494383 0.000000 +v -0.012343 -0.072687 0.029918 +vn 0.866499 -0.499179 0.000000 +v -0.017643 -0.081887 0.052018 +vn 0.866499 -0.499179 0.000000 +v -0.017643 -0.081887 0.038418 +vn 0.872097 -0.489300 0.005660 +v 0.001857 -0.058687 0.045218 +vn 0.866554 -0.499012 0.008477 +v -0.000143 -0.062187 0.030618 +vn 0.872589 -0.488448 -0.002439 +v 0.003257 -0.056087 0.045218 +vn 0.866347 -0.499345 -0.009843 +v -0.001143 -0.063787 0.057518 +vn 0.860959 -0.508430 0.015802 +v -0.001143 -0.063787 0.033018 +vn 0.867072 -0.497911 0.016445 +v -0.008043 -0.075887 0.027018 +vn 0.866746 -0.498750 -0.000600 +v -0.007743 -0.075287 0.029918 +vn 0.862696 -0.505701 -0.004682 +v -0.014343 -0.086887 0.037118 +vn 0.856430 -0.516183 -0.009062 +v -0.012943 -0.084587 0.038418 +vn 0.856014 -0.516901 0.007344 +v -0.014343 -0.086887 0.053318 +vn 0.863197 -0.504843 0.004963 +v -0.012943 -0.084587 0.052018 +vn 0.865865 -0.500240 -0.006193 +v -0.008043 -0.075887 0.063418 +vn 0.871028 -0.491099 -0.011501 +v -0.007743 -0.075287 0.060518 +vn 0.860390 -0.509251 -0.019822 +v -0.000143 -0.062187 0.059818 +vn -0.448891 -0.781403 -0.433482 +v -0.005843 -0.061087 0.057518 +vn -0.448891 -0.781403 -0.433482 +v 0.001857 -0.058687 0.045218 +vn -0.448891 -0.781403 -0.433482 +v -0.001143 -0.063787 0.057518 +vn -0.448891 -0.781403 -0.433482 +v -0.002843 -0.055987 0.045218 +vn -0.109119 -0.191473 -0.975413 +v -0.012343 -0.072687 0.060518 +vn -0.109119 -0.191473 -0.975413 +v -0.001143 -0.063787 0.057518 +vn -0.108588 -0.192118 -0.975346 +v -0.007743 -0.075287 0.060518 +vn -0.109635 -0.190846 -0.975478 +v -0.005843 -0.061087 0.057518 +vn 0.309112 0.542403 -0.781184 +v -0.017643 -0.081887 0.052018 +vn 0.309112 0.542403 -0.781184 +v -0.007743 -0.075287 0.060518 +vn 0.310653 0.540766 -0.781708 +v -0.012943 -0.084587 0.052018 +vn 0.307525 0.544083 -0.780642 +v -0.012343 -0.072687 0.060518 +vn 0.498125 0.867105 0.000000 +v -0.017643 -0.081887 0.038418 +vn 0.498125 0.867105 0.000000 +v -0.012943 -0.084587 0.052018 +vn 0.498125 0.867105 0.000000 +v -0.012943 -0.084587 0.038418 +vn 0.498125 0.867105 0.000000 +v -0.017643 -0.081887 0.052018 +vn 0.309111 0.542403 0.781184 +v -0.012343 -0.072687 0.029918 +vn 0.309111 0.542403 0.781184 +v -0.012943 -0.084587 0.038418 +vn 0.306858 0.542903 0.781725 +v -0.007743 -0.075287 0.029918 +vn 0.311311 0.541912 0.780652 +v -0.017643 -0.081887 0.038418 +vn -0.112571 -0.197530 0.973812 +v -0.005843 -0.061087 0.033018 +vn -0.112571 -0.197530 0.973812 +v -0.007743 -0.075287 0.029918 +vn -0.113402 -0.197404 0.973741 +v -0.001143 -0.063787 0.033018 +vn -0.111721 -0.197660 0.973884 +v -0.012343 -0.072687 0.029918 +vn -0.448198 -0.780197 0.436361 +v -0.002843 -0.055987 0.045218 +vn -0.448198 -0.780197 0.436361 +v -0.001143 -0.063787 0.033018 +vn -0.448199 -0.780197 0.436361 +v 0.001857 -0.058687 0.045218 +vn -0.448198 -0.780197 0.436361 +v -0.005843 -0.061087 0.033018 +vn 0.000000 0.000000 -1.000000 +v -0.112043 -0.052287 0.020518 +vn 0.000000 0.000000 -1.000000 +v -0.061843 -0.064787 0.020518 +vn 0.000000 0.000000 -1.000000 +v -0.112043 -0.064787 0.020518 +vn 0.000000 0.000000 -1.000000 +v -0.061843 -0.052287 0.020518 +vn 0.000000 0.000000 1.000000 +v -0.112043 -0.052287 0.052118 +vn 0.000000 0.000000 1.000000 +v -0.061843 -0.064787 0.052118 +vn 0.000000 0.000000 1.000000 +v -0.061843 -0.052287 0.052118 +vn 0.000000 0.000000 1.000000 +v -0.112043 -0.064787 0.052118 +vn -1.000000 0.000000 0.000000 +v -0.112043 -0.064787 0.052118 +vn -1.000000 0.000000 0.000000 +v -0.112043 -0.052287 0.020518 +vn -1.000000 0.000000 0.000000 +v -0.112043 -0.064787 0.020518 +vn -1.000000 0.000000 0.000000 +v -0.112043 -0.052287 0.052118 +vn 0.535662 -0.160699 -0.829001 +v -0.015843 -0.052287 0.047818 +vn 0.546454 -0.327873 -0.770641 +v -0.023343 -0.064787 0.047818 +vn 0.535662 -0.160699 -0.829001 +v -0.061843 -0.064787 0.020518 +vn 0.510366 0.000000 -0.859957 +v -0.061843 -0.052287 0.020518 +vn -0.174543 0.052363 0.983256 +v -0.023343 -0.064787 0.059618 +vn -0.160174 0.096104 0.982399 +v -0.015843 -0.052287 0.059618 +vn -0.174543 0.052363 0.983256 +v -0.061843 -0.052287 0.052118 +vn -0.191211 0.000000 0.981549 +v -0.061843 -0.064787 0.052118 +vn 0.000000 1.000000 0.000000 +v -0.112043 -0.052287 0.020518 +vn 0.000000 1.000000 0.000000 +v -0.015843 -0.052287 0.047818 +vn 0.000000 1.000000 0.000000 +v -0.061843 -0.052287 0.020518 +vn 0.000000 1.000000 0.000000 +v -0.061843 -0.052287 0.052118 +vn 0.000000 1.000000 0.000000 +v -0.015843 -0.052287 0.059618 +vn 0.000000 1.000000 0.000000 +v -0.112043 -0.052287 0.052118 +vn 0.000000 -1.000000 0.000000 +v -0.023343 -0.064787 0.047818 +vn 0.000000 -1.000000 0.000000 +v -0.112043 -0.064787 0.020518 +vn 0.000000 -1.000000 0.000000 +v -0.061843 -0.064787 0.020518 +vn 0.000000 -1.000000 0.000000 +v -0.061843 -0.064787 0.052118 +vn 0.000000 -1.000000 0.000000 +v -0.112043 -0.064787 0.052118 +vn 0.000000 -1.000000 0.000000 +v -0.023343 -0.064787 0.059618 +vn 0.000000 0.313683 -0.949528 +v -0.041643 0.041313 0.059418 +vn 0.000000 0.313683 -0.949528 +v 0.017057 -0.014687 0.040918 +vn 0.000000 0.313683 -0.949528 +v -0.041643 -0.014687 0.040918 +vn 0.000000 0.313683 -0.949528 +v 0.017057 0.041313 0.059418 +vn 0.000000 -0.315211 0.949022 +v -0.041643 0.028613 0.097818 +vn 0.000000 -0.315211 0.949022 +v 0.017057 -0.027387 0.079218 +vn 0.000000 -0.315211 0.949022 +v 0.017057 0.028613 0.097818 +vn 0.000000 -0.315211 0.949022 +v -0.041643 -0.027387 0.079218 +vn 1.000000 0.000000 0.000000 +v 0.017057 0.028613 0.097818 +vn 1.000000 0.000000 0.000000 +v 0.017057 -0.014687 0.040918 +vn 1.000000 0.000000 0.000000 +v 0.017057 0.041313 0.059418 +vn 1.000000 0.000000 0.000000 +v 0.017057 -0.027387 0.079218 +vn 0.000000 0.949422 0.314002 +v -0.041643 0.028613 0.097818 +vn 0.000000 0.949422 0.314002 +v 0.017057 0.041313 0.059418 +vn 0.000000 0.949422 0.314002 +v -0.041643 0.041313 0.059418 +vn 0.000000 0.949422 0.314002 +v 0.017057 0.028613 0.097818 +vn -1.000000 0.000000 0.000000 +v -0.041643 -0.027387 0.079218 +vn -1.000000 0.000000 0.000000 +v -0.041643 0.041313 0.059418 +vn -1.000000 0.000000 0.000000 +v -0.041643 -0.014687 0.040918 +vn -1.000000 0.000000 0.000000 +v -0.041643 0.028613 0.097818 +vn 0.000000 -0.949178 -0.314740 +v 0.017057 -0.027387 0.079218 +vn 0.000000 -0.949178 -0.314740 +v -0.041643 -0.014687 0.040918 +vn 0.000000 -0.949178 -0.314740 +v 0.017057 -0.014687 0.040918 +vn 0.000000 -0.949178 -0.314740 +v -0.041643 -0.027387 0.079218 +vn -0.000000 0.315657 -0.948873 +v 0.003657 -0.036187 0.105818 +vn -0.000000 0.315566 -0.948904 +v 0.017257 0.006813 0.120118 +vn 0.000997 0.315282 -0.948998 +v 0.017257 -0.023287 0.110118 +vn -0.000095 0.315718 -0.948853 +v 0.003657 0.019713 0.124418 +vn -0.000095 0.315718 -0.948853 +v -0.027843 -0.036187 0.105818 +vn 0.000000 0.315657 -0.948873 +v -0.027843 0.019713 0.124418 +vn 0.000000 0.315566 -0.948904 +v -0.041543 -0.023287 0.110118 +vn 0.000990 0.315282 -0.948998 +v -0.041543 0.006813 0.120118 +vn 0.000000 -0.313944 0.949441 +v 0.017257 -0.029087 0.127718 +vn 0.000000 -0.316228 0.948683 +v -0.027843 -0.041987 0.123418 +vn 0.000000 -0.316228 0.948683 +v 0.003657 -0.041987 0.123418 +vn 0.000000 -0.313108 0.949718 +v -0.041543 -0.029087 0.127718 +vn 0.000000 -0.313108 0.949718 +v 0.017257 0.001013 0.137618 +vn 0.000000 -0.313944 0.949441 +v -0.041543 0.001013 0.137618 +vn 0.000000 -0.316228 0.948683 +v 0.003657 0.013913 0.141918 +vn 0.000000 -0.316228 0.948683 +v -0.027843 0.013913 0.141918 +vn 1.000000 0.000000 0.000000 +v 0.017257 0.001013 0.137618 +vn 1.000000 0.000000 0.000000 +v 0.017257 -0.023287 0.110118 +vn 1.000000 0.000000 0.000000 +v 0.017257 0.006813 0.120118 +vn 1.000000 0.000000 0.000000 +v 0.017257 -0.029087 0.127718 +vn 0.000000 0.949224 0.314600 +v -0.027843 0.013913 0.141918 +vn 0.000000 0.949224 0.314600 +v 0.003657 0.019713 0.124418 +vn 0.000000 0.949224 0.314600 +v -0.027843 0.019713 0.124418 +vn 0.000000 0.949224 0.314600 +v 0.003657 0.013913 0.141918 +vn -1.000000 0.000000 0.000000 +v -0.041543 -0.029087 0.127718 +vn -1.000000 0.000000 0.000000 +v -0.041543 0.006813 0.120118 +vn -1.000000 0.000000 0.000000 +v -0.041543 -0.023287 0.110118 +vn -1.000000 0.000000 0.000000 +v -0.041543 0.001013 0.137618 +vn 0.000000 -0.949757 -0.312988 +v 0.003657 -0.041987 0.123418 +vn 0.000000 -0.949757 -0.312988 +v -0.027843 -0.036187 0.105818 +vn 0.000000 -0.949757 -0.312988 +v 0.003657 -0.036187 0.105818 +vn 0.000000 -0.949757 -0.312988 +v -0.027843 -0.041987 0.123418 +vn 0.707049 0.671258 0.222474 +v 0.003657 0.013913 0.141918 +vn 0.707049 0.671258 0.222474 +v 0.017257 0.006813 0.120118 +vn 0.707049 0.671258 0.222474 +v 0.003657 0.019713 0.124418 +vn 0.707049 0.671258 0.222474 +v 0.017257 0.001013 0.137618 +vn 0.707047 -0.671636 -0.221335 +v 0.003657 -0.036187 0.105818 +vn 0.707047 -0.671636 -0.221335 +v 0.017257 -0.029087 0.127718 +vn 0.707047 -0.671636 -0.221335 +v 0.003657 -0.041987 0.123418 +vn 0.707047 -0.671636 -0.221335 +v 0.017257 -0.023287 0.110118 +vn -0.704454 0.673712 0.223287 +v -0.041543 0.001013 0.137618 +vn -0.704454 0.673712 0.223287 +v -0.027843 0.019713 0.124418 +vn -0.704454 0.673712 0.223287 +v -0.041543 0.006813 0.120118 +vn -0.704454 0.673712 0.223287 +v -0.027843 0.013913 0.141918 +vn -0.704452 -0.674091 -0.222144 +v -0.027843 -0.041987 0.123418 +vn -0.704452 -0.674091 -0.222144 +v -0.041543 -0.023287 0.110118 +vn -0.704452 -0.674091 -0.222144 +v -0.027843 -0.036187 0.105818 +vn -0.704452 -0.674091 -0.222144 +v -0.041543 -0.029087 0.127718 +vn -0.756407 0.621289 0.204571 +v -0.032743 0.001713 0.122018 +vn -0.189550 0.932616 0.307081 +v -0.012343 0.023713 0.092918 +vn -0.944934 0.310844 0.102351 +v -0.032743 0.012513 0.089218 +vn 0.189849 0.932561 0.307063 +v -0.012343 0.012913 0.125718 +vn -1.000000 0.000000 0.000000 +v -0.032743 -0.020687 0.114618 +vn -1.000000 0.000000 0.000000 +v -0.032743 -0.009787 0.081818 +vn -0.189661 -0.932313 -0.307930 +v -0.012343 -0.031787 0.110918 +vn -0.499041 -0.822733 -0.272154 +v -0.032743 -0.009787 0.081818 +vn 0.188487 -0.932529 -0.307998 +v -0.012343 -0.020987 0.078118 +vn -0.497526 -0.823185 -0.273558 +v -0.032743 -0.020687 0.114618 +vn 0.757418 -0.619895 -0.205057 +v 0.007957 -0.020687 0.114618 +vn 0.945356 -0.309402 -0.102819 +v 0.007957 -0.009787 0.081818 +vn 0.945429 0.309482 0.101903 +v 0.007957 0.001713 0.122018 +vn 0.757344 0.620258 0.204231 +v 0.007957 0.012513 0.089218 +vn 0.000000 0.951114 -0.308839 +v -0.071643 0.049013 0.053718 +vn 0.000000 0.994182 -0.107711 +v -0.065743 0.060313 0.088518 +vn 0.000000 0.951114 -0.308839 +v -0.065743 0.049013 0.053718 +vn 0.000000 0.994171 0.107813 +v -0.071643 0.060313 0.088518 +vn 0.000000 0.408261 -0.912865 +v -0.071643 0.019413 0.032318 +vn 0.000000 0.204183 -0.978933 +v -0.065743 0.019413 0.032318 +vn 0.000000 0.585890 -0.810390 +v -0.071643 0.049013 0.053718 +vn 0.000000 0.000000 -1.000000 +v -0.071643 -0.017087 0.032318 +vn 0.000000 0.000000 -1.000000 +v -0.065743 -0.017087 0.032318 +vn 0.000000 -0.585890 -0.810390 +v -0.071643 -0.046687 0.053718 +vn 0.000000 -0.585890 -0.810390 +v -0.065743 -0.017087 0.032318 +vn 0.000000 -0.585890 -0.810390 +v -0.065743 -0.046687 0.053718 +vn 0.000000 -0.585890 -0.810390 +v -0.071643 -0.017087 0.032318 +vn 0.000000 -0.994284 -0.106769 +v -0.071643 -0.057887 0.088518 +vn 0.000000 -0.951915 -0.306363 +v -0.065743 -0.046687 0.053718 +vn 0.000000 -0.994273 0.106870 +v -0.065743 -0.057887 0.088518 +vn 0.000000 -0.951915 -0.306363 +v -0.071643 -0.046687 0.053718 +vn 0.000000 -0.951657 0.307163 +v -0.071643 -0.046687 0.123218 +vn 0.000000 -0.951657 0.307163 +v -0.065743 -0.046687 0.123218 +vn 0.000000 -0.409849 0.912153 +v -0.071643 -0.017087 0.144718 +vn 0.000000 -0.587684 0.809090 +v -0.065743 -0.046687 0.123218 +vn 0.000000 -0.205097 0.978742 +v -0.065743 -0.017087 0.144718 +vn 0.000000 -0.587684 0.809090 +v -0.071643 -0.046687 0.123218 +vn 0.000000 0.205097 0.978742 +v -0.071643 0.019413 0.144718 +vn 0.000000 0.409849 0.912153 +v -0.065743 0.019413 0.144718 +vn 0.000000 0.587684 0.809090 +v -0.071643 0.049013 0.123218 +vn 0.000000 0.587684 0.809090 +v -0.065743 0.049013 0.123218 +vn 0.000000 0.950853 0.309644 +v -0.071643 0.049013 0.123218 +vn -1.000000 0.000000 0.000000 +v -0.071643 0.060313 0.088518 +vn -1.000000 0.000000 0.000000 +v -0.071643 0.019413 0.144718 +vn -1.000000 0.000000 0.000000 +v -0.071643 0.049013 0.123218 +vn -1.000000 0.000000 0.000000 +v -0.071643 -0.017087 0.144718 +vn -1.000000 0.000000 0.000000 +v -0.071643 0.049013 0.053718 +vn -1.000000 0.000000 0.000000 +v -0.071643 -0.046687 0.123218 +vn -1.000000 0.000000 0.000000 +v -0.071643 0.019413 0.032318 +vn -1.000000 0.000000 0.000000 +v -0.071643 -0.057887 0.088518 +vn -1.000000 0.000000 0.000000 +v -0.071643 -0.017087 0.032318 +vn -1.000000 0.000000 0.000000 +v -0.071643 -0.046687 0.053718 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.017087 0.144718 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.049013 0.123218 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.019413 0.144718 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.060313 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.008813 0.112118 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.021313 0.103118 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.049013 0.053718 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.026013 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.019413 0.032318 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.021313 0.073918 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.017087 0.032318 +vn 1.000000 0.000000 0.000000 +v -0.065743 0.008813 0.064818 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.046687 0.053718 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.006487 0.064818 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.057887 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.018987 0.073918 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.046687 0.123218 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.023687 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.018987 0.103118 +vn 1.000000 0.000000 0.000000 +v -0.065743 -0.006487 0.112118 +vn 0.000000 0.951893 -0.306431 +v -0.043043 0.026013 0.088518 +vn 0.000000 0.951893 -0.306431 +v -0.065743 0.021313 0.073918 +vn 0.000000 0.951893 -0.306431 +v -0.065743 0.026013 0.088518 +vn 0.000000 0.951893 -0.306431 +v -0.043043 0.021313 0.073918 +vn 0.000000 0.588556 -0.808456 +v -0.043043 0.021313 0.073918 +vn 0.000000 0.588556 -0.808456 +v -0.065743 0.008813 0.064818 +vn 0.000000 0.588556 -0.808456 +v -0.065743 0.021313 0.073918 +vn 0.000000 0.588556 -0.808456 +v -0.043043 0.008813 0.064818 +vn 0.000000 0.000000 -1.000000 +v -0.043043 0.008813 0.064818 +vn 0.000000 0.000000 -1.000000 +v -0.065743 -0.006487 0.064818 +vn 0.000000 0.000000 -1.000000 +v -0.065743 0.008813 0.064818 +vn 0.000000 0.000000 -1.000000 +v -0.043043 -0.006487 0.064818 +vn 0.000000 -0.588556 -0.808456 +v -0.043043 -0.006487 0.064818 +vn 0.000000 -0.588556 -0.808456 +v -0.065743 -0.018987 0.073918 +vn 0.000000 -0.588556 -0.808456 +v -0.065743 -0.006487 0.064818 +vn 0.000000 -0.588556 -0.808456 +v -0.043043 -0.018987 0.073918 +vn 0.000000 -0.951893 -0.306431 +v -0.043043 -0.018987 0.073918 +vn 0.000000 -0.951893 -0.306431 +v -0.065743 -0.023687 0.088518 +vn 0.000000 -0.951893 -0.306431 +v -0.065743 -0.018987 0.073918 +vn 0.000000 -0.951893 -0.306431 +v -0.043043 -0.023687 0.088518 +vn 0.000000 -0.951893 0.306431 +v -0.043043 -0.023687 0.088518 +vn 0.000000 -0.951893 0.306431 +v -0.065743 -0.018987 0.103118 +vn 0.000000 -0.951893 0.306431 +v -0.065743 -0.023687 0.088518 +vn 0.000000 -0.951893 0.306431 +v -0.043043 -0.018987 0.103118 +vn 0.000000 -0.584305 0.811535 +v -0.043043 -0.018987 0.103118 +vn 0.000000 -0.584305 0.811535 +v -0.065743 -0.006487 0.112118 +vn 0.000000 -0.584305 0.811535 +v -0.065743 -0.018987 0.103118 +vn 0.000000 -0.584305 0.811535 +v -0.043043 -0.006487 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.043043 -0.006487 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.065743 0.008813 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.065743 -0.006487 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.043043 0.008813 0.112118 +vn 0.000000 0.584305 0.811535 +v -0.043043 0.008813 0.112118 +vn 0.000000 0.584305 0.811535 +v -0.065743 0.021313 0.103118 +vn 0.000000 0.584305 0.811535 +v -0.065743 0.008813 0.112118 +vn 0.000000 0.584305 0.811535 +v -0.043043 0.021313 0.103118 +vn 0.000000 0.951893 0.306431 +v -0.043043 0.021313 0.103118 +vn 0.000000 0.951893 0.306431 +v -0.065743 0.026013 0.088518 +vn 0.000000 0.951893 0.306431 +v -0.065743 0.021313 0.103118 +vn 0.000000 0.951893 0.306431 +v -0.043043 0.026013 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.026013 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.008813 0.064818 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.021313 0.073918 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.006487 0.064818 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.021313 0.103118 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.018987 0.073918 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.008813 0.112118 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.023687 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.006487 0.112118 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.018987 0.103118 +vn 0.000000 -0.992425 0.122855 +v -0.112643 -0.052587 0.108018 +vn 0.000000 -1.000000 0.000000 +v -0.070943 -0.052587 0.030518 +vn 0.000000 -0.923492 0.383619 +v -0.070943 -0.052587 0.108018 +vn 0.000000 -1.000000 0.000000 +v -0.112643 -0.052587 0.030518 +vn 0.000000 -0.339707 0.940531 +v -0.112643 -0.032087 0.118618 +vn 0.000000 -0.243324 0.969945 +v -0.070943 -0.032087 0.118618 +vn 0.000000 -0.056136 0.998423 +v -0.112643 0.001113 0.124218 +vn 0.000000 0.056136 0.998423 +v -0.070943 0.001113 0.124218 +vn 0.000000 0.243323 0.969945 +v -0.112643 0.034313 0.118618 +vn 0.000000 0.339707 0.940531 +v -0.070943 0.034313 0.118618 +vn 0.000000 0.923492 0.383619 +v -0.112643 0.054813 0.108018 +vn 0.000000 0.992425 0.122855 +v -0.070943 0.054813 0.108018 +vn 0.000000 0.821963 -0.569541 +v -0.112643 0.054813 0.030518 +vn 0.000000 0.339386 -0.940647 +v -0.070943 0.054813 0.030518 +vn 0.000000 0.000000 -1.000000 +v -0.112643 -0.052587 0.030518 +vn 0.000000 0.000000 -1.000000 +v -0.070943 -0.052587 0.030518 +vn 1.000000 0.000000 0.000000 +v -0.070943 0.054813 0.030518 +vn 1.000000 0.000000 0.000000 +v -0.070943 -0.052587 0.108018 +vn 1.000000 0.000000 0.000000 +v -0.070943 -0.052587 0.030518 +vn 1.000000 0.000000 0.000000 +v -0.070943 0.054813 0.108018 +vn 1.000000 0.000000 0.000000 +v -0.070943 -0.032087 0.118618 +vn 1.000000 0.000000 0.000000 +v -0.070943 0.034313 0.118618 +vn 1.000000 0.000000 0.000000 +v -0.070943 0.001113 0.124218 +vn -1.000000 0.000000 0.000000 +v -0.112643 -0.052587 0.108018 +vn -1.000000 0.000000 0.000000 +v -0.112643 0.054813 0.030518 +vn -1.000000 0.000000 0.000000 +v -0.112643 -0.052587 0.030518 +vn -1.000000 0.000000 0.000000 +v -0.112643 -0.032087 0.118618 +vn -1.000000 0.000000 0.000000 +v -0.112643 0.034313 0.118618 +vn -1.000000 0.000000 0.000000 +v -0.112643 0.001113 0.124218 +vn -1.000000 0.000000 0.000000 +v -0.112643 0.054813 0.108018 +vn 0.963680 0.155226 0.217316 +v 0.019957 -0.008587 0.007318 +vn 0.975363 0.083996 0.203990 +v 0.019957 -0.000087 0.003818 +vn 0.963245 0.082953 0.255494 +v 0.019225 -0.000087 0.007318 +vn 0.965060 0.214068 0.151107 +v 0.019225 -0.006987 0.008818 +vn 0.977881 -0.043825 0.204517 +v 0.019225 0.006913 0.008818 +vn 0.977881 -0.043825 0.204517 +v 0.019957 -0.000087 0.003818 +vn 0.963655 -0.216694 0.156248 +v 0.019957 0.008513 0.007318 +vn 0.971434 -0.167802 -0.167802 +v 0.019225 0.006913 0.022818 +vn 0.951452 -0.217645 -0.217645 +v 0.019957 0.008513 0.024418 +vn 0.972346 -0.015471 -0.233031 +v 0.019957 -0.000087 0.027918 +vn 0.971365 0.036679 -0.234743 +v 0.019225 -0.000087 0.024418 +vn 0.971380 0.168774 -0.167143 +v 0.019957 -0.008587 0.024418 +vn 0.951451 0.218917 -0.216372 +v 0.019225 -0.006987 0.022818 +vn 0.972346 -0.233030 -0.015471 +v 0.019957 0.012013 0.015818 +vn 0.971126 -0.235733 0.036670 +v 0.019225 0.008513 0.015818 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.006987 0.008818 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.006987 0.022818 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.008587 0.015818 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.000087 0.024418 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.000087 0.007318 +vn 1.000000 0.000000 0.000000 +v 0.019225 0.006913 0.022818 +vn 1.000000 0.000000 0.000000 +v 0.019225 0.006913 0.008818 +vn 1.000000 0.000000 0.000000 +v 0.019225 0.008513 0.015818 +vn 0.971300 0.235056 -0.036402 +v 0.019225 -0.008587 0.015818 +vn 0.972231 0.233510 0.015503 +v 0.019957 -0.012087 0.015818 +vn 0.672955 0.414641 0.612539 +v 0.019957 -0.049387 -0.014182 +vn 0.672955 0.414641 0.612539 +v 0.019957 -0.042887 -0.018582 +vn 0.672955 0.414641 0.612539 +v 0.018313 -0.042287 -0.017182 +vn 0.602489 0.424964 0.675583 +v 0.018313 -0.042287 -0.017182 +vn 0.675119 0.624442 0.392794 +v 0.018313 -0.048487 -0.013282 +vn 0.681190 0.138256 0.718933 +v 0.019957 -0.042887 -0.018582 +vn 0.998470 0.003821 0.055169 +v 0.018313 -0.034787 -0.018582 +vn 0.999886 0.002775 0.014867 +v 0.018313 -0.042287 -0.017182 +vn 0.690509 -0.042654 0.722065 +v 0.019957 -0.034787 -0.020182 +vn 0.675119 -0.392794 0.624442 +v 0.018313 -0.021087 -0.013282 +vn 0.675119 -0.392794 0.624442 +v 0.018313 -0.027287 -0.017182 +vn 0.675119 -0.392794 0.624442 +v 0.019957 -0.026687 -0.018582 +vn 0.605196 -0.446254 0.659238 +v 0.019957 -0.026687 -0.018582 +vn 0.635974 -0.583511 0.505027 +v 0.019957 -0.020187 -0.014182 +vn 0.997565 -0.013170 0.068485 +v 0.018313 -0.027287 -0.017182 +vn 0.671484 -0.143600 0.726972 +v 0.019957 -0.026687 -0.018582 +vn 0.675119 -0.392794 -0.624442 +v 0.018313 -0.021087 0.014118 +vn 0.612179 -0.559123 -0.559123 +v 0.019957 -0.020187 0.015018 +vn 0.605196 -0.446254 -0.659238 +v 0.019957 -0.026687 0.019418 +vn 0.675119 -0.392794 -0.624442 +v 0.019957 -0.026687 0.019418 +vn 0.675119 -0.392794 -0.624442 +v 0.018313 -0.027287 0.018018 +vn 0.999520 -0.005853 -0.030437 +v 0.018313 -0.027287 0.018018 +vn 0.690509 -0.042654 -0.722065 +v 0.019957 -0.034787 0.021018 +vn 0.998470 0.003821 -0.055169 +v 0.018313 -0.034787 0.019418 +vn 0.671484 -0.143600 -0.726972 +v 0.019957 -0.026687 0.019418 +vn 0.672955 0.414642 -0.612539 +v 0.018313 -0.042287 0.018018 +vn 0.672955 0.414642 -0.612539 +v 0.019957 -0.042887 0.019418 +vn 0.672955 0.414642 -0.612539 +v 0.019957 -0.049387 0.015018 +vn 0.612179 0.559123 -0.559123 +v 0.018313 -0.048487 0.014118 +vn 0.602489 0.424964 -0.675583 +v 0.018313 -0.042287 0.018018 +vn 0.681190 0.138256 -0.718933 +v 0.019957 -0.042887 0.019418 +vn 0.999396 0.006379 -0.034171 +v 0.018313 -0.042287 0.018018 +vn 0.672955 -0.612539 0.414642 +v 0.019957 -0.015787 -0.007682 +vn 0.640997 -0.642499 0.419901 +v 0.018313 -0.017187 -0.007082 +vn 0.681190 -0.718933 0.138256 +v 0.019957 -0.015787 -0.007682 +vn 0.986808 -0.161511 0.011187 +v 0.018313 -0.015787 0.000418 +vn 0.930683 -0.359615 0.067128 +v 0.018313 -0.017187 -0.007082 +vn 0.690509 -0.722066 -0.042654 +v 0.019957 -0.014187 0.000418 +vn 0.675118 -0.624442 -0.392794 +v 0.018313 -0.017187 0.007918 +vn 0.675118 -0.624442 -0.392794 +v 0.019957 -0.015787 0.008518 +vn 0.605196 -0.659238 -0.446254 +v 0.019957 -0.015787 0.008518 +vn 0.998750 -0.049091 -0.009441 +v 0.018313 -0.017187 0.007918 +vn 0.671484 -0.726972 -0.143599 +v 0.019957 -0.015787 0.008518 +vn 0.675119 0.624442 0.392794 +v 0.018313 -0.052387 -0.007082 +vn 0.675119 0.624442 0.392794 +v 0.019957 -0.053787 -0.007682 +vn 0.605196 0.659238 0.446254 +v 0.019957 -0.053787 -0.007682 +vn 0.998750 0.049091 0.009441 +v 0.018313 -0.052387 -0.007082 +vn 0.690509 0.722065 0.042654 +v 0.019957 -0.055387 0.000418 +vn 0.671485 0.726972 0.143599 +v 0.019957 -0.053787 -0.007682 +vn 0.986808 0.161511 -0.011187 +v 0.018313 -0.053787 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.018313 -0.021087 -0.013282 +vn 1.000000 0.000000 0.000000 +v 0.018313 -0.021087 0.014118 +vn 1.000000 0.000000 0.000000 +v 0.018313 -0.048487 -0.013282 +vn 1.000000 0.000000 0.000000 +v 0.018313 -0.048487 0.014118 +vn 0.930683 0.359615 -0.067128 +v 0.018313 -0.052387 0.007918 +vn 0.672956 0.612538 -0.414641 +v 0.019957 -0.053787 0.008518 +vn 0.640998 0.642499 -0.419901 +v 0.018313 -0.052387 0.007918 +vn 0.681190 0.718933 -0.138256 +v 0.019957 -0.053787 0.008518 +vn 0.964446 0.154361 0.214517 +v 0.019957 -0.008587 -0.023582 +vn 0.972963 -0.014348 0.230516 +v 0.019957 -0.000087 -0.027182 +vn 0.971886 0.037361 0.232470 +v 0.019225 -0.000087 -0.023582 +vn 0.965060 0.214068 0.151107 +v 0.019225 -0.006987 -0.022082 +vn 0.965937 -0.148895 0.211652 +v 0.019225 0.006913 -0.022082 +vn 0.963594 -0.217259 0.155835 +v 0.019957 0.008513 -0.023582 +vn 0.971435 -0.167802 -0.167802 +v 0.019225 0.006913 -0.008082 +vn 0.951452 -0.217645 -0.217645 +v 0.019957 0.008513 -0.006482 +vn 0.972346 -0.015471 -0.233031 +v 0.019957 -0.000087 -0.002982 +vn 0.971365 0.036679 -0.234743 +v 0.019225 -0.000087 -0.006482 +vn 0.971380 0.168774 -0.167143 +v 0.019957 -0.008587 -0.006482 +vn 0.951451 0.218917 -0.216372 +v 0.019225 -0.006987 -0.008082 +vn 0.972346 -0.233030 -0.015471 +v 0.019957 0.012013 -0.015082 +vn 0.971126 -0.235733 0.036670 +v 0.019225 0.008513 -0.015082 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.006987 -0.022082 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.006987 -0.008082 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.008587 -0.015082 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.000087 -0.006482 +vn 1.000000 0.000000 0.000000 +v 0.019225 -0.000087 -0.023582 +vn 1.000000 0.000000 0.000000 +v 0.019225 0.006913 -0.008082 +vn 1.000000 0.000000 0.000000 +v 0.019225 0.006913 -0.022082 +vn 1.000000 0.000000 0.000000 +v 0.019225 0.008513 -0.015082 +vn 0.971300 0.235056 -0.036402 +v 0.019225 -0.008587 -0.015082 +vn 0.972231 0.233510 0.015503 +v 0.019957 -0.012087 -0.015082 +vn 0.672433 0.419321 0.609921 +v 0.019957 0.020613 -0.014182 +vn 0.672433 0.419321 0.609921 +v 0.019957 0.027013 -0.018582 +vn 0.672433 0.419321 0.609921 +v 0.018313 0.027613 -0.017182 +vn 0.585634 0.431592 0.686120 +v 0.018313 0.027613 -0.017182 +vn 0.614981 0.593881 0.518752 +v 0.018313 0.021413 -0.013282 +vn 0.681183 0.136569 0.719263 +v 0.019957 0.027013 -0.018582 +vn 0.998459 0.003801 0.055359 +v 0.018313 0.035213 -0.018582 +vn 0.999884 0.002761 0.014990 +v 0.018313 0.027613 -0.017182 +vn 0.690541 -0.042473 0.722045 +v 0.019957 0.035213 -0.020182 +vn 0.675118 -0.392794 0.624442 +v 0.018313 0.048913 -0.013282 +vn 0.675118 -0.392794 0.624442 +v 0.018313 0.042713 -0.017182 +vn 0.675118 -0.392794 0.624442 +v 0.019957 0.043313 -0.018582 +vn 0.587923 -0.458275 0.666582 +v 0.019957 0.043313 -0.018582 +vn 0.614022 -0.598531 0.514527 +v 0.019957 0.049713 -0.014182 +vn 0.997537 -0.013245 0.068874 +v 0.018313 0.042713 -0.017182 +vn 0.671484 -0.143600 0.726972 +v 0.019957 0.043313 -0.018582 +vn 0.675118 -0.392794 -0.624442 +v 0.018313 0.048913 0.014118 +vn 0.590132 -0.573477 -0.568216 +v 0.019957 0.049713 0.015018 +vn 0.587923 -0.458275 -0.666582 +v 0.019957 0.043313 0.019418 +vn 0.675118 -0.392794 -0.624442 +v 0.019957 0.043313 0.019418 +vn 0.675118 -0.392794 -0.624442 +v 0.018313 0.042713 0.018018 +vn 0.999521 -0.005847 -0.030404 +v 0.018313 0.042713 0.018018 +vn 0.690541 -0.042473 -0.722045 +v 0.019957 0.035213 0.021018 +vn 0.998459 0.003801 -0.055359 +v 0.018313 0.035213 0.019418 +vn 0.671484 -0.143600 -0.726972 +v 0.019957 0.043313 0.019418 +vn 0.672433 0.419321 -0.609921 +v 0.018313 0.027613 0.018018 +vn 0.672433 0.419321 -0.609921 +v 0.019957 0.027013 0.019418 +vn 0.672433 0.419321 -0.609921 +v 0.019957 0.020613 0.015018 +vn 0.590240 0.570796 -0.570796 +v 0.018313 0.021413 0.014118 +vn 0.585634 0.431592 -0.686120 +v 0.018313 0.027613 0.018018 +vn 0.681183 0.136569 -0.719263 +v 0.019957 0.027013 0.019418 +vn 0.999382 0.006369 -0.034576 +v 0.018313 0.027613 0.018018 +vn 0.678510 -0.696579 0.233243 +v 0.019957 0.054113 -0.007682 +vn 0.633324 -0.698967 0.332183 +v 0.018313 0.052813 -0.007082 +vn 0.698327 -0.714704 -0.039203 +v 0.019957 0.055813 0.000418 +vn 0.697355 -0.714793 0.052604 +v 0.018313 0.054113 0.000418 +vn 0.678281 -0.700549 -0.221734 +v 0.018313 0.052813 0.007918 +vn 0.634051 -0.696930 -0.335063 +v 0.019957 0.054113 0.008518 +vn 0.678281 0.700549 0.221733 +v 0.018313 0.017513 -0.007082 +vn 0.634051 0.696931 0.335063 +v 0.019957 0.016213 -0.007682 +vn 0.697355 0.714792 -0.052604 +v 0.018313 0.016213 0.000418 +vn 0.698327 0.714704 0.039203 +v 0.019957 0.014513 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.054113 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.048913 -0.013282 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.052813 -0.007082 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.052813 0.007918 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.048913 0.014118 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.021413 -0.013282 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.017513 -0.007082 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.016213 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.021413 0.014118 +vn 1.000000 0.000000 0.000000 +v 0.018313 0.017513 0.007918 +vn 0.678510 0.696578 -0.233243 +v 0.019957 0.016213 0.008518 +vn 0.633324 0.698968 -0.332183 +v 0.018313 0.017513 0.007918 +vn -1.000000 0.000000 0.000000 +v 0.019957 -0.047687 0.029718 +vn -1.000000 0.000000 0.000000 +v 0.019957 -0.026687 0.019418 +vn -1.000000 0.000000 0.000000 +v 0.019957 -0.020187 0.015018 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.000087 -0.027182 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.024713 -0.028882 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.008513 -0.023582 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.000187 -0.031382 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.015013 -0.030582 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.008587 -0.023582 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.024187 -0.028882 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.015387 -0.030582 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.012087 -0.015082 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.026687 -0.018582 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.034187 -0.026982 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.008587 -0.006482 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.000087 0.003818 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.008587 0.007318 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.000087 -0.002982 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.014187 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.012087 0.015818 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.008513 0.007318 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.008513 -0.006482 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.045513 -0.023482 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.035213 -0.020182 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.034613 -0.026982 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.012013 -0.015082 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.026113 0.031118 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.020613 0.015018 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.027013 0.019418 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.015013 0.031318 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.035213 0.021018 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.048113 0.029718 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.058313 0.026818 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.053713 0.029118 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.062813 0.020718 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.043313 0.019418 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.063313 0.011718 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.049713 0.015018 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.062613 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.054113 0.008518 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.060313 -0.010882 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.055813 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.052913 -0.019882 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.054113 -0.007682 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.049713 -0.014182 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.050613 -0.021082 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.043313 -0.018582 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.027013 -0.018582 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.020613 -0.014182 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.016213 -0.007682 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.014513 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.016213 0.008518 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.008587 0.024418 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.025687 0.031118 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.047687 0.029718 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.057887 0.026818 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.053287 0.029118 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.034787 0.021018 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.026687 0.019418 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.012013 0.015818 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.020187 0.015018 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.015387 0.031318 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.042887 0.019418 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.062387 0.020718 +vn 1.000000 0.000000 0.000000 +v 0.019957 0.008513 0.024418 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.049387 0.015018 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.062787 0.011718 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.000087 0.027918 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.000187 0.031618 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.053787 0.008518 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.062187 0.000418 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.015787 0.008518 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.015787 -0.007682 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.020187 -0.014182 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.034787 -0.020182 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.045087 -0.023482 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.042887 -0.018582 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.052487 -0.019882 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.050187 -0.021082 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.059887 -0.010882 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.049387 -0.014182 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.053787 -0.007682 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.055387 0.000418 +vn 0.000000 -0.019733 0.999805 +v -0.104443 -0.015387 0.031318 +vn 0.000000 -0.019733 0.999805 +v 0.019957 -0.015387 0.031318 +vn 0.000000 -0.019733 0.999805 +v -0.104443 -0.000187 0.031618 +vn 0.000000 -0.019733 0.999805 +v 0.019957 -0.000187 0.031618 +vn 0.000000 0.019733 0.999805 +v -0.104443 -0.000187 0.031618 +vn 0.000000 0.019733 0.999805 +v 0.019957 -0.000187 0.031618 +vn 0.000000 0.019733 0.999805 +v -0.104443 0.015013 0.031318 +vn 0.000000 0.019733 0.999805 +v 0.019957 0.015013 0.031318 +vn 0.000000 -0.462566 -0.886585 +v -0.104443 -0.052487 -0.019882 +vn 0.000000 -0.462566 -0.886585 +v -0.104443 -0.050187 -0.021082 +vn 0.000000 -0.462566 -0.886585 +v 0.019957 -0.052487 -0.019882 +vn 0.000000 -0.462566 -0.886585 +v 0.019957 -0.050187 -0.021082 +vn 0.000000 -0.425797 -0.904819 +v -0.104443 -0.045087 -0.023482 +vn 0.000000 -0.425797 -0.904819 +v 0.019957 -0.045087 -0.023482 +vn 0.000000 -0.425797 -0.904819 +v -0.104443 -0.050187 -0.021082 +vn 0.000000 -0.425797 -0.904819 +v 0.019957 -0.050187 -0.021082 +vn 0.000000 -0.186661 -0.982424 +v -0.104443 -0.024187 -0.028882 +vn 0.000000 -0.186661 -0.982424 +v 0.019957 -0.024187 -0.028882 +vn 0.000000 -0.186661 -0.982424 +v -0.104443 -0.034187 -0.026982 +vn 0.000000 -0.186661 -0.982424 +v 0.019957 -0.034187 -0.026982 +vn 0.000000 -0.305726 -0.952119 +v -0.104443 -0.045087 -0.023482 +vn 0.000000 -0.305726 -0.952119 +v -0.104443 -0.034187 -0.026982 +vn 0.000000 -0.305726 -0.952119 +v 0.019957 -0.045087 -0.023482 +vn 0.000000 -0.305726 -0.952119 +v 0.019957 -0.034187 -0.026982 +vn 0.000000 -0.804724 0.593649 +v -0.104443 -0.062387 0.020718 +vn 0.000000 -0.804724 0.593649 +v 0.019957 -0.062387 0.020718 +vn 0.000000 -0.804724 0.593649 +v -0.104443 -0.057887 0.026818 +vn 0.000000 -0.804724 0.593649 +v 0.019957 -0.057887 0.026818 +vn 0.000000 -0.447214 0.894427 +v -0.104443 -0.057887 0.026818 +vn 0.000000 -0.447214 0.894427 +v 0.019957 -0.057887 0.026818 +vn 0.000000 -0.447214 0.894427 +v -0.104443 -0.053287 0.029118 +vn 0.000000 -0.447214 0.894427 +v 0.019957 -0.053287 0.029118 +vn 0.000000 -0.063508 0.997981 +v -0.104443 -0.047687 0.029718 +vn 0.000000 -0.063508 0.997981 +v 0.019957 -0.025687 0.031118 +vn 0.000000 -0.063508 0.997981 +v -0.104443 -0.025687 0.031118 +vn 0.000000 -0.063508 0.997981 +v 0.019957 -0.047687 0.029718 +vn 0.000000 -0.106533 0.994309 +v -0.104443 -0.053287 0.029118 +vn 0.000000 -0.106533 0.994309 +v 0.019957 -0.053287 0.029118 +vn 0.000000 -0.106533 0.994309 +v -0.104443 -0.047687 0.029718 +vn 0.000000 -0.106533 0.994309 +v 0.019957 -0.047687 0.029718 +vn 0.000000 -0.772425 -0.635105 +v -0.104443 -0.059887 -0.010882 +vn 0.000000 -0.772425 -0.635105 +v -0.104443 -0.052487 -0.019882 +vn 0.000000 -0.772425 -0.635105 +v 0.019957 -0.059887 -0.010882 +vn 0.000000 -0.772425 -0.635105 +v 0.019957 -0.052487 -0.019882 +vn 0.000000 -0.979908 -0.199450 +v -0.104443 -0.062187 0.000418 +vn 0.000000 -0.979908 -0.199450 +v -0.104443 -0.059887 -0.010882 +vn 0.000000 -0.979908 -0.199450 +v 0.019957 -0.062187 0.000418 +vn 0.000000 -0.979908 -0.199450 +v 0.019957 -0.059887 -0.010882 +vn 0.000000 -0.999014 0.044400 +v -0.104443 -0.062787 0.011718 +vn 0.000000 -0.999014 0.044400 +v 0.019957 -0.062787 0.011718 +vn 0.000000 -0.999014 0.044400 +v -0.104443 -0.062387 0.020718 +vn 0.000000 -0.999014 0.044400 +v 0.019957 -0.062387 0.020718 +vn 0.000000 -0.998593 -0.053022 +v -0.104443 -0.062787 0.011718 +vn 0.000000 -0.998593 -0.053022 +v -0.104443 -0.062187 0.000418 +vn 0.000000 -0.998593 -0.053022 +v 0.019957 -0.062787 0.011718 +vn 0.000000 -0.998593 -0.053022 +v 0.019957 -0.062187 0.000418 +vn 0.000000 -0.052559 -0.998618 +v -0.104443 -0.015387 -0.030582 +vn 0.000000 -0.052559 -0.998618 +v -0.104443 -0.000187 -0.031382 +vn 0.000000 -0.052559 -0.998618 +v 0.019957 -0.015387 -0.030582 +vn 0.000000 -0.052559 -0.998618 +v 0.019957 -0.000187 -0.031382 +vn 0.000000 0.052559 -0.998618 +v -0.104443 -0.000187 -0.031382 +vn 0.000000 0.052559 -0.998618 +v -0.104443 0.015013 -0.030582 +vn 0.000000 0.052559 -0.998618 +v 0.019957 -0.000187 -0.031382 +vn 0.000000 0.052559 -0.998618 +v 0.019957 0.015013 -0.030582 +vn 0.000000 0.188480 -0.982077 +v -0.104443 0.024713 -0.028882 +vn 0.000000 0.188480 -0.982077 +v -0.104443 0.034613 -0.026982 +vn 0.000000 0.188480 -0.982077 +v 0.019957 0.024713 -0.028882 +vn 0.000000 0.188480 -0.982077 +v 0.019957 0.034613 -0.026982 +vn 0.000000 0.305726 -0.952119 +v -0.104443 0.034613 -0.026982 +vn 0.000000 0.305726 -0.952119 +v -0.104443 0.045513 -0.023482 +vn 0.000000 0.305726 -0.952119 +v 0.019957 0.034613 -0.026982 +vn 0.000000 0.305726 -0.952119 +v 0.019957 0.045513 -0.023482 +vn 0.000000 0.462567 -0.886584 +v -0.104443 0.050613 -0.021082 +vn 0.000000 0.462567 -0.886584 +v -0.104443 0.052913 -0.019882 +vn 0.000000 0.462567 -0.886584 +v 0.019957 0.050613 -0.021082 +vn 0.000000 0.462567 -0.886584 +v 0.019957 0.052913 -0.019882 +vn 0.000000 0.425797 -0.904819 +v -0.104443 0.045513 -0.023482 +vn 0.000000 0.425797 -0.904819 +v -0.104443 0.050613 -0.021082 +vn 0.000000 0.425797 -0.904819 +v 0.019957 0.045513 -0.023482 +vn 0.000000 0.425797 -0.904819 +v 0.019957 0.050613 -0.021082 +vn 0.000000 0.804724 0.593649 +v -0.104443 0.058313 0.026818 +vn 0.000000 0.804724 0.593649 +v 0.019957 0.058313 0.026818 +vn 0.000000 0.804724 0.593649 +v -0.104443 0.062813 0.020718 +vn 0.000000 0.804724 0.593649 +v 0.019957 0.062813 0.020718 +vn 0.000000 0.447214 0.894427 +v -0.104443 0.053713 0.029118 +vn 0.000000 0.447214 0.894427 +v 0.019957 0.053713 0.029118 +vn 0.000000 0.447214 0.894427 +v -0.104443 0.058313 0.026818 +vn 0.000000 0.447214 0.894427 +v 0.019957 0.058313 0.026818 +vn 0.000000 0.063508 0.997981 +v -0.104443 0.026113 0.031118 +vn 0.000000 0.063508 0.997981 +v 0.019957 0.048113 0.029718 +vn 0.000000 0.063508 0.997981 +v -0.104443 0.048113 0.029718 +vn 0.000000 0.063508 0.997981 +v 0.019957 0.026113 0.031118 +vn 0.000000 0.106533 0.994309 +v -0.104443 0.048113 0.029718 +vn 0.000000 0.106533 0.994309 +v 0.019957 0.048113 0.029718 +vn 0.000000 0.106533 0.994309 +v -0.104443 0.053713 0.029118 +vn 0.000000 0.106533 0.994309 +v 0.019957 0.053713 0.029118 +vn 0.000000 0.772425 -0.635106 +v -0.104443 0.052913 -0.019882 +vn 0.000000 0.772425 -0.635106 +v -0.104443 0.060313 -0.010882 +vn 0.000000 0.772425 -0.635106 +v 0.019957 0.052913 -0.019882 +vn 0.000000 0.772425 -0.635106 +v 0.019957 0.060313 -0.010882 +vn 0.000000 0.979908 -0.199450 +v -0.104443 0.060313 -0.010882 +vn 0.000000 0.979908 -0.199450 +v -0.104443 0.062613 0.000418 +vn 0.000000 0.979908 -0.199450 +v 0.019957 0.060313 -0.010882 +vn 0.000000 0.979908 -0.199450 +v 0.019957 0.062613 0.000418 +vn 0.000000 0.998460 0.055470 +v -0.104443 0.062813 0.020718 +vn 0.000000 0.998460 0.055470 +v 0.019957 0.062813 0.020718 +vn 0.000000 0.998460 0.055470 +v -0.104443 0.063313 0.011718 +vn 0.000000 0.998460 0.055470 +v 0.019957 0.063313 0.011718 +vn 0.000000 0.998087 -0.061828 +v -0.104443 0.063313 0.011718 +vn 0.000000 0.998087 -0.061828 +v 0.019957 0.063313 0.011718 +vn 0.000000 0.998087 -0.061828 +v -0.104443 0.062613 0.000418 +vn 0.000000 0.998087 -0.061828 +v 0.019957 0.062613 0.000418 +vn 0.000000 -0.019414 0.999812 +v -0.104443 -0.025687 0.031118 +vn 0.000000 -0.019414 0.999812 +v 0.019957 -0.025687 0.031118 +vn 0.000000 -0.019414 0.999812 +v -0.104443 -0.015387 0.031318 +vn 0.000000 -0.019414 0.999812 +v 0.019957 -0.015387 0.031318 +vn 0.000000 0.172627 -0.984987 +v -0.104443 0.024713 -0.028882 +vn 0.000000 0.172627 -0.984987 +v 0.019957 0.024713 -0.028882 +vn 0.000000 0.172627 -0.984987 +v -0.104443 0.015013 -0.030582 +vn 0.000000 0.172627 -0.984987 +v 0.019957 0.015013 -0.030582 +vn 0.000000 0.018015 0.999838 +v -0.104443 0.026113 0.031118 +vn 0.000000 0.018015 0.999838 +v -0.104443 0.015013 0.031318 +vn 0.000000 0.018015 0.999838 +v 0.019957 0.026113 0.031118 +vn 0.000000 0.018015 0.999838 +v 0.019957 0.015013 0.031318 +vn 0.000000 -0.189675 -0.981847 +v -0.104443 -0.015387 -0.030582 +vn 0.000000 -0.189675 -0.981847 +v 0.019957 -0.015387 -0.030582 +vn 0.000000 -0.189675 -0.981847 +v -0.104443 -0.024187 -0.028882 +vn 0.000000 -0.189675 -0.981847 +v 0.019957 -0.024187 -0.028882 +vn -0.756493 -0.132579 -0.640423 +v -0.061543 -0.021687 0.080018 +vn -0.500341 -0.175520 -0.847851 +v -0.054043 -0.036787 0.078718 +vn -0.944479 -0.067463 -0.321573 +v -0.061543 -0.035987 0.083018 +vn -0.496961 -0.173637 -0.850223 +v -0.054043 -0.022587 0.075818 +vn -0.944129 0.065504 0.323002 +v -0.061543 -0.020087 0.088518 +vn -0.754444 0.133058 0.642736 +v -0.061543 -0.034387 0.091418 +vn -0.192288 0.200238 0.960692 +v -0.054043 -0.019287 0.092718 +vn 0.187312 0.200434 0.961634 +v -0.054043 -0.033487 0.095718 +vn 0.756288 0.132627 0.640655 +v -0.046543 -0.020087 0.088518 +vn 0.944687 0.065185 0.321429 +v -0.046543 -0.034387 0.091418 +vn 0.944111 -0.067679 -0.322605 +v -0.046543 -0.021687 0.080018 +vn 0.754651 -0.133009 -0.642503 +v -0.046543 -0.035987 0.083018 +vn 0.500341 -0.175520 -0.847851 +v -0.054043 -0.022587 0.075818 +vn 0.503709 -0.172857 -0.846403 +v -0.054043 -0.036787 0.078718 +vn -0.111615 -0.992804 0.043390 +v -0.054043 -0.036887 0.081718 +vn -0.089158 -0.982158 0.165580 +v -0.058943 -0.035987 0.084418 +vn -0.111615 -0.992804 0.043390 +v -0.061543 -0.035987 0.083018 +vn -0.124726 -0.991640 -0.033055 +v -0.054043 -0.036787 0.078718 +vn 0.018715 -0.973155 0.229387 +v -0.058943 -0.035987 0.084418 +vn 0.189709 -0.939504 0.285207 +v -0.058943 -0.034287 0.090018 +vn 0.018715 -0.973155 0.229387 +v -0.061543 -0.034387 0.091418 +vn -0.100245 -0.977390 0.186170 +v -0.061543 -0.035987 0.083018 +vn 0.126997 -0.991450 0.029978 +v -0.058943 -0.034287 0.090018 +vn 0.197933 -0.979672 -0.032655 +v -0.054043 -0.033387 0.092718 +vn 0.126997 -0.991450 0.029978 +v -0.054043 -0.033487 0.095718 +vn 0.077510 -0.994321 0.072922 +v -0.061543 -0.034387 0.091418 +vn -0.126997 -0.991450 0.029978 +v -0.054043 -0.033387 0.092718 +vn -0.108618 -0.985370 0.131334 +v -0.049143 -0.034287 0.090018 +vn -0.126997 -0.991450 0.029978 +v -0.046543 -0.034387 0.091418 +vn -0.137709 -0.989923 -0.032997 +v -0.054043 -0.033487 0.095718 +vn -0.018715 -0.973155 0.229387 +v -0.049143 -0.034287 0.090018 +vn 0.154535 -0.945386 0.286993 +v -0.049143 -0.035987 0.084418 +vn -0.018715 -0.973155 0.229387 +v -0.046543 -0.035987 0.083018 +vn -0.137225 -0.973046 0.185342 +v -0.046543 -0.034387 0.091418 +vn 0.111615 -0.992804 0.043391 +v -0.049143 -0.035987 0.084418 +vn 0.197934 -0.979671 -0.032656 +v -0.054043 -0.036887 0.081718 +vn 0.111615 -0.992804 0.043391 +v -0.054043 -0.036787 0.078718 +vn 0.051356 -0.994116 0.095376 +v -0.046543 -0.035987 0.083018 +vn -0.511224 -0.343023 -0.788026 +v -0.054043 -0.045587 0.085418 +vn -0.511224 -0.343023 -0.788026 +v -0.058943 -0.035987 0.084418 +vn -0.501039 -0.338697 -0.796394 +v -0.054043 -0.036887 0.081718 +vn -0.521568 -0.347393 -0.779285 +v -0.058943 -0.044287 0.088118 +vn -0.505181 0.351004 0.788409 +v -0.058943 -0.041787 0.093318 +vn -0.505181 0.351004 0.788409 +v -0.054043 -0.033387 0.092718 +vn -0.500636 0.348634 0.792350 +v -0.058943 -0.034287 0.090018 +vn -0.509911 0.353466 0.784253 +v -0.054043 -0.040487 0.095918 +vn 0.505181 0.351004 0.788409 +v -0.054043 -0.040487 0.095918 +vn 0.505181 0.351004 0.788409 +v -0.049143 -0.034287 0.090018 +vn 0.500309 0.355776 0.789376 +v -0.054043 -0.033387 0.092718 +vn 0.509760 0.346483 0.787461 +v -0.049143 -0.041787 0.093318 +vn 0.511224 -0.343023 -0.788026 +v -0.049143 -0.044287 0.088118 +vn 0.511224 -0.343023 -0.788026 +v -0.054043 -0.036887 0.081718 +vn 0.500463 -0.352502 -0.790746 +v -0.049143 -0.035987 0.084418 +vn 0.521319 -0.333976 -0.785294 +v -0.054043 -0.045587 0.085418 +vn -0.498376 -0.653909 -0.569231 +v -0.054043 -0.052287 0.093018 +vn -0.498376 -0.653909 -0.569231 +v -0.058943 -0.044287 0.088118 +vn -0.490857 -0.653540 -0.576147 +v -0.054043 -0.045587 0.085418 +vn -0.507388 -0.654265 -0.560799 +v -0.058943 -0.049687 0.094418 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.049687 0.094418 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.035987 0.084418 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.044287 0.088118 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.041787 0.093318 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.034287 0.090018 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.044687 0.097318 +vn -0.486689 0.728503 0.482097 +v -0.058943 -0.044687 0.097318 +vn -0.516041 0.743706 0.424975 +v -0.054043 -0.042087 0.098718 +vn -0.486689 0.728503 0.482097 +v -0.054043 -0.040487 0.095918 +vn -0.465698 0.716459 0.519433 +v -0.058943 -0.041787 0.093318 +vn 0.486689 0.728503 0.482097 +v -0.054043 -0.042087 0.098718 +vn 0.512787 0.695063 0.503921 +v -0.049143 -0.044687 0.097318 +vn 0.486689 0.728503 0.482097 +v -0.049143 -0.041787 0.093318 +vn 0.442622 0.778561 0.444892 +v -0.054043 -0.040487 0.095918 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.035987 0.084418 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.049687 0.094418 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.044287 0.088118 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.041787 0.093318 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.044687 0.097318 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.034287 0.090018 +vn 0.498377 -0.653909 -0.569231 +v -0.049143 -0.049687 0.094418 +vn 0.498377 -0.653909 -0.569231 +v -0.054043 -0.045587 0.085418 +vn 0.488627 -0.662446 -0.567811 +v -0.049143 -0.044287 0.088118 +vn 0.506207 -0.646917 -0.570309 +v -0.054043 -0.052287 0.093018 +vn -0.468424 -0.875159 0.121146 +v -0.054043 -0.050787 0.105418 +vn -0.508767 -0.849160 0.141717 +v -0.057743 -0.048687 0.104718 +vn -0.468424 -0.875159 0.121146 +v -0.058943 -0.049687 0.094418 +vn -0.441794 -0.890624 0.107737 +v -0.054043 -0.052287 0.093018 +vn -0.988709 -0.022544 0.148145 +v -0.057743 -0.048687 0.104718 +vn -0.977982 0.070190 0.196532 +v -0.057743 -0.044487 0.103218 +vn -0.988709 -0.022544 0.148145 +v -0.058943 -0.044687 0.097318 +vn -0.989969 -0.070887 0.122218 +v -0.058943 -0.049687 0.094418 +vn -0.482734 0.873067 0.068720 +v -0.057743 -0.044487 0.103218 +vn -0.482734 0.873067 0.068720 +v -0.054043 -0.042087 0.098718 +vn -0.482837 0.873018 0.068610 +v -0.058943 -0.044687 0.097318 +vn -0.482535 0.873160 0.068934 +v -0.054043 -0.042387 0.102518 +vn 0.482734 0.873066 0.068721 +v -0.054043 -0.042387 0.102518 +vn 0.482734 0.873066 0.068721 +v -0.049143 -0.044687 0.097318 +vn 0.482895 0.872962 0.068918 +v -0.054043 -0.042087 0.098718 +vn 0.482602 0.873152 0.068558 +v -0.050343 -0.044487 0.103218 +vn 0.988709 -0.022544 0.148145 +v -0.050343 -0.044487 0.103218 +vn 0.992928 0.039930 0.111804 +v -0.050343 -0.048687 0.104718 +vn 0.988709 -0.022544 0.148145 +v -0.049143 -0.049687 0.094418 +vn 0.972423 -0.117014 0.201747 +v -0.049143 -0.044687 0.097318 +vn 0.468424 -0.875159 0.121146 +v -0.050343 -0.048687 0.104718 +vn 0.505703 -0.856464 0.103605 +v -0.054043 -0.050787 0.105418 +vn 0.468424 -0.875159 0.121146 +v -0.054043 -0.052287 0.093018 +vn 0.433477 -0.890694 0.136977 +v -0.049143 -0.049687 0.094418 +vn -0.509566 -0.828571 0.231974 +v -0.054043 -0.046287 0.121418 +vn -0.509566 -0.828571 0.231974 +v -0.057743 -0.048687 0.104718 +vn -0.512975 -0.826343 0.232409 +v -0.054043 -0.050787 0.105418 +vn -0.504856 -0.831618 0.231368 +v -0.056743 -0.044787 0.120918 +vn -0.998216 0.018645 0.056713 +v -0.056743 -0.044787 0.120918 +vn -0.998216 0.018645 0.056713 +v -0.057743 -0.044487 0.103218 +vn -0.998183 0.020264 0.056738 +v -0.057743 -0.048687 0.104718 +vn -0.998257 0.016455 0.056678 +v -0.056743 -0.041687 0.120018 +vn -0.513108 0.850827 -0.113198 +v -0.056743 -0.041687 0.120018 +vn -0.513108 0.850827 -0.113198 +v -0.054043 -0.042387 0.102518 +vn -0.506470 0.854908 -0.112338 +v -0.057743 -0.044487 0.103218 +vn -0.522046 0.845217 -0.114353 +v -0.054043 -0.040087 0.119518 +vn 0.513109 0.850826 -0.113198 +v -0.054043 -0.040087 0.119518 +vn 0.513109 0.850826 -0.113198 +v -0.050343 -0.044487 0.103218 +vn 0.506746 0.854312 -0.115583 +v -0.054043 -0.042387 0.102518 +vn 0.521703 0.846013 -0.109948 +v -0.051343 -0.041687 0.120018 +vn 0.998216 0.018645 0.056713 +v -0.051343 -0.041687 0.120018 +vn 0.998216 0.018645 0.056713 +v -0.050343 -0.048687 0.104718 +vn 0.998225 0.020029 0.056080 +v -0.050343 -0.044487 0.103218 +vn 0.998200 0.016720 0.057592 +v -0.051343 -0.044787 0.120918 +vn 0.509567 -0.828571 0.231974 +v -0.051343 -0.044787 0.120918 +vn 0.509567 -0.828571 0.231974 +v -0.054043 -0.050787 0.105418 +vn 0.512937 -0.826840 0.230717 +v -0.050343 -0.048687 0.104718 +vn 0.504908 -0.830934 0.233700 +v -0.054043 -0.046287 0.121418 +vn -0.023802 0.257836 0.965895 +v -0.054043 -0.045287 0.121118 +vn -0.031451 0.220155 0.974958 +v -0.055643 -0.044187 0.120818 +vn -0.023802 0.257836 0.965895 +v -0.056743 -0.044787 0.120918 +vn -0.017737 0.287300 0.957676 +v -0.054043 -0.046287 0.121418 +vn -0.013605 0.299312 0.954058 +v -0.055643 -0.044187 0.120818 +vn 0.064220 0.329668 0.941910 +v -0.055643 -0.042187 0.120118 +vn -0.013605 0.299312 0.954058 +v -0.056743 -0.041687 0.120018 +vn -0.064638 0.278227 0.958338 +v -0.056743 -0.044787 0.120918 +vn 0.065834 0.227432 0.971566 +v -0.055643 -0.042187 0.120118 +vn 0.132970 0.177300 0.975133 +v -0.054043 -0.041187 0.119718 +vn 0.065834 0.227432 0.971566 +v -0.054043 -0.040087 0.119518 +vn 0.027971 0.254854 0.966575 +v -0.056743 -0.041687 0.120018 +vn -0.065834 0.227432 0.971566 +v -0.054043 -0.041187 0.119718 +vn -0.050124 0.300753 0.952384 +v -0.052443 -0.042187 0.120118 +vn -0.065834 0.227432 0.971566 +v -0.051343 -0.041687 0.120018 +vn -0.075970 0.178371 0.981026 +v -0.054043 -0.040087 0.119518 +vn 0.013605 0.299312 0.954058 +v -0.052443 -0.042187 0.120118 +vn 0.093967 0.328888 0.939682 +v -0.052443 -0.044187 0.120818 +vn 0.013605 0.299312 0.954058 +v -0.051343 -0.044787 0.120918 +vn -0.039396 0.278594 0.959601 +v -0.051343 -0.041687 0.120018 +vn 0.023802 0.257836 0.965895 +v -0.052443 -0.044187 0.120818 +vn -0.017951 0.287299 0.957673 +v -0.054043 -0.045287 0.121118 +vn 0.023802 0.257836 0.965895 +v -0.054043 -0.046287 0.121418 +vn 0.044450 0.242994 0.969009 +v -0.051343 -0.044787 0.120918 +vn -0.564766 -0.769834 0.297315 +v -0.054043 -0.042387 0.128518 +vn -0.550294 -0.780444 0.296788 +v -0.055643 -0.041487 0.127918 +vn -0.564766 -0.769834 0.297315 +v -0.055643 -0.044187 0.120818 +vn -0.578117 -0.759700 0.297720 +v -0.054043 -0.045287 0.121118 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.041487 0.127918 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.042187 0.120118 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.044187 0.120818 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.039787 0.126718 +vn -0.553523 0.783218 -0.283163 +v -0.055643 -0.039787 0.126718 +vn -0.553523 0.783218 -0.283163 +v -0.054043 -0.041187 0.119718 +vn -0.558222 0.779738 -0.283542 +v -0.055643 -0.042187 0.120118 +vn -0.548613 0.786811 -0.282760 +v -0.054043 -0.038887 0.126118 +vn 0.553524 0.783217 -0.283163 +v -0.054043 -0.038887 0.126118 +vn 0.553524 0.783217 -0.283163 +v -0.052443 -0.042187 0.120118 +vn 0.558175 0.780832 -0.280611 +v -0.054043 -0.041187 0.119718 +vn 0.548969 0.785519 -0.285644 +v -0.052443 -0.039787 0.126718 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.039787 0.126718 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.044187 0.120818 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.042187 0.120118 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.041487 0.127918 +vn 0.564766 -0.769833 0.297314 +v -0.052443 -0.041487 0.127918 +vn 0.551160 -0.776873 0.304450 +v -0.054043 -0.042387 0.128518 +vn 0.564766 -0.769833 0.297314 +v -0.054043 -0.045287 0.121118 +vn 0.578516 -0.762404 0.289928 +v -0.052443 -0.044187 0.120818 +vn -0.578660 -0.286898 0.763441 +v -0.051843 -0.032387 0.134218 +vn -0.578660 -0.286898 0.763441 +v -0.053443 -0.032087 0.133118 +vn -0.578660 -0.286898 0.763441 +v -0.055643 -0.041487 0.127918 +vn -0.493813 -0.346071 0.797736 +v -0.055643 -0.041487 0.127918 +vn -0.493813 -0.346071 0.797736 +v -0.054043 -0.042387 0.128518 +vn -0.493813 -0.346071 0.797736 +v -0.051843 -0.032387 0.134218 +vn -0.976589 0.174675 0.125547 +v -0.053443 -0.032087 0.133118 +vn -0.972660 0.222438 0.066731 +v -0.053443 -0.031487 0.131118 +vn -0.976589 0.174675 0.125547 +v -0.055643 -0.039787 0.126718 +vn -0.975079 0.127943 0.181252 +v -0.055643 -0.041487 0.127918 +vn -0.545043 0.499281 -0.673532 +v -0.053443 -0.031487 0.131118 +vn -0.545043 0.499281 -0.673532 +v -0.054043 -0.038887 0.126118 +vn -0.536663 0.501848 -0.678337 +v -0.055643 -0.039787 0.126718 +vn -0.553001 0.496782 -0.668878 +v -0.051843 -0.031187 0.130018 +vn 0.540952 0.268147 -0.797162 +v -0.051843 -0.031187 0.130018 +vn 0.604651 0.248224 -0.756824 +v -0.050343 -0.031487 0.131118 +vn 0.540952 0.268147 -0.797162 +v -0.052443 -0.039787 0.126718 +vn 0.473511 0.286554 -0.832871 +v -0.054043 -0.038887 0.126118 +vn 0.978603 -0.167079 -0.120088 +v -0.050343 -0.031487 0.131118 +vn 0.980573 -0.187884 -0.056365 +v -0.050343 -0.032087 0.133118 +vn 0.978603 -0.167079 -0.120088 +v -0.052443 -0.041487 0.127918 +vn 0.970014 -0.140163 -0.198563 +v -0.052443 -0.039787 0.126718 +vn 0.557188 -0.497186 0.665092 +v -0.050343 -0.032087 0.133118 +vn 0.575639 -0.496833 0.649459 +v -0.051843 -0.032387 0.134218 +vn 0.557188 -0.497186 0.665092 +v -0.054043 -0.042387 0.128518 +vn 0.535642 -0.497234 0.682529 +v -0.052443 -0.041487 0.127918 +vn -0.555491 0.137895 0.820009 +v -0.049543 -0.015187 0.132918 +vn -0.555491 0.137895 0.820009 +v -0.053443 -0.032087 0.133118 +vn -0.543963 0.135330 0.828125 +v -0.051843 -0.032387 0.134218 +vn -0.568516 0.140788 0.810536 +v -0.051043 -0.015487 0.131918 +vn -0.988936 0.148340 0.000000 +v -0.051043 -0.015487 0.131918 +vn -0.987707 0.150303 -0.042944 +v -0.051043 -0.016087 0.129818 +vn -0.988936 0.148340 0.000000 +v -0.053443 -0.031487 0.131118 +vn -0.988306 0.146055 0.043816 +v -0.053443 -0.032087 0.133118 +vn -0.560337 0.018720 -0.828053 +v -0.051043 -0.016087 0.129818 +vn -0.560337 0.018720 -0.828053 +v -0.051843 -0.031187 0.130018 +vn -0.568873 0.019249 -0.822200 +v -0.053443 -0.031487 0.131118 +vn -0.551253 0.018158 -0.834141 +v -0.049543 -0.016487 0.128818 +vn 0.557507 -0.154794 -0.815613 +v -0.049543 -0.016487 0.128818 +vn 0.557507 -0.154794 -0.815613 +v -0.050343 -0.031487 0.131118 +vn 0.563993 -0.154464 -0.811205 +v -0.051843 -0.031187 0.130018 +vn 0.551179 -0.155105 -0.819844 +v -0.047943 -0.016087 0.129818 +vn 0.988936 -0.148340 0.000000 +v -0.047943 -0.016087 0.129818 +vn 0.989322 -0.140140 0.040040 +v -0.047943 -0.015487 0.131918 +vn 0.988936 -0.148340 0.000000 +v -0.050343 -0.032087 0.133118 +vn 0.986351 -0.157711 -0.047313 +v -0.050343 -0.031487 0.131118 +vn 0.560771 -0.016749 0.827802 +v -0.047943 -0.015487 0.131918 +vn 0.529095 -0.006617 0.848537 +v -0.049543 -0.015187 0.132918 +vn 0.560771 -0.016749 0.827802 +v -0.051843 -0.032387 0.134218 +vn 0.594759 -0.027910 0.803420 +v -0.050343 -0.032087 0.133118 +vn -0.581684 0.407619 0.703911 +v -0.045643 0.018813 0.116518 +vn -0.601862 0.404035 0.688853 +v -0.047143 0.018113 0.115618 +vn -0.581684 0.407619 0.703911 +v -0.051043 -0.015487 0.131918 +vn -0.561176 0.410932 0.718482 +v -0.049543 -0.015187 0.132918 +vn -0.994492 0.095169 -0.043924 +v -0.047143 0.018113 0.115618 +vn -0.994288 0.088803 -0.059202 +v -0.047143 0.016913 0.113818 +vn -0.994492 0.095169 -0.043924 +v -0.051043 -0.016087 0.129818 +vn -0.994427 0.101374 -0.028964 +v -0.051043 -0.015487 0.131918 +vn -0.555458 -0.307129 -0.772747 +v -0.047143 0.016913 0.113818 +vn -0.555458 -0.307129 -0.772747 +v -0.045643 0.016213 0.113018 +vn -0.555458 -0.307129 -0.772747 +v -0.049543 -0.016487 0.128818 +vn -0.583241 -0.297541 -0.755843 +v -0.051043 -0.016087 0.129818 +vn -0.583241 -0.297541 -0.755843 +v -0.047143 0.016913 0.113818 +vn 0.550245 -0.415808 -0.724109 +v -0.045643 0.016213 0.113018 +vn 0.550245 -0.415808 -0.724109 +v -0.047943 -0.016087 0.129818 +vn 0.554573 -0.414721 -0.721426 +v -0.049543 -0.016487 0.128818 +vn 0.545810 -0.416907 -0.726829 +v -0.044043 0.016913 0.113818 +vn 0.994492 -0.095169 0.043924 +v -0.044043 0.016913 0.113818 +vn 0.994490 -0.087223 0.058149 +v -0.044043 0.018113 0.115618 +vn 0.994492 -0.095169 0.043924 +v -0.047943 -0.015487 0.131918 +vn 0.994223 -0.103203 0.029487 +v -0.047943 -0.016087 0.129818 +vn 0.564944 0.306141 0.766235 +v -0.044043 0.018113 0.115618 +vn 0.555116 0.309424 0.772077 +v -0.045643 0.018813 0.116518 +vn 0.555116 0.309424 0.772077 +v -0.047943 -0.015487 0.131918 +vn 0.544890 0.312765 0.777993 +v -0.049543 -0.015187 0.132918 +vn -0.564910 0.585518 0.581417 +v -0.045043 0.038013 0.097618 +vn -0.525876 0.600424 0.602450 +v -0.046643 0.037013 0.097218 +vn -0.564910 0.585518 0.581417 +v -0.047143 0.018113 0.115618 +vn -0.601725 0.569775 0.559717 +v -0.045643 0.018813 0.116518 +vn -0.999809 0.012334 -0.015180 +v -0.046643 0.037013 0.097218 +vn -0.999809 0.012334 -0.015180 +v -0.047143 0.016913 0.113818 +vn -0.999814 0.016040 -0.010693 +v -0.047143 0.018113 0.115618 +vn -0.999761 0.008115 -0.020287 +v -0.046643 0.035013 0.096418 +vn -0.549078 -0.569406 -0.611793 +v -0.046643 0.035013 0.096418 +vn -0.519671 -0.580859 -0.626535 +v -0.045043 0.034013 0.096018 +vn -0.549078 -0.569406 -0.611793 +v -0.045643 0.016213 0.113018 +vn -0.577997 -0.557184 -0.596209 +v -0.047143 0.016913 0.113818 +vn 0.539146 -0.592020 -0.599027 +v -0.045043 0.034013 0.096018 +vn 0.525339 -0.598680 -0.604650 +v -0.043443 0.035013 0.096418 +vn 0.539146 -0.592020 -0.599027 +v -0.044043 0.016913 0.113818 +vn 0.552697 -0.585259 -0.593294 +v -0.045643 0.016213 0.113018 +vn 0.999725 -0.014799 0.018215 +v -0.043443 0.035013 0.096418 +vn 0.999725 -0.014799 0.018215 +v -0.044043 0.018113 0.115618 +vn 0.999705 -0.020196 0.013464 +v -0.044043 0.016913 0.113818 +vn 0.999690 -0.009242 0.023105 +v -0.043443 0.037013 0.097218 +vn 0.551101 0.574816 0.604875 +v -0.043443 0.037013 0.097218 +vn 0.522540 0.589775 0.615725 +v -0.045043 0.038013 0.097618 +vn 0.551101 0.574816 0.604875 +v -0.045643 0.018813 0.116518 +vn 0.578601 0.559438 0.593507 +v -0.044043 0.018113 0.115618 +vn -0.553863 0.828768 0.079874 +v -0.043843 0.040513 0.080318 +vn -0.553863 0.828768 0.079874 +v -0.046643 0.037013 0.097218 +vn -0.543020 0.835599 0.083085 +v -0.045043 0.038013 0.097618 +vn -0.564866 0.821622 0.076571 +v -0.045443 0.039413 0.080318 +vn -0.997387 0.010461 -0.071481 +v -0.045443 0.039413 0.080318 +vn -0.997058 -0.007267 -0.076301 +v -0.045443 0.037313 0.080518 +vn -0.997387 0.010461 -0.071481 +v -0.046643 0.035013 0.096418 +vn -0.997392 0.026806 -0.067014 +v -0.046643 0.037013 0.097218 +vn -0.555492 -0.816098 -0.159415 +v -0.045443 0.037313 0.080518 +vn -0.555492 -0.816098 -0.159415 +v -0.045043 0.034013 0.096018 +vn -0.551631 -0.818590 -0.160045 +v -0.046643 0.035013 0.096418 +vn -0.559342 -0.813588 -0.158781 +v -0.043843 0.036213 0.080518 +vn 0.553716 -0.829183 -0.076510 +v -0.043843 0.036213 0.080518 +vn 0.553716 -0.829183 -0.076510 +v -0.043443 0.035013 0.096418 +vn 0.542170 -0.836753 -0.076791 +v -0.045043 0.034013 0.096018 +vn 0.564880 -0.821645 -0.076222 +v -0.042243 0.037313 0.080518 +vn 0.997387 -0.010461 0.071481 +v -0.042243 0.037313 0.080518 +vn 0.997396 0.006837 0.071792 +v -0.042243 0.039413 0.080318 +vn 0.997387 -0.010461 0.071481 +v -0.043443 0.037013 0.097218 +vn 0.997061 -0.028454 0.071134 +v -0.043443 0.035013 0.096418 +vn 0.559651 0.814039 0.155342 +v -0.042243 0.039413 0.080318 +vn 0.555495 0.816755 0.156003 +v -0.043843 0.040513 0.080318 +vn 0.555495 0.816755 0.156003 +v -0.043443 0.037013 0.097218 +vn 0.551322 0.819452 0.156660 +v -0.045043 0.038013 0.097618 +vn -0.569729 0.717350 -0.401020 +v -0.044343 0.032013 0.065518 +vn -0.569729 0.717350 -0.401020 +v -0.045843 0.031213 0.066218 +vn -0.569729 0.717350 -0.401020 +v -0.045443 0.039413 0.080318 +vn -0.515831 0.750298 -0.413488 +v -0.043843 0.040513 0.080318 +vn -0.515831 0.750298 -0.413488 +v -0.044343 0.032013 0.065518 +vn -0.999669 0.010742 0.023381 +v -0.045843 0.031213 0.066218 +vn -0.999669 0.010742 0.023381 +v -0.045443 0.037313 0.080518 +vn -0.999636 0.002559 0.026870 +v -0.045443 0.039413 0.080318 +vn -0.999625 0.018726 0.019974 +v -0.045843 0.029613 0.067718 +vn -0.548261 -0.705331 0.449352 +v -0.045843 0.029613 0.067718 +vn -0.593907 -0.673505 0.440074 +v -0.044343 0.028813 0.068518 +vn -0.548261 -0.705331 0.449352 +v -0.043843 0.036213 0.080518 +vn -0.503986 -0.733069 0.456736 +v -0.045443 0.037313 0.080518 +vn 0.538514 -0.729177 0.422260 +v -0.044343 0.028813 0.068518 +vn 0.563504 -0.717436 0.409571 +v -0.042743 0.029613 0.067718 +vn 0.538514 -0.729177 0.422260 +v -0.042243 0.037313 0.080518 +vn 0.509829 -0.741570 0.436059 +v -0.043843 0.036213 0.080518 +vn 0.999414 -0.023402 -0.024962 +v -0.042743 0.029613 0.067718 +vn 0.999483 -0.013425 -0.029220 +v -0.042743 0.031213 0.066218 +vn 0.999483 -0.013425 -0.029220 +v -0.042243 0.037313 0.080518 +vn 0.999431 -0.003198 -0.033581 +v -0.042243 0.039413 0.080318 +vn 0.547250 0.717668 -0.430662 +v -0.042743 0.031213 0.066218 +vn 0.547250 0.717668 -0.430662 +v -0.044343 0.032013 0.065518 +vn 0.547250 0.717668 -0.430662 +v -0.043843 0.040513 0.080318 +vn 0.506856 0.737246 -0.446727 +v -0.043843 0.040513 0.080318 +vn 0.506856 0.737246 -0.446727 +v -0.042243 0.039413 0.080318 +vn 0.506856 0.737246 -0.446727 +v -0.042743 0.031213 0.066218 +vn -0.553509 0.571029 -0.606262 +v -0.047243 0.020513 0.057418 +vn -0.531399 0.578486 -0.618845 +v -0.048843 0.020113 0.058418 +vn -0.553509 0.571029 -0.606262 +v -0.045843 0.031213 0.066218 +vn -0.576561 0.562673 -0.592433 +v -0.044343 0.032013 0.065518 +vn -0.975117 0.176101 0.134666 +v -0.048843 0.020113 0.058418 +vn -0.973370 0.202859 0.106768 +v -0.048843 0.019113 0.060318 +vn -0.975117 0.176101 0.134666 +v -0.045843 0.029613 0.067718 +vn -0.975428 0.150684 0.160730 +v -0.045843 0.031213 0.066218 +vn -0.572750 -0.356558 0.738122 +v -0.048843 0.019113 0.060318 +vn -0.576286 -0.354954 0.736140 +v -0.047243 0.018613 0.061318 +vn -0.576286 -0.354954 0.736140 +v -0.045843 0.029613 0.067718 +vn -0.579928 -0.353291 0.734077 +v -0.044343 0.028813 0.068518 +vn 0.578043 -0.573854 0.580137 +v -0.047243 0.018613 0.061318 +vn 0.577687 -0.573989 0.580357 +v -0.045743 0.019113 0.060318 +vn 0.577687 -0.573989 0.580357 +v -0.044343 0.028813 0.068518 +vn 0.577344 -0.574119 0.580570 +v -0.042743 0.029613 0.067718 +vn 0.975117 -0.176101 -0.134666 +v -0.045743 0.019113 0.060318 +vn 0.976035 -0.192572 -0.101353 +v -0.045743 0.020113 0.058418 +vn 0.975117 -0.176101 -0.134666 +v -0.042743 0.031213 0.066218 +vn 0.972723 -0.158653 -0.169231 +v -0.042743 0.029613 0.067718 +vn 0.581851 0.365137 -0.726722 +v -0.045743 0.020113 0.058418 +vn 0.581851 0.365137 -0.726722 +v -0.047243 0.020513 0.057418 +vn 0.581851 0.365137 -0.726722 +v -0.044343 0.032013 0.065518 +vn 0.525621 0.389430 -0.756351 +v -0.042743 0.031213 0.066218 +vn 0.525621 0.389430 -0.756351 +v -0.045743 0.020113 0.058418 +vn -0.549569 0.368842 -0.749620 +v -0.054043 0.002813 0.053718 +vn -0.549569 0.368842 -0.749620 +v -0.048843 0.020113 0.058418 +vn -0.557164 0.369506 -0.743662 +v -0.047243 0.020513 0.057418 +vn -0.542250 0.368174 -0.755257 +v -0.055643 0.002713 0.054818 +vn -0.930605 0.350588 0.105176 +v -0.055643 0.002713 0.054818 +vn -0.927315 0.372596 0.035485 +v -0.055643 0.002513 0.056918 +vn -0.930605 0.350588 0.105176 +v -0.048843 0.019113 0.060318 +vn -0.929033 0.327417 0.172325 +v -0.048843 0.020113 0.058418 +vn -0.540947 0.052833 0.839396 +v -0.055643 0.002513 0.056918 +vn -0.562315 0.068159 0.824109 +v -0.054043 0.002413 0.058018 +vn -0.540947 0.052833 0.839396 +v -0.047243 0.018613 0.061318 +vn -0.520874 0.038709 0.852755 +v -0.048843 0.019113 0.060318 +vn 0.567794 -0.382580 0.728864 +v -0.054043 0.002413 0.058018 +vn 0.541388 -0.372859 0.753575 +v -0.052443 0.002513 0.056918 +vn 0.567794 -0.382580 0.728864 +v -0.045743 0.019113 0.060318 +vn 0.597162 -0.393090 0.699198 +v -0.047243 0.018613 0.061318 +vn 0.932431 -0.346110 -0.103833 +v -0.052443 0.002513 0.056918 +vn 0.934993 -0.353069 -0.033626 +v -0.052443 0.002713 0.054818 +vn 0.932431 -0.346110 -0.103833 +v -0.045743 0.020113 0.058418 +vn 0.924693 -0.336902 -0.177316 +v -0.045743 0.019113 0.060318 +vn 0.555822 -0.041098 -0.830285 +v -0.052443 0.002713 0.054818 +vn 0.555822 -0.041098 -0.830285 +v -0.047243 0.020513 0.057418 +vn 0.547312 -0.037766 -0.836076 +v -0.045743 0.020113 0.058418 +vn 0.564088 -0.044354 -0.824523 +v -0.054043 0.002813 0.053718 +vn -0.673490 0.000000 0.739196 +v -0.016443 -0.117787 0.012318 +vn -0.158071 0.000000 0.987428 +v -0.000443 -0.092587 0.020018 +vn -0.870754 0.000000 0.491720 +v -0.016443 -0.092587 0.012318 +vn 0.157751 0.000000 0.987479 +v -0.000443 -0.117787 0.020018 +vn -0.997980 0.000000 -0.063526 +v -0.020443 -0.117787 -0.005082 +vn -0.927625 0.000000 -0.373513 +v -0.020443 -0.092587 -0.005082 +vn -0.570704 0.000000 -0.821156 +v -0.009343 -0.117787 -0.018982 +vn -0.285276 0.000000 -0.958445 +v -0.009343 -0.092587 -0.018982 +vn 0.000000 0.000000 -1.000000 +v 0.008457 -0.117787 -0.018982 +vn 0.000000 0.000000 -1.000000 +v 0.008457 -0.092587 -0.018982 +vn 0.926913 0.000000 -0.375277 +v 0.019557 -0.117787 -0.005082 +vn 0.997712 0.000000 -0.067607 +v 0.019557 -0.092587 -0.005082 +vn 0.781417 0.000000 -0.624009 +v 0.008457 -0.117787 -0.018982 +vn 0.871630 0.000000 0.490164 +v 0.015657 -0.117787 0.012318 +vn 0.672469 0.000000 0.740126 +v 0.015657 -0.092587 0.012318 +vn 0.000000 1.000000 0.000000 +v 0.019557 -0.092587 -0.005082 +vn 0.000000 1.000000 0.000000 +v -0.000443 -0.092587 0.020018 +vn 0.000000 1.000000 0.000000 +v 0.015657 -0.092587 0.012318 +vn 0.000000 1.000000 0.000000 +v 0.008457 -0.092587 -0.018982 +vn 0.000000 1.000000 0.000000 +v -0.016443 -0.092587 0.012318 +vn 0.000000 1.000000 0.000000 +v -0.009343 -0.092587 -0.018982 +vn 0.000000 1.000000 0.000000 +v -0.020443 -0.092587 -0.005082 +vn 0.000000 -1.000000 0.000000 +v -0.014443 -0.099687 0.010718 +vn 0.000000 -1.000000 0.000000 +v 0.013557 -0.099687 0.010718 +vn 0.000000 -1.000000 0.000000 +v -0.000443 -0.099687 0.017418 +vn 0.000000 -1.000000 0.000000 +v -0.017843 -0.099687 -0.004482 +vn 0.000000 -1.000000 0.000000 +v 0.017057 -0.099687 -0.004482 +vn 0.000000 -1.000000 0.000000 +v -0.008143 -0.099687 -0.016582 +vn 0.000000 -1.000000 0.000000 +v 0.007357 -0.099687 -0.016582 +vn 0.000000 -1.000000 0.000000 +v -0.000443 -0.117787 0.017418 +vn 0.000000 -1.000000 0.000000 +v 0.015657 -0.117787 0.012318 +vn 0.000000 -1.000000 0.000000 +v -0.000443 -0.117787 0.020018 +vn 0.000000 -1.000000 0.000000 +v 0.013557 -0.117787 0.010718 +vn 0.000000 -1.000000 0.000000 +v 0.019557 -0.117787 -0.005082 +vn 0.000000 -1.000000 0.000000 +v 0.017057 -0.117787 -0.004482 +vn 0.000000 -1.000000 0.000000 +v 0.008457 -0.117787 -0.018982 +vn 0.000000 -1.000000 0.000000 +v 0.007357 -0.117787 -0.016582 +vn 0.000000 -1.000000 0.000000 +v -0.009343 -0.117787 -0.018982 +vn 0.000000 -1.000000 0.000000 +v -0.008143 -0.117787 -0.016582 +vn 0.000000 -1.000000 0.000000 +v -0.020443 -0.117787 -0.005082 +vn 0.000000 -1.000000 0.000000 +v -0.017843 -0.117787 -0.004482 +vn 0.000000 -1.000000 0.000000 +v -0.014443 -0.117787 0.010718 +vn 0.000000 -1.000000 0.000000 +v -0.016443 -0.117787 0.012318 +vn 0.431684 0.000000 -0.902025 +v -0.014443 -0.099687 0.010718 +vn 0.431684 0.000000 -0.902025 +v -0.000443 -0.117787 0.017418 +vn 0.431684 0.000000 -0.902025 +v -0.014443 -0.117787 0.010718 +vn 0.431684 0.000000 -0.902025 +v -0.000443 -0.099687 0.017418 +vn 0.975884 0.000000 -0.218290 +v -0.017843 -0.099687 -0.004482 +vn 0.975884 0.000000 -0.218290 +v -0.014443 -0.117787 0.010718 +vn 0.975884 0.000000 -0.218290 +v -0.017843 -0.117787 -0.004482 +vn 0.975884 0.000000 -0.218290 +v -0.014443 -0.099687 0.010718 +vn 0.780239 0.000000 0.625481 +v -0.008143 -0.099687 -0.016582 +vn 0.780239 0.000000 0.625481 +v -0.017843 -0.117787 -0.004482 +vn 0.780239 0.000000 0.625481 +v -0.008143 -0.117787 -0.016582 +vn 0.780239 0.000000 0.625481 +v -0.017843 -0.099687 -0.004482 +vn 0.000000 0.000000 1.000000 +v 0.007357 -0.099687 -0.016582 +vn 0.000000 0.000000 1.000000 +v -0.008143 -0.117787 -0.016582 +vn 0.000000 0.000000 1.000000 +v 0.007357 -0.117787 -0.016582 +vn 0.000000 0.000000 1.000000 +v -0.008143 -0.099687 -0.016582 +vn -0.780239 0.000000 0.625481 +v 0.017057 -0.099687 -0.004482 +vn -0.780239 0.000000 0.625481 +v 0.007357 -0.117787 -0.016582 +vn -0.780239 0.000000 0.625481 +v 0.017057 -0.117787 -0.004482 +vn -0.780239 0.000000 0.625481 +v 0.007357 -0.099687 -0.016582 +vn -0.974499 0.000000 -0.224391 +v 0.013557 -0.099687 0.010718 +vn -0.974499 0.000000 -0.224391 +v 0.017057 -0.117787 -0.004482 +vn -0.974499 0.000000 -0.224391 +v 0.013557 -0.117787 0.010718 +vn -0.974499 0.000000 -0.224391 +v 0.017057 -0.099687 -0.004482 +vn -0.431684 0.000000 -0.902025 +v -0.000443 -0.099687 0.017418 +vn -0.431684 0.000000 -0.902025 +v 0.013557 -0.117787 0.010718 +vn -0.431684 0.000000 -0.902025 +v -0.000443 -0.117787 0.017418 +vn -0.431684 0.000000 -0.902025 +v 0.013557 -0.099687 0.010718 +vn 0.672469 0.000000 0.740126 +v 0.015657 0.117213 0.012318 +vn 0.157751 0.000000 0.987479 +v -0.000443 0.092013 0.020018 +vn 0.871630 0.000000 0.490164 +v 0.015657 0.092013 0.012318 +vn -0.158071 0.000000 0.987428 +v -0.000443 0.117213 0.020018 +vn 0.997712 0.000000 -0.067607 +v 0.019557 0.117213 -0.005082 +vn 0.926913 0.000000 -0.375277 +v 0.019557 0.092013 -0.005082 +vn 0.781417 0.000000 -0.624009 +v 0.008457 0.117213 -0.018982 +vn 0.781417 0.000000 -0.624009 +v 0.008457 0.092013 -0.018982 +vn -0.285276 0.000000 -0.958445 +v -0.009343 0.117213 -0.018982 +vn 0.000000 0.000000 -1.000000 +v 0.008457 0.092013 -0.018982 +vn -0.570704 0.000000 -0.821156 +v -0.009343 0.092013 -0.018982 +vn 0.000000 0.000000 -1.000000 +v 0.008457 0.117213 -0.018982 +vn -0.927625 0.000000 -0.373513 +v -0.020443 0.117213 -0.005082 +vn -0.997980 0.000000 -0.063526 +v -0.020443 0.092013 -0.005082 +vn -0.870754 0.000000 0.491720 +v -0.016443 0.117213 0.012318 +vn -0.673490 0.000000 0.739196 +v -0.016443 0.092013 0.012318 +vn 0.000000 -1.000000 0.000000 +v -0.020443 0.092013 -0.005082 +vn 0.000000 -1.000000 0.000000 +v -0.000443 0.092013 0.020018 +vn 0.000000 -1.000000 0.000000 +v -0.016443 0.092013 0.012318 +vn 0.000000 -1.000000 0.000000 +v -0.009343 0.092013 -0.018982 +vn 0.000000 -1.000000 0.000000 +v 0.015657 0.092013 0.012318 +vn 0.000000 -1.000000 0.000000 +v 0.008457 0.092013 -0.018982 +vn 0.000000 -1.000000 0.000000 +v 0.019557 0.092013 -0.005082 +vn 0.000000 1.000000 0.000000 +v 0.013557 0.099113 0.010718 +vn 0.000000 1.000000 0.000000 +v -0.014443 0.099113 0.010718 +vn 0.000000 1.000000 0.000000 +v -0.000443 0.099113 0.017418 +vn 0.000000 1.000000 0.000000 +v 0.017057 0.099113 -0.004482 +vn 0.000000 1.000000 0.000000 +v -0.017843 0.099113 -0.004482 +vn 0.000000 1.000000 0.000000 +v 0.007357 0.099113 -0.016582 +vn 0.000000 1.000000 0.000000 +v -0.008143 0.099113 -0.016582 +vn 0.000000 1.000000 0.000000 +v -0.000443 0.117213 0.017418 +vn 0.000000 1.000000 0.000000 +v -0.016443 0.117213 0.012318 +vn 0.000000 1.000000 0.000000 +v -0.000443 0.117213 0.020018 +vn 0.000000 1.000000 0.000000 +v -0.014443 0.117213 0.010718 +vn 0.000000 1.000000 0.000000 +v -0.020443 0.117213 -0.005082 +vn 0.000000 1.000000 0.000000 +v -0.017843 0.117213 -0.004482 +vn 0.000000 1.000000 0.000000 +v -0.009343 0.117213 -0.018982 +vn 0.000000 1.000000 0.000000 +v -0.008143 0.117213 -0.016582 +vn 0.000000 1.000000 0.000000 +v 0.008457 0.117213 -0.018982 +vn 0.000000 1.000000 0.000000 +v 0.007357 0.117213 -0.016582 +vn 0.000000 1.000000 0.000000 +v 0.019557 0.117213 -0.005082 +vn 0.000000 1.000000 0.000000 +v 0.017057 0.117213 -0.004482 +vn 0.000000 1.000000 0.000000 +v 0.013557 0.117213 0.010718 +vn 0.000000 1.000000 0.000000 +v 0.015657 0.117213 0.012318 +vn -0.431684 0.000000 -0.902025 +v 0.013557 0.099113 0.010718 +vn -0.431684 0.000000 -0.902025 +v -0.000443 0.117213 0.017418 +vn -0.431684 0.000000 -0.902025 +v 0.013557 0.117213 0.010718 +vn -0.431684 0.000000 -0.902025 +v -0.000443 0.099113 0.017418 +vn -0.974499 0.000000 -0.224391 +v 0.017057 0.099113 -0.004482 +vn -0.974499 0.000000 -0.224391 +v 0.013557 0.117213 0.010718 +vn -0.974499 0.000000 -0.224391 +v 0.017057 0.117213 -0.004482 +vn -0.974499 0.000000 -0.224391 +v 0.013557 0.099113 0.010718 +vn -0.780239 0.000000 0.625481 +v 0.007357 0.099113 -0.016582 +vn -0.780239 0.000000 0.625481 +v 0.017057 0.117213 -0.004482 +vn -0.780239 0.000000 0.625481 +v 0.007357 0.117213 -0.016582 +vn -0.780239 0.000000 0.625481 +v 0.017057 0.099113 -0.004482 +vn 0.000000 0.000000 1.000000 +v -0.008143 0.099113 -0.016582 +vn 0.000000 0.000000 1.000000 +v 0.007357 0.117213 -0.016582 +vn 0.000000 0.000000 1.000000 +v -0.008143 0.117213 -0.016582 +vn 0.000000 0.000000 1.000000 +v 0.007357 0.099113 -0.016582 +vn 0.780239 0.000000 0.625481 +v -0.017843 0.099113 -0.004482 +vn 0.780239 0.000000 0.625481 +v -0.008143 0.117213 -0.016582 +vn 0.780239 0.000000 0.625481 +v -0.017843 0.117213 -0.004482 +vn 0.780239 0.000000 0.625481 +v -0.008143 0.099113 -0.016582 +vn 0.975884 0.000000 -0.218290 +v -0.014443 0.099113 0.010718 +vn 0.975884 0.000000 -0.218290 +v -0.017843 0.117213 -0.004482 +vn 0.975884 0.000000 -0.218290 +v -0.014443 0.117213 0.010718 +vn 0.975884 0.000000 -0.218290 +v -0.017843 0.099113 -0.004482 +vn 0.431684 0.000000 -0.902025 +v -0.000443 0.099113 0.017418 +vn 0.431684 0.000000 -0.902025 +v -0.014443 0.117213 0.010718 +vn 0.431684 0.000000 -0.902025 +v -0.000443 0.117213 0.017418 +vn 0.431684 0.000000 -0.902025 +v -0.014443 0.099113 0.010718 +vn 1.000000 0.000000 0.000000 +v -0.111943 -0.068787 0.031818 +vn 1.000000 0.000000 0.000000 +v -0.111943 0.068713 -0.031782 +vn 1.000000 0.000000 0.000000 +v -0.111943 0.068713 0.031818 +vn 1.000000 0.000000 0.000000 +v -0.111943 -0.068787 -0.031782 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.091487 -0.027982 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.068787 0.031818 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.068713 0.031818 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.078287 0.031818 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.091487 0.027918 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.084487 0.031818 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.078287 -0.031782 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.084487 -0.031782 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.078213 -0.031782 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.091413 -0.027982 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.084413 -0.031782 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.091413 0.027918 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.078213 0.031818 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.084413 0.031818 +vn -1.000000 0.000000 0.000000 +v -0.122043 0.068713 -0.031782 +vn -1.000000 0.000000 0.000000 +v -0.122043 -0.068787 -0.031782 +vn 0.999969 -0.007840 0.000919 +v -0.103743 0.084413 -0.031782 +vn 0.999969 -0.007827 0.000000 +v -0.103743 0.091413 0.027918 +vn 0.999948 -0.010193 0.000579 +v -0.103843 0.078213 -0.031782 +vn 0.999969 -0.007815 -0.000810 +v -0.103843 0.078213 0.031818 +vn 1.000000 0.000000 0.000000 +v -0.103743 0.091413 -0.027982 +vn 0.999451 -0.016120 -0.028934 +v -0.103743 0.084413 0.031818 +vn 0.999969 0.007847 -0.000919 +v -0.103743 -0.084487 0.031818 +vn 0.999969 0.007827 0.000000 +v -0.103743 -0.091487 -0.027982 +vn 0.999948 0.010196 -0.000578 +v -0.103843 -0.078287 0.031818 +vn 0.999969 0.007809 0.000811 +v -0.103843 -0.078287 -0.031782 +vn 1.000000 0.000000 0.000000 +v -0.103743 -0.091487 0.027918 +vn 0.999429 0.016120 0.029695 +v -0.103743 -0.084487 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.103843 0.078213 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.103943 0.068713 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.111943 0.068713 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 0.078213 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 0.068713 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 -0.068787 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.111943 -0.068787 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.111943 0.084413 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.103743 0.084413 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 0.084413 -0.031782 +vn 0.000000 0.000000 1.000000 +v -0.103843 -0.078287 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.103943 -0.068787 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.111943 -0.068787 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.111943 0.068713 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 -0.068787 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 0.068713 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 -0.078287 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 -0.084487 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.111943 -0.084487 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.103743 -0.084487 0.031818 +vn 0.000000 -1.000000 0.000000 +v -0.111943 0.068713 -0.031782 +vn 0.000000 -1.000000 0.000000 +v -0.103943 0.068713 -0.031782 +vn 0.000000 -1.000000 0.000000 +v -0.111943 0.068713 0.031818 +vn 0.000000 -1.000000 0.000000 +v -0.103943 0.068713 0.031818 +vn 0.000000 1.000000 0.000000 +v -0.111943 -0.068787 0.031818 +vn 0.000000 1.000000 0.000000 +v -0.103943 -0.068787 0.031818 +vn 0.000000 1.000000 0.000000 +v -0.111943 -0.068787 -0.031782 +vn 0.000000 1.000000 0.000000 +v -0.103943 -0.068787 -0.031782 +vn 0.256273 -0.001349 -0.966603 +v -0.067643 0.086013 -0.022182 +vn 0.256273 -0.001349 -0.966603 +v -0.103943 0.068713 -0.031782 +vn 0.256876 -0.002704 -0.966440 +v -0.103843 0.078213 -0.031782 +vn 0.255673 0.000000 -0.966763 +v -0.067643 0.076513 -0.022182 +vn 0.258797 0.001362 0.965931 +v -0.067643 -0.086987 0.022118 +vn 0.258797 0.001362 0.965931 +v -0.103943 -0.068787 0.031818 +vn 0.259436 0.002731 0.965756 +v -0.103843 -0.078287 0.031818 +vn 0.258160 0.000000 0.966102 +v -0.067643 -0.077487 0.022118 +vn -0.210635 0.977565 0.000000 +v -0.067643 0.086013 0.022118 +vn -0.210635 0.977565 0.000000 +v -0.103843 0.078213 -0.031782 +vn -0.210635 0.977565 0.000000 +v -0.103843 0.078213 0.031818 +vn -0.210635 0.977565 0.000000 +v -0.067643 0.086013 -0.022182 +vn -0.233678 -0.972314 0.000000 +v -0.067643 -0.086987 -0.022182 +vn -0.233678 -0.972314 0.000000 +v -0.103843 -0.078287 0.031818 +vn -0.233678 -0.972314 0.000000 +v -0.103843 -0.078287 -0.031782 +vn -0.233678 -0.972314 0.000000 +v -0.067643 -0.086987 0.022118 +vn 0.256305 0.001349 -0.966595 +v -0.067643 -0.077487 -0.022182 +vn 0.256305 0.001349 -0.966595 +v -0.103843 -0.078287 -0.031782 +vn 0.256276 0.002698 -0.966600 +v -0.103943 -0.068787 -0.031782 +vn 0.256333 0.000000 -0.966589 +v -0.067643 -0.086987 -0.022182 +vn 0.258765 -0.001362 0.965939 +v -0.067643 0.076513 0.022118 +vn 0.258765 -0.001362 0.965939 +v -0.103843 0.078213 0.031818 +vn 0.258705 -0.002723 0.965953 +v -0.103943 0.068713 0.031818 +vn 0.258825 0.000000 0.965924 +v -0.067643 0.086013 0.022118 +vn 0.210081 -0.977684 0.000000 +v -0.067643 0.076513 -0.022182 +vn 0.210081 -0.977684 0.000000 +v -0.103943 0.068713 0.031818 +vn 0.210081 -0.977684 0.000000 +v -0.103943 0.068713 -0.031782 +vn 0.210081 -0.977684 0.000000 +v -0.067643 0.076513 0.022118 +vn 0.233069 0.972460 0.000000 +v -0.067643 -0.077487 0.022118 +vn 0.233069 0.972460 0.000000 +v -0.103943 -0.068787 -0.031782 +vn 0.233069 0.972460 0.000000 +v -0.103943 -0.068787 0.031818 +vn 0.233069 0.972460 0.000000 +v -0.067643 -0.077487 -0.022182 +vn 0.091478 0.000000 -0.995807 +v -0.029543 0.090213 -0.018682 +vn 0.091478 0.000000 -0.995807 +v -0.067643 0.076513 -0.022182 +vn 0.091478 0.000000 -0.995807 +v -0.067643 0.086013 -0.022182 +vn 0.091478 0.000000 -0.995807 +v -0.029543 0.080713 -0.018682 +vn 0.091478 0.000000 0.995807 +v -0.029543 -0.090587 0.018618 +vn 0.091478 0.000000 0.995807 +v -0.067643 -0.077487 0.022118 +vn 0.091478 0.000000 0.995807 +v -0.067643 -0.086987 0.022118 +vn 0.091478 0.000000 0.995807 +v -0.029543 -0.081087 0.018618 +vn -0.109573 0.993979 0.000000 +v -0.029543 0.090213 0.018618 +vn -0.109573 0.993979 0.000000 +v -0.067643 0.086013 -0.022182 +vn -0.109573 0.993979 0.000000 +v -0.067643 0.086013 0.022118 +vn -0.109573 0.993979 0.000000 +v -0.029543 0.090213 -0.018682 +vn -0.094069 -0.995566 0.000000 +v -0.029543 -0.090587 -0.018682 +vn -0.094069 -0.995566 0.000000 +v -0.067643 -0.086987 0.022118 +vn -0.094069 -0.995566 0.000000 +v -0.067643 -0.086987 -0.022182 +vn -0.094069 -0.995566 0.000000 +v -0.029543 -0.090587 0.018618 +vn 0.091478 0.000000 -0.995807 +v -0.029543 -0.081087 -0.018682 +vn 0.091478 0.000000 -0.995807 +v -0.067643 -0.086987 -0.022182 +vn 0.091478 0.000000 -0.995807 +v -0.067643 -0.077487 -0.022182 +vn 0.091478 0.000000 -0.995807 +v -0.029543 -0.090587 -0.018682 +vn 0.091478 0.000000 0.995807 +v -0.029543 0.080713 0.018618 +vn 0.091478 0.000000 0.995807 +v -0.067643 0.086013 0.022118 +vn 0.091478 0.000000 0.995807 +v -0.067643 0.076513 0.022118 +vn 0.091478 0.000000 0.995807 +v -0.029543 0.090213 0.018618 +vn 0.109572 -0.993979 0.000000 +v -0.029543 0.080713 -0.018682 +vn 0.109572 -0.993979 0.000000 +v -0.067643 0.076513 0.022118 +vn 0.109572 -0.993979 0.000000 +v -0.067643 0.076513 -0.022182 +vn 0.109572 -0.993979 0.000000 +v -0.029543 0.080713 0.018618 +vn 0.094069 0.995566 0.000000 +v -0.029543 -0.081087 0.018618 +vn 0.094069 0.995566 0.000000 +v -0.067643 -0.077487 -0.022182 +vn 0.094069 0.995566 0.000000 +v -0.067643 -0.077487 0.022118 +vn 0.094069 0.995566 0.000000 +v -0.029543 -0.081087 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.001243 0.090213 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.029543 0.080713 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.029543 0.090213 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.001243 0.080713 -0.018682 +vn 0.000000 0.000000 1.000000 +v -0.001243 -0.090587 0.018618 +vn 0.000000 0.000000 1.000000 +v -0.029543 -0.081087 0.018618 +vn 0.000000 0.000000 1.000000 +v -0.029543 -0.090587 0.018618 +vn 0.000000 0.000000 1.000000 +v -0.001243 -0.081087 0.018618 +vn 0.000000 1.000000 0.000000 +v -0.001243 0.090213 0.018618 +vn 0.000000 1.000000 0.000000 +v -0.029543 0.090213 -0.018682 +vn 0.000000 1.000000 0.000000 +v -0.029543 0.090213 0.018618 +vn 0.000000 1.000000 0.000000 +v -0.001243 0.090213 -0.018682 +vn 0.000000 -1.000000 0.000000 +v -0.001243 -0.090587 -0.018682 +vn 0.000000 -1.000000 0.000000 +v -0.029543 -0.090587 0.018618 +vn 0.000000 -1.000000 0.000000 +v -0.029543 -0.090587 -0.018682 +vn 0.000000 -1.000000 0.000000 +v -0.001243 -0.090587 0.018618 +vn 0.000000 0.000000 -1.000000 +v -0.001243 -0.081087 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.029543 -0.090587 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.029543 -0.081087 -0.018682 +vn 0.000000 0.000000 -1.000000 +v -0.001243 -0.090587 -0.018682 +vn 0.000000 0.000000 1.000000 +v -0.001243 0.080713 0.018618 +vn 0.000000 0.000000 1.000000 +v -0.029543 0.090213 0.018618 +vn 0.000000 0.000000 1.000000 +v -0.029543 0.080713 0.018618 +vn 0.000000 0.000000 1.000000 +v -0.001243 0.090213 0.018618 +vn 0.000000 -1.000000 0.000000 +v -0.001243 0.080713 -0.018682 +vn 0.000000 -1.000000 0.000000 +v -0.029543 0.080713 0.018618 +vn 0.000000 -1.000000 0.000000 +v -0.029543 0.080713 -0.018682 +vn 0.000000 -1.000000 0.000000 +v -0.001243 0.080713 0.018618 +vn 0.000000 1.000000 0.000000 +v -0.001243 -0.081087 0.018618 +vn 0.000000 1.000000 0.000000 +v -0.029543 -0.081087 -0.018682 +vn 0.000000 1.000000 0.000000 +v -0.029543 -0.081087 0.018618 +vn 0.000000 1.000000 0.000000 +v -0.001243 -0.081087 -0.018682 +vn 1.000000 0.000000 0.000000 +v -0.001243 0.080713 -0.018682 +vn 1.000000 0.000000 0.000000 +v -0.001243 0.090213 0.018618 +vn 1.000000 0.000000 0.000000 +v -0.001243 0.080713 0.018618 +vn 1.000000 0.000000 0.000000 +v -0.001243 0.090213 -0.018682 +vn 1.000000 0.000000 0.000000 +v -0.001243 -0.081087 0.018618 +vn 1.000000 0.000000 0.000000 +v -0.001243 -0.090587 -0.018682 +vn 1.000000 0.000000 0.000000 +v -0.001243 -0.081087 -0.018682 +vn 1.000000 0.000000 0.000000 +v -0.001243 -0.090587 0.018618 +vn 0.000000 0.477092 -0.878853 +v -0.111943 0.084413 -0.031782 +vn 0.000000 0.477092 -0.878853 +v -0.122043 0.091413 -0.027982 +vn 0.000000 0.477092 -0.878853 +v -0.111943 0.091413 -0.027982 +vn 0.000000 0.477092 -0.878853 +v -0.122043 0.084413 -0.031782 +vn 0.000000 0.477092 -0.878853 +v -0.103743 0.091413 -0.027982 +vn 0.000000 0.477092 -0.878853 +v -0.103743 0.084413 -0.031782 +vn 0.000000 1.000000 0.000000 +v -0.111943 0.091413 -0.027982 +vn 0.000000 1.000000 0.000000 +v -0.122043 0.091413 0.027918 +vn 0.000000 1.000000 0.000000 +v -0.111943 0.091413 0.027918 +vn 0.000000 1.000000 0.000000 +v -0.122043 0.091413 -0.027982 +vn 0.000000 1.000000 0.000000 +v -0.103743 0.091413 0.027918 +vn 0.000000 1.000000 0.000000 +v -0.103743 0.091413 -0.027982 +vn 0.000000 0.486702 0.873568 +v -0.111943 0.091413 0.027918 +vn 0.000000 0.486702 0.873568 +v -0.122043 0.084413 0.031818 +vn 0.000000 0.486702 0.873568 +v -0.111943 0.084413 0.031818 +vn 0.000000 0.486702 0.873568 +v -0.122043 0.091413 0.027918 +vn 0.000000 0.486702 0.873568 +v -0.103743 0.084413 0.031818 +vn 0.000000 0.486702 0.873568 +v -0.103743 0.091413 0.027918 +vn 0.000000 0.000000 1.000000 +v -0.103843 0.078213 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.103743 0.084413 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.111943 0.084413 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 0.078213 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 0.068713 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.111943 0.068713 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.122043 0.084413 0.031818 +vn 0.000000 0.000000 1.000000 +v -0.103943 0.068713 0.031818 +vn 0.000000 -0.486702 0.873568 +v -0.111943 -0.084487 0.031818 +vn 0.000000 -0.486702 0.873568 +v -0.122043 -0.091487 0.027918 +vn 0.000000 -0.486702 0.873568 +v -0.111943 -0.091487 0.027918 +vn 0.000000 -0.486702 0.873568 +v -0.122043 -0.084487 0.031818 +vn 0.000000 -0.486702 0.873568 +v -0.103743 -0.091487 0.027918 +vn 0.000000 -0.486702 0.873568 +v -0.103743 -0.084487 0.031818 +vn 0.000000 -1.000000 0.000000 +v -0.111943 -0.091487 0.027918 +vn 0.000000 -1.000000 0.000000 +v -0.122043 -0.091487 -0.027982 +vn 0.000000 -1.000000 0.000000 +v -0.111943 -0.091487 -0.027982 +vn 0.000000 -1.000000 0.000000 +v -0.122043 -0.091487 0.027918 +vn 0.000000 -1.000000 0.000000 +v -0.103743 -0.091487 -0.027982 +vn 0.000000 -1.000000 0.000000 +v -0.103743 -0.091487 0.027918 +vn 0.000000 -0.477092 -0.878853 +v -0.111943 -0.091487 -0.027982 +vn 0.000000 -0.477092 -0.878853 +v -0.122043 -0.084487 -0.031782 +vn 0.000000 -0.477092 -0.878853 +v -0.111943 -0.084487 -0.031782 +vn 0.000000 -0.477092 -0.878853 +v -0.122043 -0.091487 -0.027982 +vn 0.000000 -0.477092 -0.878853 +v -0.103743 -0.084487 -0.031782 +vn 0.000000 -0.477092 -0.878853 +v -0.103743 -0.091487 -0.027982 +vn 0.000000 0.000000 -1.000000 +v -0.103843 -0.078287 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.103743 -0.084487 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.111943 -0.084487 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 -0.078287 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 -0.068787 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.111943 -0.068787 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.122043 -0.084487 -0.031782 +vn 0.000000 0.000000 -1.000000 +v -0.103943 -0.068787 -0.031782 +vn 0.000000 -0.995579 -0.093923 +v -0.052443 0.002713 0.054818 +vn 0.000000 -0.995634 -0.093341 +v -0.055643 0.002713 0.054818 +vn 0.000000 -0.995893 -0.090536 +v -0.054043 0.002813 0.053718 +vn 0.000000 -0.995579 -0.093923 +v -0.055643 0.002513 0.056918 +vn 0.000000 -0.995634 -0.093341 +v -0.052443 0.002513 0.056918 +vn 0.000000 -0.995893 -0.090536 +v -0.054043 0.002413 0.058018 +vn -0.309168 0.541044 0.782104 +v -0.024843 0.066113 0.063418 +vn 0.000000 0.585890 -0.810390 +v -0.065743 0.049013 0.053718 +vn 0.000000 0.950853 0.309644 +v -0.065743 0.049013 0.123218 +vn 0.938659 -0.129992 0.319408 +v 0.019957 -0.000087 0.003818 +vn 0.977881 -0.043825 0.204517 +v 0.019225 -0.000087 0.007318 +vn 0.948546 -0.227119 0.220630 +v 0.019225 0.006913 0.008818 +vn 0.612161 0.553782 0.564432 +v 0.019957 -0.049387 -0.014182 +vn 0.612161 0.553782 0.564432 +v 0.018313 -0.048487 -0.013282 +vn 0.612161 -0.564432 0.553782 +v 0.018313 -0.021087 -0.013282 +vn 0.675118 -0.624442 -0.392794 +v 0.018313 -0.021087 0.014118 +vn 0.636708 0.580749 -0.507281 +v 0.019957 -0.049387 0.015018 +vn 0.590438 0.565233 0.576103 +v 0.019957 0.020613 -0.014182 +vn 0.589876 -0.579121 0.562731 +v 0.018313 0.048913 -0.013282 +vn 0.614022 -0.598531 -0.514527 +v 0.018313 0.048913 0.014118 +vn 0.614981 0.593881 -0.518752 +v 0.019957 0.020613 0.015018 +vn 1.000000 0.000000 0.000000 +v 0.019957 -0.047687 0.029718 +vn -0.583241 -0.297541 -0.755843 +v -0.049543 -0.016487 0.128818 +vn -0.515831 0.750298 -0.413488 +v -0.045443 0.039413 0.080318 +vn 0.525621 0.389430 -0.756351 +v -0.044343 0.032013 0.065518 +vn 0.781417 0.000000 -0.624009 +v 0.008457 -0.092587 -0.018982 +vn 0.612179 -0.559123 -0.559123 +v 0.018313 -0.021087 0.014118 +# 1737 vertices, 0 vertices normals + +f 1//1 2//2 3//3 +f 1//1 4//4 2//2 +f 5//5 3//3 6//6 +f 5//5 1//1 3//3 +f 7//7 8//8 9//9 +f 7//7 10//10 8//8 +f 11//11 9//9 12//12 +f 11//11 7//7 9//9 +f 13//13 12//12 14//14 +f 13//13 11//11 12//12 +f 15//15 14//14 16//16 +f 15//15 13//13 14//14 +f 4//4 16//16 2//2 +f 4//4 15//15 16//16 +f 17//17 18//18 19//19 +f 17//17 20//20 18//18 +f 21//21 22//22 23//23 +f 21//21 24//24 22//22 +f 25//25 26//26 27//27 +f 25//25 28//28 26//26 +f 29//29 30//30 31//31 +f 29//29 32//32 30//30 +f 33//33 34//34 35//35 +f 33//33 36//36 34//34 +f 37//37 38//38 39//39 +f 37//37 40//40 38//38 +f 41//41 42//42 43//43 +f 41//41 44//44 42//42 +f 45//45 46//46 47//47 +f 48//48 49//49 50//50 +f 51//51 52//52 53//53 +f 51//51 54//54 52//52 +f 55//55 56//56 57//57 +f 55//55 58//58 56//56 +f 59//59 60//60 61//61 +f 61//61 62//62 59//59 +f 63//63 64//64 65//65 +f 65//65 66//66 63//63 +f 67//67 68//68 69//69 +f 67//67 70//70 68//68 +f 71//71 72//72 73//73 +f 74//74 75//75 76//76 +f 77//77 78//78 79//79 +f 79//79 80//80 77//77 +f 81//81 82//82 83//83 +f 83//83 84//84 81//81 +f 85//85 86//86 87//87 +f 87//87 88//88 85//85 +f 89//89 90//90 91//91 +f 91//91 92//92 89//89 +f 93//93 94//94 95//95 +f 95//95 96//96 93//93 +f 97//97 98//98 99//99 +f 97//97 100//100 98//98 +f 101//101 102//102 103//103 +f 103//103 104//104 101//101 +f 105//105 106//106 107//107 +f 105//105 108//108 106//106 +f 109//109 110//110 111//111 +f 109//109 112//112 110//110 +f 113//113 114//114 115//115 +f 113//113 116//116 114//114 +f 117//117 118//118 119//119 +f 117//117 120//120 118//118 +f 121//121 122//122 123//123 +f 121//121 124//124 122//122 +f 125//125 126//126 127//127 +f 125//125 128//128 126//126 +f 129//129 130//130 131//131 +f 129//129 132//132 130//130 +f 133//133 134//134 135//135 +f 133//133 136//136 134//134 +f 137//137 138//138 139//139 +f 137//137 140//140 138//138 +f 141//141 142//142 143//143 +f 141//141 144//144 142//142 +f 145//145 146//146 147//147 +f 145//145 148//148 146//146 +f 149//149 150//150 151//151 +f 149//149 152//152 150//150 +f 153//153 154//154 155//155 +f 153//153 156//156 154//154 +f 157//157 158//158 159//159 +f 157//157 160//160 158//158 +f 161//161 162//162 163//163 +f 164//164 162//162 161//161 +f 164//164 165//165 162//162 +f 166//166 165//165 164//164 +f 166//166 167//167 165//165 +f 168//168 169//169 170//170 +f 168//168 171//171 169//169 +f 172//172 171//171 168//168 +f 172//172 173//173 171//171 +f 174//174 1717//1717 175//175 +f 174//174 176//176 1717//1717 +f 177//177 176//176 174//174 +f 177//177 178//178 176//176 +f 179//179 178//178 177//177 +f 179//179 180//180 178//178 +f 181//181 182//182 183//183 +f 181//181 184//184 182//182 +f 170//170 184//184 181//181 +f 170//170 169//169 184//184 +f 185//185 186//186 187//187 +f 188//188 186//186 185//185 +f 188//188 189//189 186//186 +f 190//190 189//189 188//188 +f 190//190 191//191 189//189 +f 192//192 193//193 194//194 +f 195//195 193//193 192//192 +f 195//195 196//196 193//193 +f 197//197 196//196 195//195 +f 197//197 198//198 196//196 +f 199//199 200//200 201//201 +f 199//199 201//201 202//202 +f 203//203 199//199 202//202 +f 204//204 201//201 200//200 +f 205//205 200//200 206//206 +f 205//205 204//204 200//200 +f 207//207 206//206 208//208 +f 207//207 205//205 206//206 +f 209//209 208//208 210//210 +f 209//209 207//207 208//208 +f 211//211 202//202 212//212 +f 211//211 203//203 202//202 +f 211//211 209//209 210//210 +f 211//211 212//212 209//209 +f 213//213 214//214 215//215 +f 213//213 216//216 214//214 +f 217//217 218//218 219//219 +f 217//217 220//220 218//218 +f 221//221 222//222 223//223 +f 221//221 224//224 222//222 +f 225//225 226//226 227//227 +f 225//225 228//228 226//226 +f 229//229 230//230 231//231 +f 229//229 232//232 230//230 +f 233//233 234//234 235//235 +f 233//233 236//236 234//234 +f 237//237 238//238 239//239 +f 237//237 240//240 238//238 +f 241//241 242//242 243//243 +f 241//241 244//244 242//242 +f 245//245 246//246 247//247 +f 245//245 248//248 246//246 +f 249//249 250//250 251//251 +f 252//252 250//250 249//249 +f 252//252 253//253 250//250 +f 252//252 249//249 254//254 +f 255//255 256//256 257//257 +f 255//255 258//258 256//256 +f 259//259 260//260 261//261 +f 262//262 260//260 259//259 +f 262//262 263//263 260//260 +f 262//262 259//259 264//264 +f 265//265 266//266 267//267 +f 267//267 268//268 265//265 +f 269//269 270//270 271//271 +f 271//271 272//272 269//269 +f 273//273 274//274 275//275 +f 273//273 276//276 274//274 +f 277//277 275//275 278//278 +f 277//277 273//273 275//275 +f 279//279 280//280 281//281 +f 279//279 282//282 280//280 +f 283//283 281//281 284//284 +f 283//283 279//279 281//281 +f 285//285 284//284 286//286 +f 285//285 283//283 284//284 +f 287//287 288//288 289//289 +f 287//287 290//290 288//288 +f 276//276 289//289 274//274 +f 276//276 287//287 289//289 +f 291//291 292//292 293//293 +f 294//294 292//292 291//291 +f 294//294 295//295 292//292 +f 296//296 295//295 294//294 +f 296//296 297//297 295//295 +f 298//298 299//299 300//300 +f 301//301 299//299 298//298 +f 301//301 302//302 299//299 +f 303//303 302//302 301//301 +f 303//303 304//304 302//302 +f 305//305 306//306 307//307 +f 305//305 307//307 308//308 +f 306//306 305//305 309//309 +f 310//310 309//309 311//311 +f 310//310 306//306 309//309 +f 312//312 311//311 313//313 +f 312//312 310//310 311//311 +f 314//314 313//313 315//315 +f 314//314 312//312 313//313 +f 316//316 315//315 317//317 +f 316//316 314//314 315//315 +f 308//308 307//307 318//318 +f 308//308 316//316 317//317 +f 308//308 318//318 316//316 +f 319//319 320//320 321//321 +f 319//319 322//322 320//320 +f 323//323 324//324 325//325 +f 323//323 326//326 324//324 +f 327//327 328//328 329//329 +f 327//327 330//330 328//328 +f 331//331 332//332 333//333 +f 331//331 334//334 332//332 +f 335//335 336//336 337//337 +f 335//335 338//338 336//336 +f 339//339 340//340 341//341 +f 339//339 342//342 340//340 +f 343//343 344//344 345//345 +f 343//343 346//346 344//344 +f 347//347 348//348 349//349 +f 347//347 350//350 348//348 +f 351//351 352//352 353//353 +f 351//351 354//354 352//352 +f 355//355 356//356 357//357 +f 355//355 358//358 356//356 +f 359//359 360//360 361//361 +f 361//361 362//362 359//359 +f 363//363 364//364 365//365 +f 365//365 366//366 363//363 +f 367//367 368//368 369//369 +f 370//370 368//368 367//367 +f 370//370 371//371 368//368 +f 370//370 367//367 372//372 +f 373//373 374//374 375//375 +f 376//376 374//374 373//373 +f 376//376 377//377 374//374 +f 376//376 373//373 378//378 +f 379//379 380//380 381//381 +f 379//379 382//382 380//380 +f 383//383 384//384 385//385 +f 383//383 386//386 384//384 +f 387//387 388//388 389//389 +f 387//387 390//390 388//388 +f 391//391 392//392 393//393 +f 391//391 394//394 392//392 +f 395//395 396//396 397//397 +f 395//395 398//398 396//396 +f 399//399 400//400 401//401 +f 399//399 402//402 400//400 +f 403//403 404//404 405//405 +f 403//403 406//406 404//404 +f 407//407 406//406 403//403 +f 407//407 408//408 406//406 +f 409//409 408//408 407//407 +f 409//409 410//410 408//408 +f 411//411 412//412 413//413 +f 411//411 414//414 412//412 +f 415//415 414//414 411//411 +f 415//415 416//416 414//414 +f 417//417 416//416 415//415 +f 417//417 418//418 416//416 +f 419//419 420//420 421//421 +f 419//419 422//422 420//420 +f 423//423 424//424 425//425 +f 423//423 426//426 424//424 +f 427//427 428//428 429//429 +f 427//427 430//430 428//428 +f 431//431 432//432 433//433 +f 431//431 434//434 432//432 +f 435//435 436//436 437//437 +f 435//435 438//438 436//436 +f 439//439 440//440 441//441 +f 439//439 442//442 440//440 +f 443//443 444//444 445//445 +f 443//443 446//446 444//444 +f 447//447 448//448 449//449 +f 447//447 450//450 448//448 +f 451//451 452//452 453//453 +f 451//451 454//454 452//452 +f 455//455 453//453 456//456 +f 455//455 451//451 453//453 +f 457//457 458//458 459//459 +f 457//457 460//460 458//458 +f 461//461 459//459 462//462 +f 461//461 457//457 459//459 +f 463//463 462//462 464//464 +f 463//463 461//461 462//462 +f 454//454 464//464 452//452 +f 454//454 463//463 464//464 +f 465//465 466//466 467//467 +f 465//465 468//468 466//466 +f 469//469 1718//1718 470//470 +f 469//469 471//471 1718//1718 +f 472//472 470//470 473//473 +f 472//472 469//469 470//470 +f 474//474 475//475 476//476 +f 474//474 477//477 475//475 +f 478//478 479//479 480//480 +f 478//478 481//481 479//479 +f 482//482 480//480 483//483 +f 482//482 478//478 480//480 +f 484//484 485//485 486//486 +f 484//484 487//487 485//485 +f 488//488 486//486 489//489 +f 488//488 484//484 486//486 +f 490//490 489//489 491//491 +f 490//490 488//488 489//489 +f 468//468 1719//1719 466//466 +f 468//468 492//492 1719//1719 +f 493//493 494//494 495//495 +f 493//493 496//496 494//494 +f 497//497 496//496 493//493 +f 497//497 498//498 496//496 +f 499//499 498//498 497//497 +f 499//499 500//500 498//498 +f 501//501 500//500 499//499 +f 501//501 502//502 500//500 +f 503//503 504//504 505//505 +f 503//503 506//506 504//504 +f 507//507 506//506 503//503 +f 507//507 508//508 506//506 +f 509//509 506//506 510//510 +f 510//510 506//506 508//508 +f 511//511 509//509 512//512 +f 512//512 509//509 510//510 +f 513//513 511//511 514//514 +f 514//514 511//511 512//512 +f 515//515 513//513 516//516 +f 516//516 513//513 514//514 +f 517//517 515//515 518//518 +f 518//518 515//515 516//516 +f 519//519 517//517 520//520 +f 520//520 517//517 518//518 +f 503//503 519//519 521//521 +f 521//521 519//519 520//520 +f 522//522 507//507 503//503 +f 522//522 503//503 521//521 +f 523//523 524//524 525//525 +f 523//523 526//526 524//524 +f 527//527 528//528 529//529 +f 527//527 530//530 528//528 +f 531//531 532//532 533//533 +f 531//531 534//534 532//532 +f 535//535 536//536 537//537 +f 535//535 538//538 536//536 +f 539//539 540//540 541//541 +f 539//539 542//542 540//540 +f 543//543 544//544 545//545 +f 543//543 546//546 544//544 +f 547//547 548//548 549//549 +f 547//547 550//550 548//548 +f 551//551 552//552 553//553 +f 551//551 554//554 552//552 +f 555//555 556//556 557//557 +f 555//555 558//558 556//556 +f 559//559 560//560 561//561 +f 559//559 562//562 560//560 +f 563//563 564//564 565//565 +f 563//563 566//566 564//564 +f 567//567 566//566 563//563 +f 567//567 568//568 566//566 +f 569//569 568//568 567//567 +f 569//569 570//570 568//568 +f 571//571 570//570 569//569 +f 571//571 572//572 570//570 +f 573//573 574//574 575//575 +f 573//573 576//576 574//574 +f 577//577 575//575 578//578 +f 577//577 573//573 575//575 +f 579//579 578//578 580//580 +f 579//579 577//577 578//578 +f 581//581 580//580 582//582 +f 581//581 579//579 580//580 +f 583//583 582//582 584//584 +f 583//583 581//581 582//582 +f 585//585 584//584 586//586 +f 585//585 583//583 584//584 +f 587//587 586//586 588//588 +f 587//587 585//585 586//586 +f 589//589 590//590 591//591 +f 592//592 593//593 589//589 +f 589//589 593//593 590//590 +f 594//594 593//593 592//592 +f 594//594 595//595 593//593 +f 596//596 597//597 598//598 +f 599//599 597//597 596//596 +f 599//599 600//600 597//597 +f 601//601 600//600 599//599 +f 597//597 600//600 602//602 +f 603//603 604//604 605//605 +f 605//605 606//606 603//603 +f 607//607 1721//1721 608//608 +f 1720//1720 609//609 1722//1722 +f 610//610 611//611 612//612 +f 612//612 613//613 610//610 +f 613//613 612//612 614//614 +f 614//614 615//615 613//613 +f 609//609 616//616 617//617 +f 617//617 1722//1722 609//609 +f 610//610 617//617 616//616 +f 616//616 611//611 610//610 +f 618//618 619//619 620//620 +f 618//618 621//621 619//619 +f 622//622 621//621 618//618 +f 622//622 623//623 621//621 +f 624//624 623//623 622//622 +f 624//624 625//625 623//623 +f 606//606 626//626 627//627 +f 627//627 603//603 606//606 +f 614//614 627//627 626//626 +f 626//626 615//615 614//614 +f 628//628 629//629 630//630 +f 631//631 1724//1724 1723//1723 +f 633//633 634//634 635//635 +f 633//633 636//636 634//634 +f 637//637 638//638 639//639 +f 640//640 641//641 1725//1725 +f 642//642 636//636 643//643 +f 642//642 634//634 636//636 +f 1737//1737 645//645 646//646 +f 647//647 648//648 644//644 +f 649//649 650//650 651//651 +f 649//649 652//652 650//650 +f 653//653 654//654 655//655 +f 1727//1727 656//656 657//657 +f 651//651 658//658 659//659 +f 651//651 650//650 658//658 +f 641//641 660//660 661//661 +f 661//661 1725//1725 641//641 +f 662//662 663//663 664//664 +f 662//662 665//665 663//663 +f 1726//1726 666//666 667//667 +f 668//668 645//645 1737//1737 +f 669//669 665//665 670//670 +f 669//669 663//663 665//665 +f 632//632 671//671 672//672 +f 673//673 1723//1723 1724//1724 +f 674//674 675//675 676//676 +f 674//674 677//677 675//675 +f 663//663 678//678 664//664 +f 663//663 642//642 678//678 +f 669//669 642//642 663//663 +f 669//669 634//634 642//642 +f 679//679 634//634 669//669 +f 679//679 635//635 634//634 +f 649//649 635//635 679//679 +f 649//649 680//680 635//635 +f 651//651 680//680 649//649 +f 651//651 674//674 680//680 +f 659//659 674//674 651//651 +f 659//659 677//677 674//674 +f 681//681 677//677 659//659 +f 681//681 682//682 677//677 +f 1727//1727 683//683 684//684 +f 684//684 656//656 1727//1727 +f 685//685 677//677 682//682 +f 685//685 675//675 677//677 +f 686//686 687//687 688//688 +f 688//688 689//689 686//686 +f 690//690 688//688 687//687 +f 687//687 691//691 690//690 +f 692//692 693//693 694//694 +f 694//694 695//695 692//692 +f 695//695 694//694 696//696 +f 696//696 697//697 695//695 +f 691//691 698//698 699//699 +f 699//699 690//690 691//691 +f 692//692 699//699 698//698 +f 698//698 693//693 692//692 +f 700//700 701//701 702//702 +f 700//700 703//703 701//701 +f 704//704 703//703 700//700 +f 704//704 705//705 703//703 +f 706//706 705//705 704//704 +f 706//706 707//707 705//705 +f 689//689 708//708 709//709 +f 709//709 686//686 689//689 +f 696//696 709//709 708//708 +f 708//708 697//697 696//696 +f 710//710 711//711 712//712 +f 713//713 714//714 1728//1728 +f 715//715 716//716 717//717 +f 715//715 718//718 716//716 +f 719//719 720//720 721//721 +f 722//722 723//723 1729//1729 +f 724//724 718//718 725//725 +f 724//724 716//716 718//718 +f 1730//1730 727//727 728//728 +f 729//729 730//730 726//726 +f 731//731 732//732 733//733 +f 731//731 734//734 732//732 +f 735//735 736//736 737//737 +f 1731//1731 738//738 739//739 +f 733//733 740//740 741//741 +f 733//733 732//732 740//740 +f 723//723 742//742 743//743 +f 743//743 1729//1729 723//723 +f 742//742 744//744 745//745 +f 745//745 743//743 742//742 +f 1730//1730 746//746 747//747 +f 747//747 727//727 1730//1730 +f 746//746 745//745 744//744 +f 744//744 747//747 746//746 +f 714//714 748//748 749//749 +f 749//749 1728//1728 714//714 +f 748//748 750//750 751//751 +f 751//751 749//749 748//748 +f 752//752 753//753 754//754 +f 752//752 724//724 753//753 +f 755//755 724//724 752//752 +f 755//755 716//716 724//724 +f 756//756 716//716 755//755 +f 756//756 717//717 716//716 +f 731//731 717//717 756//756 +f 731//731 757//757 717//717 +f 733//733 757//757 731//731 +f 733//733 758//758 757//757 +f 741//741 758//758 733//733 +f 741//741 759//759 758//758 +f 760//760 759//759 741//741 +f 760//760 761//761 759//759 +f 1731//1731 762//762 763//763 +f 763//763 738//738 1731//1731 +f 762//762 751//751 750//750 +f 750//750 763//763 762//762 +f 764//764 765//765 766//766 +f 767//767 768//768 769//769 +f 770//770 771//771 767//767 +f 767//767 771//771 768//768 +f 772//772 770//770 767//767 +f 773//773 774//774 772//772 +f 772//772 774//774 770//770 +f 775//775 773//773 772//772 +f 776//776 773//773 775//775 +f 776//776 777//777 773//773 +f 778//778 779//779 780//780 +f 778//778 781//781 779//779 +f 782//782 780//780 783//783 +f 775//775 778//778 780//780 +f 784//784 781//781 785//785 +f 784//784 779//779 781//781 +f 786//786 787//787 788//788 +f 787//787 768//768 788//788 +f 789//789 769//769 768//768 +f 790//790 791//791 792//792 +f 790//790 793//793 791//791 +f 794//794 790//790 792//792 +f 794//794 795//795 790//790 +f 796//796 795//795 794//794 +f 796//796 797//797 795//795 +f 798//798 796//796 799//799 +f 799//799 796//796 794//794 +f 800//800 798//798 801//801 +f 801//801 798//798 799//799 +f 802//802 800//800 803//803 +f 803//803 800//800 801//801 +f 804//804 802//802 805//805 +f 805//805 802//802 803//803 +f 806//806 804//804 807//807 +f 807//807 804//804 805//805 +f 808//808 806//806 807//807 +f 786//786 809//809 808//808 +f 808//808 809//809 806//806 +f 786//786 808//808 810//810 +f 786//786 810//810 787//787 +f 768//768 787//787 811//811 +f 789//789 768//768 811//811 +f 785//785 789//789 812//812 +f 812//812 789//789 811//811 +f 785//785 812//812 813//813 +f 784//784 813//813 814//814 +f 784//784 785//785 813//813 +f 815//815 791//791 793//793 +f 816//816 817//817 1732//1732 +f 819//819 818//818 820//820 +f 821//821 818//818 819//819 +f 821//821 822//822 818//818 +f 823//823 814//814 815//815 +f 823//823 784//784 814//814 +f 816//816 1732//1732 824//824 +f 816//816 825//825 817//817 +f 826//826 819//819 827//827 +f 826//826 821//821 819//819 +f 828//828 823//823 793//793 +f 793//793 823//823 815//815 +f 829//829 827//827 830//830 +f 829//829 826//826 827//827 +f 831//831 793//793 832//832 +f 831//831 828//828 793//793 +f 833//833 830//830 834//834 +f 833//833 829//829 830//830 +f 816//816 831//831 832//832 +f 816//816 832//832 825//825 +f 783//783 824//824 835//835 +f 783//783 816//816 824//824 +f 783//783 835//835 782//782 +f 775//775 780//780 782//782 +f 775//775 782//782 836//836 +f 775//775 836//836 837//837 +f 775//775 837//837 776//776 +f 838//838 777//777 776//776 +f 839//839 777//777 838//838 +f 840//840 839//839 838//838 +f 841//841 842//842 840//840 +f 840//840 842//842 839//839 +f 843//843 841//841 844//844 +f 844//844 841//841 840//840 +f 834//834 843//843 845//845 +f 845//845 843//843 844//844 +f 846//846 833//833 834//834 +f 846//846 834//834 845//845 +f 847//847 848//848 849//849 +f 849//849 848//848 850//850 +f 851//851 852//852 853//853 +f 853//853 852//852 854//854 +f 855//855 856//856 857//857 +f 857//857 856//856 858//858 +f 859//859 860//860 861//861 +f 861//861 860//860 862//862 +f 863//863 864//864 865//865 +f 865//865 864//864 866//866 +f 867//867 868//868 869//869 +f 869//869 868//868 870//870 +f 871//871 872//872 873//873 +f 873//873 872//872 874//874 +f 875//875 876//876 877//877 +f 877//877 876//876 878//878 +f 879//879 880//880 881//881 +f 879//879 882//882 880//880 +f 883//883 884//884 885//885 +f 885//885 884//884 886//886 +f 887//887 888//888 889//889 +f 889//889 888//888 890//890 +f 891//891 892//892 893//893 +f 893//893 892//892 894//894 +f 895//895 896//896 897//897 +f 897//897 896//896 898//898 +f 899//899 900//900 901//901 +f 901//901 900//900 902//902 +f 903//903 904//904 905//905 +f 905//905 904//904 906//906 +f 907//907 908//908 909//909 +f 909//909 908//908 910//910 +f 911//911 912//912 913//913 +f 913//913 912//912 914//914 +f 915//915 916//916 917//917 +f 917//917 916//916 918//918 +f 919//919 920//920 921//921 +f 921//921 920//920 922//922 +f 923//923 924//924 925//925 +f 925//925 924//924 926//926 +f 927//927 928//928 929//929 +f 929//929 928//928 930//930 +f 931//931 932//932 933//933 +f 933//933 932//932 934//934 +f 935//935 936//936 937//937 +f 935//935 938//938 936//936 +f 939//939 940//940 941//941 +f 941//941 940//940 942//942 +f 943//943 944//944 945//945 +f 945//945 944//944 946//946 +f 947//947 948//948 949//949 +f 949//949 948//948 950//950 +f 951//951 952//952 953//953 +f 953//953 952//952 954//954 +f 955//955 956//956 957//957 +f 957//957 956//956 958//958 +f 959//959 960//960 961//961 +f 961//961 960//960 962//962 +f 963//963 964//964 965//965 +f 965//965 964//964 966//966 +f 967//967 968//968 969//969 +f 969//969 968//968 970//970 +f 971//971 972//972 973//973 +f 973//973 972//972 974//974 +f 975//975 976//976 977//977 +f 975//975 978//978 976//976 +f 979//979 977//977 980//980 +f 979//979 975//975 977//977 +f 981//981 980//980 982//982 +f 981//981 979//979 980//980 +f 983//983 982//982 984//984 +f 983//983 981//981 982//982 +f 985//985 984//984 986//986 +f 985//985 983//983 984//984 +f 987//987 986//986 988//988 +f 987//987 985//985 986//986 +f 989//989 990//990 991//991 +f 991//991 992//992 989//989 +f 993//993 994//994 995//995 +f 995//995 996//996 993//993 +f 997//997 998//998 999//999 +f 999//999 1000//1000 997//997 +f 1001//1001 1002//1002 1003//1003 +f 1003//1003 1004//1004 1001//1001 +f 1005//1005 1006//1006 1007//1007 +f 1007//1007 1008//1008 1005//1005 +f 1009//1009 1010//1010 1011//1011 +f 1011//1011 1012//1012 1009//1009 +f 1013//1013 1014//1014 1015//1015 +f 1013//1013 1016//1016 1014//1014 +f 1017//1017 1018//1018 1019//1019 +f 1017//1017 1020//1020 1018//1018 +f 1021//1021 1022//1022 1023//1023 +f 1021//1021 1024//1024 1022//1022 +f 1025//1025 1026//1026 1027//1027 +f 1025//1025 1028//1028 1026//1026 +f 1029//1029 1030//1030 1031//1031 +f 1029//1029 1032//1032 1030//1030 +f 1033//1033 1034//1034 1035//1035 +f 1036//1036 1034//1034 1033//1033 +f 1036//1036 1037//1037 1034//1034 +f 1036//1036 1033//1033 1038//1038 +f 1039//1039 1040//1040 1041//1041 +f 1041//1041 1042//1042 1039//1039 +f 1043//1043 1044//1044 1045//1045 +f 1045//1045 1046//1046 1043//1043 +f 1047//1047 1048//1048 1049//1049 +f 1050//1050 1048//1048 1047//1047 +f 1050//1050 1051//1051 1048//1048 +f 1050//1050 1047//1047 1052//1052 +f 1053//1053 1054//1054 1055//1055 +f 1053//1053 1056//1056 1054//1054 +f 1057//1057 1058//1058 1059//1059 +f 1059//1059 1060//1060 1057//1057 +f 1061//1061 1062//1062 1063//1063 +f 1063//1063 1064//1064 1061//1061 +f 1065//1065 1066//1066 1067//1067 +f 1065//1065 1068//1068 1066//1066 +f 1069//1069 1070//1070 1071//1071 +f 1069//1069 1072//1072 1070//1070 +f 1073//1073 1074//1074 1075//1075 +f 1075//1075 1076//1076 1073//1073 +f 1077//1077 1078//1078 1079//1079 +f 1079//1079 1080//1080 1077//1077 +f 1081//1081 1082//1082 1083//1083 +f 1081//1081 1084//1084 1082//1082 +f 1085//1085 1086//1086 1087//1087 +f 1085//1085 1088//1088 1086//1086 +f 1089//1089 1090//1090 1091//1091 +f 1089//1089 1092//1092 1090//1090 +f 1093//1093 1094//1094 1095//1095 +f 1093//1093 1096//1096 1094//1094 +f 1097//1097 1098//1098 1099//1099 +f 1097//1097 1100//1100 1098//1098 +f 1101//1101 1102//1102 1103//1103 +f 1101//1101 1104//1104 1102//1102 +f 1105//1105 1106//1106 1107//1107 +f 1107//1107 1108//1108 1105//1105 +f 1109//1109 1110//1110 1111//1111 +f 1111//1111 1112//1112 1109//1109 +f 1113//1113 1114//1114 1115//1115 +f 1115//1115 1116//1116 1113//1113 +f 1117//1117 1118//1118 1119//1119 +f 1119//1119 1120//1120 1117//1117 +f 1121//1121 1122//1122 1123//1123 +f 1123//1123 1124//1124 1121//1121 +f 1125//1125 1126//1126 1127//1127 +f 1127//1127 1128//1128 1125//1125 +f 1129//1129 1130//1130 1131//1131 +f 1131//1131 1132//1132 1129//1129 +f 1133//1133 1134//1134 1135//1135 +f 1133//1133 1136//1136 1134//1134 +f 1137//1137 1138//1138 1139//1139 +f 1137//1137 1140//1140 1138//1138 +f 1141//1141 1142//1142 1143//1143 +f 1141//1141 1144//1144 1142//1142 +f 1145//1145 1146//1146 1147//1147 +f 1145//1145 1148//1148 1146//1146 +f 1149//1149 1150//1150 1151//1151 +f 1151//1151 1152//1152 1149//1149 +f 1153//1153 1154//1154 1155//1155 +f 1156//1156 1157//1157 1158//1158 +f 1159//1159 1160//1160 1161//1161 +f 1161//1161 1162//1162 1159//1159 +f 1163//1163 1164//1164 1165//1165 +f 1163//1163 1166//1166 1164//1164 +f 1167//1167 1168//1168 1169//1169 +f 1169//1169 1170//1170 1167//1167 +f 1171//1171 1172//1172 1173//1173 +f 1173//1173 1174//1174 1171//1171 +f 1175//1175 1176//1176 1177//1177 +f 1177//1177 1178//1178 1175//1175 +f 1179//1179 1180//1180 1181//1181 +f 1179//1179 1182//1182 1180//1180 +f 1183//1183 1184//1184 1185//1185 +f 1185//1185 1186//1186 1183//1183 +f 1187//1187 1188//1188 1189//1189 +f 1187//1187 1190//1190 1188//1188 +f 1191//1191 1192//1192 1193//1193 +f 1191//1191 1194//1194 1192//1192 +f 1195//1195 1196//1196 1197//1197 +f 1197//1197 1198//1198 1195//1195 +f 1199//1199 1200//1200 1201//1201 +f 1201//1201 1202//1202 1199//1199 +f 1203//1203 1204//1204 1205//1205 +f 1205//1205 1206//1206 1203//1203 +f 1207//1207 1208//1208 1209//1209 +f 1209//1209 1210//1210 1207//1207 +f 1211//1211 1212//1212 1213//1213 +f 1733//1733 1214//1214 1215//1215 +f 1216//1216 1217//1217 1218//1218 +f 1216//1216 1219//1219 1217//1217 +f 1220//1220 1221//1221 1222//1222 +f 1222//1222 1223//1223 1220//1220 +f 1224//1224 1225//1225 1226//1226 +f 1226//1226 1225//1225 1227//1227 +f 1228//1228 1229//1229 1230//1230 +f 1230//1230 1231//1231 1228//1228 +f 1232//1232 1233//1233 1234//1234 +f 1232//1232 1235//1235 1233//1233 +f 1236//1236 1237//1237 1238//1238 +f 1238//1238 1239//1239 1236//1236 +f 1240//1240 1241//1241 1242//1242 +f 1242//1242 1243//1243 1240//1240 +f 1244//1244 1245//1245 1246//1246 +f 1244//1244 1247//1247 1245//1245 +f 1248//1248 1249//1249 1250//1250 +f 1250//1250 1251//1251 1248//1248 +f 1252//1252 1253//1253 1254//1254 +f 1252//1252 1255//1255 1253//1253 +f 1256//1256 1257//1257 1258//1258 +f 1258//1258 1259//1259 1256//1256 +f 1260//1260 1261//1261 1262//1262 +f 1260//1260 1263//1263 1261//1261 +f 1264//1264 1265//1265 1266//1266 +f 1264//1264 1267//1267 1265//1265 +f 1268//1268 1269//1269 1270//1270 +f 1270//1270 1271//1271 1268//1268 +f 1272//1272 1273//1273 1274//1274 +f 1274//1274 1273//1273 1275//1275 +f 1276//1276 1277//1277 1278//1278 +f 1734//1734 1279//1279 1280//1280 +f 1281//1281 1282//1282 1283//1283 +f 1281//1281 1284//1284 1282//1282 +f 1285//1285 1286//1286 1287//1287 +f 1287//1287 1288//1288 1285//1285 +f 1289//1289 1290//1290 1291//1291 +f 1291//1291 1292//1292 1289//1289 +f 1293//1293 1294//1294 1295//1295 +f 1295//1295 1294//1294 1296//1296 +f 1297//1297 1298//1298 1299//1299 +f 1300//1300 1301//1301 1302//1302 +f 1303//1303 1304//1304 1305//1305 +f 1305//1305 1306//1306 1303//1303 +f 1307//1307 1308//1308 1309//1309 +f 1309//1309 1310//1310 1307//1307 +f 1311//1311 1312//1312 1313//1313 +f 1313//1313 1312//1312 1314//1314 +f 1315//1315 1316//1316 1317//1317 +f 1317//1317 1316//1316 1318//1318 +f 1319//1319 1320//1320 1321//1321 +f 1321//1321 1322//1322 1319//1319 +f 1323//1323 1324//1324 1325//1325 +f 1735//1735 1326//1326 1327//1327 +f 1328//1328 1329//1329 1330//1330 +f 1328//1328 1331//1331 1329//1329 +f 1332//1332 1333//1333 1334//1334 +f 1334//1334 1335//1335 1332//1332 +f 1336//1336 1337//1337 1338//1338 +f 1338//1338 1339//1339 1336//1336 +f 1340//1340 1341//1341 1342//1342 +f 1342//1342 1343//1343 1340//1340 +f 1344//1344 1345//1345 1346//1346 +f 1346//1346 1347//1347 1344//1344 +f 1348//1348 1349//1349 1350//1350 +f 1348//1348 1351//1351 1349//1349 +f 1352//1352 1353//1353 1354//1354 +f 1352//1352 1355//1355 1353//1353 +f 1356//1356 1354//1354 1357//1357 +f 1356//1356 1352//1352 1354//1354 +f 1358//1358 1357//1357 1359//1359 +f 1358//1358 1356//1356 1357//1357 +f 1360//1360 1359//1359 1361//1361 +f 1360//1360 1358//1358 1359//1359 +f 1362//1362 1736//1736 1363//1363 +f 1362//1362 1364//1364 1736//1736 +f 1365//1365 1363//1363 1366//1366 +f 1365//1365 1362//1362 1363//1363 +f 1355//1355 1366//1366 1353//1353 +f 1355//1355 1365//1365 1366//1366 +f 1367//1367 1368//1368 1369//1369 +f 1370//1370 1368//1368 1367//1367 +f 1370//1370 1371//1371 1368//1368 +f 1372//1372 1371//1371 1370//1370 +f 1372//1372 1373//1373 1371//1371 +f 1374//1374 1375//1375 1376//1376 +f 1377//1377 1375//1375 1374//1374 +f 1377//1377 1378//1378 1375//1375 +f 1379//1379 1378//1378 1377//1377 +f 1379//1379 1380//1380 1378//1378 +f 1381//1381 1382//1382 1383//1383 +f 1382//1382 1381//1381 1384//1384 +f 1385//1385 1384//1384 1386//1386 +f 1385//1385 1382//1382 1384//1384 +f 1387//1387 1386//1386 1388//1388 +f 1387//1387 1385//1385 1386//1386 +f 1389//1389 1388//1388 1390//1390 +f 1389//1389 1387//1387 1388//1388 +f 1391//1391 1390//1390 1392//1392 +f 1391//1391 1389//1389 1390//1390 +f 1393//1393 1381//1381 1394//1394 +f 1394//1394 1381//1381 1383//1383 +f 1393//1393 1391//1391 1392//1392 +f 1393//1393 1394//1394 1391//1391 +f 1395//1395 1396//1396 1397//1397 +f 1395//1395 1398//1398 1396//1396 +f 1399//1399 1400//1400 1401//1401 +f 1399//1399 1402//1402 1400//1400 +f 1403//1403 1404//1404 1405//1405 +f 1403//1403 1406//1406 1404//1404 +f 1407//1407 1408//1408 1409//1409 +f 1407//1407 1410//1410 1408//1408 +f 1411//1411 1412//1412 1413//1413 +f 1411//1411 1414//1414 1412//1412 +f 1415//1415 1416//1416 1417//1417 +f 1415//1415 1418//1418 1416//1416 +f 1419//1419 1420//1420 1421//1421 +f 1419//1419 1422//1422 1420//1420 +f 1423//1423 1424//1424 1425//1425 +f 1423//1423 1426//1426 1424//1424 +f 1427//1427 1425//1425 1428//1428 +f 1427//1427 1423//1423 1425//1425 +f 1429//1429 1428//1428 1430//1430 +f 1429//1429 1427//1427 1428//1428 +f 1431//1431 1432//1432 1433//1433 +f 1431//1431 1434//1434 1432//1432 +f 1435//1435 1433//1433 1436//1436 +f 1435//1435 1431//1431 1433//1433 +f 1437//1437 1436//1436 1438//1438 +f 1437//1437 1435//1435 1436//1436 +f 1426//1426 1438//1438 1424//1424 +f 1426//1426 1437//1437 1438//1438 +f 1439//1439 1440//1440 1441//1441 +f 1442//1442 1440//1440 1439//1439 +f 1442//1442 1443//1443 1440//1440 +f 1444//1444 1443//1443 1442//1442 +f 1444//1444 1445//1445 1443//1443 +f 1446//1446 1447//1447 1448//1448 +f 1449//1449 1447//1447 1446//1446 +f 1449//1449 1450//1450 1447//1447 +f 1451//1451 1450//1450 1449//1449 +f 1451//1451 1452//1452 1450//1450 +f 1453//1453 1454//1454 1455//1455 +f 1454//1454 1453//1453 1456//1456 +f 1457//1457 1456//1456 1458//1458 +f 1457//1457 1454//1454 1456//1456 +f 1459//1459 1458//1458 1460//1460 +f 1459//1459 1457//1457 1458//1458 +f 1461//1461 1460//1460 1462//1462 +f 1461//1461 1459//1459 1460//1460 +f 1463//1463 1462//1462 1464//1464 +f 1463//1463 1461//1461 1462//1462 +f 1465//1465 1453//1453 1466//1466 +f 1466//1466 1453//1453 1455//1455 +f 1465//1465 1466//1466 1464//1464 +f 1464//1464 1466//1466 1463//1463 +f 1467//1467 1468//1468 1469//1469 +f 1467//1467 1470//1470 1468//1468 +f 1471//1471 1472//1472 1473//1473 +f 1471//1471 1474//1474 1472//1472 +f 1475//1475 1476//1476 1477//1477 +f 1475//1475 1478//1478 1476//1476 +f 1479//1479 1480//1480 1481//1481 +f 1479//1479 1482//1482 1480//1480 +f 1483//1483 1484//1484 1485//1485 +f 1483//1483 1486//1486 1484//1484 +f 1487//1487 1488//1488 1489//1489 +f 1487//1487 1490//1490 1488//1488 +f 1491//1491 1492//1492 1493//1493 +f 1491//1491 1494//1494 1492//1492 +f 1495//1495 1496//1496 1497//1497 +f 1495//1495 1498//1498 1496//1496 +f 1499//1499 1500//1500 1501//1501 +f 1502//1502 1503//1503 1504//1504 +f 1500//1500 1499//1499 1502//1502 +f 1502//1502 1499//1499 1503//1503 +f 1505//1505 1499//1499 1501//1501 +f 1505//1505 1506//1506 1499//1499 +f 1507//1507 1508//1508 1509//1509 +f 1507//1507 1510//1510 1508//1508 +f 1511//1511 1510//1510 1507//1507 +f 1511//1511 1512//1512 1510//1510 +f 1513//1513 1501//1501 1511//1511 +f 1514//1514 1505//1505 1501//1501 +f 1513//1513 1511//1511 1507//1507 +f 1514//1514 1501//1501 1513//1513 +f 1515//1515 1516//1516 1517//1517 +f 1517//1517 1516//1516 1518//1518 +f 1519//1519 1516//1516 1515//1515 +f 1518//1518 1516//1516 1520//1520 +f 1521//1521 1522//1522 1523//1523 +f 1523//1523 1522//1522 1524//1524 +f 1525//1525 1522//1522 1521//1521 +f 1524//1524 1522//1522 1526//1526 +f 1527//1527 1528//1528 1529//1529 +f 1530//1530 1529//1529 1531//1531 +f 1531//1531 1529//1529 1532//1532 +f 1532//1532 1529//1529 1533//1533 +f 1530//1530 1527//1527 1529//1529 +f 1534//1534 1527//1527 1530//1530 +f 1534//1534 1535//1535 1527//1527 +f 1534//1534 1530//1530 1536//1536 +f 1537//1537 1538//1538 1539//1539 +f 1539//1539 1540//1540 1541//1541 +f 1541//1541 1540//1540 1542//1542 +f 1543//1543 1544//1544 1545//1545 +f 1541//1541 1537//1537 1539//1539 +f 1541//1541 1546//1546 1537//1537 +f 1543//1543 1546//1546 1541//1541 +f 1543//1543 1545//1545 1546//1546 +f 1547//1547 1548//1548 1549//1549 +f 1549//1549 1548//1548 1550//1550 +f 1551//1551 1552//1552 1553//1553 +f 1553//1553 1552//1552 1554//1554 +f 1555//1555 1556//1556 1557//1557 +f 1555//1555 1558//1558 1556//1556 +f 1559//1559 1560//1560 1561//1561 +f 1559//1559 1562//1562 1560//1560 +f 1563//1563 1564//1564 1565//1565 +f 1563//1563 1566//1566 1564//1564 +f 1567//1567 1568//1568 1569//1569 +f 1567//1567 1570//1570 1568//1568 +f 1571//1571 1572//1572 1573//1573 +f 1571//1571 1574//1574 1572//1572 +f 1575//1575 1576//1576 1577//1577 +f 1575//1575 1578//1578 1576//1576 +f 1579//1579 1580//1580 1581//1581 +f 1579//1579 1582//1582 1580//1580 +f 1583//1583 1584//1584 1585//1585 +f 1583//1583 1586//1586 1584//1584 +f 1587//1587 1588//1588 1589//1589 +f 1587//1587 1590//1590 1588//1588 +f 1591//1591 1592//1592 1593//1593 +f 1591//1591 1594//1594 1592//1592 +f 1595//1595 1596//1596 1597//1597 +f 1595//1595 1598//1598 1596//1596 +f 1599//1599 1600//1600 1601//1601 +f 1599//1599 1602//1602 1600//1600 +f 1603//1603 1604//1604 1605//1605 +f 1603//1603 1606//1606 1604//1604 +f 1607//1607 1608//1608 1609//1609 +f 1607//1607 1610//1610 1608//1608 +f 1611//1611 1612//1612 1613//1613 +f 1611//1611 1614//1614 1612//1612 +f 1615//1615 1616//1616 1617//1617 +f 1615//1615 1618//1618 1616//1616 +f 1619//1619 1620//1620 1621//1621 +f 1619//1619 1622//1622 1620//1620 +f 1623//1623 1624//1624 1625//1625 +f 1623//1623 1626//1626 1624//1624 +f 1627//1627 1628//1628 1629//1629 +f 1627//1627 1630//1630 1628//1628 +f 1631//1631 1632//1632 1633//1633 +f 1631//1631 1634//1634 1632//1632 +f 1635//1635 1636//1636 1637//1637 +f 1635//1635 1638//1638 1636//1636 +f 1639//1639 1640//1640 1641//1641 +f 1639//1639 1642//1642 1640//1640 +f 1643//1643 1644//1644 1645//1645 +f 1643//1643 1646//1646 1644//1644 +f 1647//1647 1648//1648 1649//1649 +f 1647//1647 1650//1650 1648//1648 +f 1651//1651 1652//1652 1653//1653 +f 1651//1651 1654//1654 1652//1652 +f 1655//1655 1656//1656 1657//1657 +f 1655//1655 1658//1658 1656//1656 +f 1659//1659 1660//1660 1661//1661 +f 1659//1659 1662//1662 1660//1660 +f 1659//1659 1663//1663 1664//1664 +f 1659//1659 1661//1661 1663//1663 +f 1665//1665 1666//1666 1667//1667 +f 1665//1665 1668//1668 1666//1666 +f 1665//1665 1669//1669 1670//1670 +f 1665//1665 1667//1667 1669//1669 +f 1671//1671 1672//1672 1673//1673 +f 1671//1671 1674//1674 1672//1672 +f 1671//1671 1675//1675 1676//1676 +f 1671//1671 1673//1673 1675//1675 +f 1677//1677 1678//1678 1679//1679 +f 1680//1680 1681//1681 1682//1682 +f 1683//1683 1677//1677 1679//1679 +f 1683//1683 1684//1684 1677//1677 +f 1680//1680 1684//1684 1683//1683 +f 1680//1680 1682//1682 1684//1684 +f 1685//1685 1686//1686 1687//1687 +f 1685//1685 1688//1688 1686//1686 +f 1685//1685 1689//1689 1690//1690 +f 1685//1685 1687//1687 1689//1689 +f 1691//1691 1692//1692 1693//1693 +f 1691//1691 1694//1694 1692//1692 +f 1691//1691 1695//1695 1696//1696 +f 1691//1691 1693//1693 1695//1695 +f 1697//1697 1698//1698 1699//1699 +f 1697//1697 1700//1700 1698//1698 +f 1697//1697 1701//1701 1702//1702 +f 1697//1697 1699//1699 1701//1701 +f 1703//1703 1704//1704 1705//1705 +f 1706//1706 1707//1707 1708//1708 +f 1709//1709 1703//1703 1705//1705 +f 1709//1709 1710//1710 1703//1703 +f 1706//1706 1710//1710 1709//1709 +f 1706//1706 1708//1708 1710//1710 +f 1711//1711 1712//1712 1713//1713 +f 1711//1711 1714//1714 1712//1712 +f 1715//1715 1714//1714 1711//1711 +f 1715//1715 1716//1716 1714//1714 +# 1099 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/head_camera.obj b/examples/Atlas/urdf/mesh/head_camera.obj new file mode 100644 index 0000000..6c083e4 --- /dev/null +++ b/examples/Atlas/urdf/mesh/head_camera.obj @@ -0,0 +1,1232 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object head_camera.obj +# +# Vertices: 480 +# Faces: 256 +# +#### +vn 0.000000 -0.315211 0.949022 +v -0.041643 0.028613 0.097818 +vn 0.000000 -0.315211 0.949022 +v 0.017057 -0.027387 0.079218 +vn 0.000000 -0.315211 0.949022 +v 0.017057 0.028613 0.097818 +vn 0.000000 -0.315211 0.949022 +v -0.041643 -0.027387 0.079218 +vn 1.000000 0.000000 0.000000 +v 0.017057 0.028613 0.097818 +vn 1.000000 0.000000 0.000000 +v 0.017057 -0.014687 0.040918 +vn 1.000000 0.000000 0.000000 +v 0.017057 0.041313 0.059418 +vn 1.000000 0.000000 0.000000 +v 0.017057 -0.027387 0.079218 +vn 0.000000 0.949422 0.314002 +v -0.041643 0.028613 0.097818 +vn 0.000000 0.949422 0.314002 +v 0.017057 0.041313 0.059418 +vn 0.000000 0.949422 0.314002 +v -0.041643 0.041313 0.059418 +vn 0.000000 0.949422 0.314002 +v 0.017057 0.028613 0.097818 +vn -1.000000 0.000000 0.000000 +v -0.041643 -0.027387 0.079218 +vn -1.000000 0.000000 0.000000 +v -0.041643 0.041313 0.059418 +vn -1.000000 0.000000 0.000000 +v -0.041643 -0.014687 0.040918 +vn -1.000000 0.000000 0.000000 +v -0.041643 0.028613 0.097818 +vn 0.000000 -0.949178 -0.314740 +v 0.017057 -0.027387 0.079218 +vn 0.000000 -0.949178 -0.314740 +v -0.041643 -0.014687 0.040918 +vn 0.000000 -0.949178 -0.314740 +v 0.017057 -0.014687 0.040918 +vn 0.000000 -0.949178 -0.314740 +v -0.041643 -0.027387 0.079218 +vn -0.000000 0.315657 -0.948873 +v 0.003657 -0.036187 0.105818 +vn -0.000000 0.315566 -0.948904 +v 0.017257 0.006813 0.120118 +vn 0.000997 0.315282 -0.948998 +v 0.017257 -0.023287 0.110118 +vn -0.000095 0.315718 -0.948853 +v 0.003657 0.019713 0.124418 +vn -0.000095 0.315718 -0.948853 +v -0.027843 -0.036187 0.105818 +vn 0.000000 0.315657 -0.948873 +v -0.027843 0.019713 0.124418 +vn 0.000000 0.315566 -0.948904 +v -0.041543 -0.023287 0.110118 +vn 0.000990 0.315282 -0.948998 +v -0.041543 0.006813 0.120118 +vn 0.000000 -0.313944 0.949441 +v 0.017257 -0.029087 0.127718 +vn 0.000000 -0.316228 0.948683 +v -0.027843 -0.041987 0.123418 +vn 0.000000 -0.316228 0.948683 +v 0.003657 -0.041987 0.123418 +vn 0.000000 -0.313108 0.949718 +v -0.041543 -0.029087 0.127718 +vn 0.000000 -0.313108 0.949718 +v 0.017257 0.001013 0.137618 +vn 0.000000 -0.313944 0.949441 +v -0.041543 0.001013 0.137618 +vn 0.000000 -0.316228 0.948683 +v 0.003657 0.013913 0.141918 +vn 0.000000 -0.316228 0.948683 +v -0.027843 0.013913 0.141918 +vn 1.000000 0.000000 0.000000 +v 0.017257 0.001013 0.137618 +vn 1.000000 0.000000 0.000000 +v 0.017257 -0.023287 0.110118 +vn 1.000000 0.000000 0.000000 +v 0.017257 0.006813 0.120118 +vn 1.000000 0.000000 0.000000 +v 0.017257 -0.029087 0.127718 +vn 0.000000 0.949224 0.314600 +v -0.027843 0.013913 0.141918 +vn 0.000000 0.949224 0.314600 +v 0.003657 0.019713 0.124418 +vn 0.000000 0.949224 0.314600 +v -0.027843 0.019713 0.124418 +vn 0.000000 0.949224 0.314600 +v 0.003657 0.013913 0.141918 +vn -1.000000 0.000000 0.000000 +v -0.041543 -0.029087 0.127718 +vn -1.000000 0.000000 0.000000 +v -0.041543 0.006813 0.120118 +vn -1.000000 0.000000 0.000000 +v -0.041543 -0.023287 0.110118 +vn -1.000000 0.000000 0.000000 +v -0.041543 0.001013 0.137618 +vn 0.000000 -0.949757 -0.312988 +v 0.003657 -0.041987 0.123418 +vn 0.000000 -0.949757 -0.312988 +v -0.027843 -0.036187 0.105818 +vn 0.000000 -0.949757 -0.312988 +v 0.003657 -0.036187 0.105818 +vn 0.000000 -0.949757 -0.312988 +v -0.027843 -0.041987 0.123418 +vn 0.707049 0.671258 0.222474 +v 0.003657 0.013913 0.141918 +vn 0.707049 0.671258 0.222474 +v 0.017257 0.006813 0.120118 +vn 0.707049 0.671258 0.222474 +v 0.003657 0.019713 0.124418 +vn 0.707049 0.671258 0.222474 +v 0.017257 0.001013 0.137618 +vn 0.707047 -0.671636 -0.221335 +v 0.003657 -0.036187 0.105818 +vn 0.707047 -0.671636 -0.221335 +v 0.017257 -0.029087 0.127718 +vn 0.707047 -0.671636 -0.221335 +v 0.003657 -0.041987 0.123418 +vn 0.707047 -0.671636 -0.221335 +v 0.017257 -0.023287 0.110118 +vn -0.704454 0.673712 0.223287 +v -0.041543 0.001013 0.137618 +vn -0.704454 0.673712 0.223287 +v -0.027843 0.019713 0.124418 +vn -0.704454 0.673712 0.223287 +v -0.041543 0.006813 0.120118 +vn -0.704454 0.673712 0.223287 +v -0.027843 0.013913 0.141918 +vn -0.704452 -0.674091 -0.222144 +v -0.027843 -0.041987 0.123418 +vn -0.704452 -0.674091 -0.222144 +v -0.041543 -0.023287 0.110118 +vn -0.704452 -0.674091 -0.222144 +v -0.027843 -0.036187 0.105818 +vn -0.704452 -0.674091 -0.222144 +v -0.041543 -0.029087 0.127718 +vn -0.756407 0.621289 0.204571 +v -0.032743 0.001713 0.122018 +vn -0.189550 0.932616 0.307081 +v -0.012343 0.023713 0.092918 +vn -0.944934 0.310844 0.102351 +v -0.032743 0.012513 0.089218 +vn 0.189849 0.932561 0.307063 +v -0.012343 0.012913 0.125718 +vn -1.000000 0.000000 0.000000 +v -0.032743 -0.020687 0.114618 +vn -1.000000 0.000000 0.000000 +v -0.032743 -0.009787 0.081818 +vn -0.189661 -0.932313 -0.307930 +v -0.012343 -0.031787 0.110918 +vn -0.499041 -0.822733 -0.272154 +v -0.032743 -0.009787 0.081818 +vn 0.188487 -0.932529 -0.307998 +v -0.012343 -0.020987 0.078118 +vn -0.497526 -0.823185 -0.273558 +v -0.032743 -0.020687 0.114618 +vn 0.757418 -0.619895 -0.205057 +v 0.007957 -0.020687 0.114618 +vn 0.945356 -0.309402 -0.102819 +v 0.007957 -0.009787 0.081818 +vn 0.945429 0.309482 0.101903 +v 0.007957 0.001713 0.122018 +vn 0.757344 0.620258 0.204231 +v 0.007957 0.012513 0.089218 +vn 0.000000 0.951114 -0.308839 +v -0.071643 0.049013 0.053718 +vn 0.000000 0.994182 -0.107711 +v -0.065743 0.060313 0.088518 +vn 0.000000 0.951114 -0.308839 +v -0.065743 0.049013 0.053718 +vn 0.000000 0.994171 0.107813 +v -0.071643 0.060313 0.088518 +vn 0.000000 0.950853 0.309644 +v -0.071643 0.049013 0.123218 +vn 0.000000 0.951893 -0.306431 +v -0.043043 0.026013 0.088518 +vn 0.000000 0.951893 -0.306431 +v -0.065743 0.021313 0.073918 +vn 0.000000 0.951893 -0.306431 +v -0.065743 0.026013 0.088518 +vn 0.000000 0.951893 -0.306431 +v -0.043043 0.021313 0.073918 +vn 0.000000 0.588556 -0.808456 +v -0.043043 0.021313 0.073918 +vn 0.000000 0.588556 -0.808456 +v -0.065743 0.008813 0.064818 +vn 0.000000 0.588556 -0.808456 +v -0.065743 0.021313 0.073918 +vn 0.000000 0.588556 -0.808456 +v -0.043043 0.008813 0.064818 +vn 0.000000 -0.588556 -0.808456 +v -0.043043 -0.006487 0.064818 +vn 0.000000 -0.588556 -0.808456 +v -0.065743 -0.018987 0.073918 +vn 0.000000 -0.588556 -0.808456 +v -0.065743 -0.006487 0.064818 +vn 0.000000 -0.588556 -0.808456 +v -0.043043 -0.018987 0.073918 +vn 0.000000 -0.951893 -0.306431 +v -0.043043 -0.018987 0.073918 +vn 0.000000 -0.951893 -0.306431 +v -0.065743 -0.023687 0.088518 +vn 0.000000 -0.951893 -0.306431 +v -0.065743 -0.018987 0.073918 +vn 0.000000 -0.951893 -0.306431 +v -0.043043 -0.023687 0.088518 +vn 0.000000 -0.951893 0.306431 +v -0.043043 -0.023687 0.088518 +vn 0.000000 -0.951893 0.306431 +v -0.065743 -0.018987 0.103118 +vn 0.000000 -0.951893 0.306431 +v -0.065743 -0.023687 0.088518 +vn 0.000000 -0.951893 0.306431 +v -0.043043 -0.018987 0.103118 +vn 0.000000 -0.584305 0.811535 +v -0.043043 -0.018987 0.103118 +vn 0.000000 -0.584305 0.811535 +v -0.065743 -0.006487 0.112118 +vn 0.000000 -0.584305 0.811535 +v -0.065743 -0.018987 0.103118 +vn 0.000000 -0.584305 0.811535 +v -0.043043 -0.006487 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.043043 -0.006487 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.065743 0.008813 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.065743 -0.006487 0.112118 +vn 0.000000 0.000000 1.000000 +v -0.043043 0.008813 0.112118 +vn 0.000000 0.584305 0.811535 +v -0.043043 0.008813 0.112118 +vn 0.000000 0.584305 0.811535 +v -0.065743 0.021313 0.103118 +vn 0.000000 0.584305 0.811535 +v -0.065743 0.008813 0.112118 +vn 0.000000 0.584305 0.811535 +v -0.043043 0.021313 0.103118 +vn 0.000000 0.951893 0.306431 +v -0.043043 0.021313 0.103118 +vn 0.000000 0.951893 0.306431 +v -0.065743 0.026013 0.088518 +vn 0.000000 0.951893 0.306431 +v -0.065743 0.021313 0.103118 +vn 0.000000 0.951893 0.306431 +v -0.043043 0.026013 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.026013 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.008813 0.064818 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.021313 0.073918 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.006487 0.064818 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.021313 0.103118 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.018987 0.073918 +vn 1.000000 0.000000 0.000000 +v -0.043043 0.008813 0.112118 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.023687 0.088518 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.006487 0.112118 +vn 1.000000 0.000000 0.000000 +v -0.043043 -0.018987 0.103118 +vn -0.756493 -0.132579 -0.640423 +v -0.061543 -0.021687 0.080018 +vn -0.500341 -0.175520 -0.847851 +v -0.054043 -0.036787 0.078718 +vn -0.944479 -0.067463 -0.321573 +v -0.061543 -0.035987 0.083018 +vn -0.496961 -0.173637 -0.850223 +v -0.054043 -0.022587 0.075818 +vn -0.944129 0.065504 0.323002 +v -0.061543 -0.020087 0.088518 +vn -0.754444 0.133058 0.642736 +v -0.061543 -0.034387 0.091418 +vn -0.192288 0.200238 0.960692 +v -0.054043 -0.019287 0.092718 +vn 0.187312 0.200434 0.961634 +v -0.054043 -0.033487 0.095718 +vn 0.756288 0.132627 0.640655 +v -0.046543 -0.020087 0.088518 +vn 0.944687 0.065185 0.321429 +v -0.046543 -0.034387 0.091418 +vn 0.944111 -0.067679 -0.322605 +v -0.046543 -0.021687 0.080018 +vn 0.754651 -0.133009 -0.642503 +v -0.046543 -0.035987 0.083018 +vn 0.500341 -0.175520 -0.847851 +v -0.054043 -0.022587 0.075818 +vn 0.503709 -0.172857 -0.846403 +v -0.054043 -0.036787 0.078718 +vn -0.111615 -0.992804 0.043390 +v -0.054043 -0.036887 0.081718 +vn -0.089158 -0.982158 0.165580 +v -0.058943 -0.035987 0.084418 +vn -0.111615 -0.992804 0.043390 +v -0.061543 -0.035987 0.083018 +vn -0.124726 -0.991640 -0.033055 +v -0.054043 -0.036787 0.078718 +vn 0.018715 -0.973155 0.229387 +v -0.058943 -0.035987 0.084418 +vn 0.189709 -0.939504 0.285207 +v -0.058943 -0.034287 0.090018 +vn 0.018715 -0.973155 0.229387 +v -0.061543 -0.034387 0.091418 +vn -0.100245 -0.977390 0.186170 +v -0.061543 -0.035987 0.083018 +vn 0.126997 -0.991450 0.029978 +v -0.058943 -0.034287 0.090018 +vn 0.197933 -0.979672 -0.032655 +v -0.054043 -0.033387 0.092718 +vn 0.126997 -0.991450 0.029978 +v -0.054043 -0.033487 0.095718 +vn 0.077510 -0.994321 0.072922 +v -0.061543 -0.034387 0.091418 +vn -0.126997 -0.991450 0.029978 +v -0.054043 -0.033387 0.092718 +vn -0.108618 -0.985370 0.131334 +v -0.049143 -0.034287 0.090018 +vn -0.126997 -0.991450 0.029978 +v -0.046543 -0.034387 0.091418 +vn -0.137709 -0.989923 -0.032997 +v -0.054043 -0.033487 0.095718 +vn -0.018715 -0.973155 0.229387 +v -0.049143 -0.034287 0.090018 +vn 0.154535 -0.945386 0.286993 +v -0.049143 -0.035987 0.084418 +vn -0.018715 -0.973155 0.229387 +v -0.046543 -0.035987 0.083018 +vn -0.137225 -0.973046 0.185342 +v -0.046543 -0.034387 0.091418 +vn 0.111615 -0.992804 0.043391 +v -0.049143 -0.035987 0.084418 +vn 0.197934 -0.979671 -0.032656 +v -0.054043 -0.036887 0.081718 +vn 0.111615 -0.992804 0.043391 +v -0.054043 -0.036787 0.078718 +vn 0.051356 -0.994116 0.095376 +v -0.046543 -0.035987 0.083018 +vn -0.511224 -0.343023 -0.788026 +v -0.054043 -0.045587 0.085418 +vn -0.511224 -0.343023 -0.788026 +v -0.058943 -0.035987 0.084418 +vn -0.501039 -0.338697 -0.796394 +v -0.054043 -0.036887 0.081718 +vn -0.521568 -0.347393 -0.779285 +v -0.058943 -0.044287 0.088118 +vn -0.505181 0.351004 0.788409 +v -0.058943 -0.041787 0.093318 +vn -0.505181 0.351004 0.788409 +v -0.054043 -0.033387 0.092718 +vn -0.500636 0.348634 0.792350 +v -0.058943 -0.034287 0.090018 +vn -0.509911 0.353466 0.784253 +v -0.054043 -0.040487 0.095918 +vn 0.505181 0.351004 0.788409 +v -0.054043 -0.040487 0.095918 +vn 0.505181 0.351004 0.788409 +v -0.049143 -0.034287 0.090018 +vn 0.500309 0.355776 0.789376 +v -0.054043 -0.033387 0.092718 +vn 0.509760 0.346483 0.787461 +v -0.049143 -0.041787 0.093318 +vn 0.511224 -0.343023 -0.788026 +v -0.049143 -0.044287 0.088118 +vn 0.511224 -0.343023 -0.788026 +v -0.054043 -0.036887 0.081718 +vn 0.500463 -0.352502 -0.790746 +v -0.049143 -0.035987 0.084418 +vn 0.521319 -0.333976 -0.785294 +v -0.054043 -0.045587 0.085418 +vn -0.498376 -0.653909 -0.569231 +v -0.054043 -0.052287 0.093018 +vn -0.498376 -0.653909 -0.569231 +v -0.058943 -0.044287 0.088118 +vn -0.490857 -0.653540 -0.576147 +v -0.054043 -0.045587 0.085418 +vn -0.507388 -0.654265 -0.560799 +v -0.058943 -0.049687 0.094418 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.049687 0.094418 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.035987 0.084418 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.044287 0.088118 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.041787 0.093318 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.034287 0.090018 +vn -1.000000 0.000000 0.000000 +v -0.058943 -0.044687 0.097318 +vn -0.486689 0.728503 0.482097 +v -0.058943 -0.044687 0.097318 +vn -0.516041 0.743706 0.424975 +v -0.054043 -0.042087 0.098718 +vn -0.486689 0.728503 0.482097 +v -0.054043 -0.040487 0.095918 +vn -0.465698 0.716459 0.519433 +v -0.058943 -0.041787 0.093318 +vn 0.486689 0.728503 0.482097 +v -0.054043 -0.042087 0.098718 +vn 0.512787 0.695063 0.503921 +v -0.049143 -0.044687 0.097318 +vn 0.486689 0.728503 0.482097 +v -0.049143 -0.041787 0.093318 +vn 0.442622 0.778561 0.444892 +v -0.054043 -0.040487 0.095918 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.035987 0.084418 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.049687 0.094418 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.044287 0.088118 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.041787 0.093318 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.044687 0.097318 +vn 1.000000 0.000000 0.000000 +v -0.049143 -0.034287 0.090018 +vn 0.498377 -0.653909 -0.569231 +v -0.049143 -0.049687 0.094418 +vn 0.498377 -0.653909 -0.569231 +v -0.054043 -0.045587 0.085418 +vn 0.488627 -0.662446 -0.567811 +v -0.049143 -0.044287 0.088118 +vn 0.506207 -0.646917 -0.570309 +v -0.054043 -0.052287 0.093018 +vn -0.468424 -0.875159 0.121146 +v -0.054043 -0.050787 0.105418 +vn -0.508767 -0.849160 0.141717 +v -0.057743 -0.048687 0.104718 +vn -0.468424 -0.875159 0.121146 +v -0.058943 -0.049687 0.094418 +vn -0.441794 -0.890624 0.107737 +v -0.054043 -0.052287 0.093018 +vn -0.988709 -0.022544 0.148145 +v -0.057743 -0.048687 0.104718 +vn -0.977982 0.070190 0.196532 +v -0.057743 -0.044487 0.103218 +vn -0.988709 -0.022544 0.148145 +v -0.058943 -0.044687 0.097318 +vn -0.989969 -0.070887 0.122218 +v -0.058943 -0.049687 0.094418 +vn -0.482734 0.873067 0.068720 +v -0.057743 -0.044487 0.103218 +vn -0.482734 0.873067 0.068720 +v -0.054043 -0.042087 0.098718 +vn -0.482837 0.873018 0.068610 +v -0.058943 -0.044687 0.097318 +vn -0.482535 0.873160 0.068934 +v -0.054043 -0.042387 0.102518 +vn 0.482734 0.873066 0.068721 +v -0.054043 -0.042387 0.102518 +vn 0.482734 0.873066 0.068721 +v -0.049143 -0.044687 0.097318 +vn 0.482895 0.872962 0.068918 +v -0.054043 -0.042087 0.098718 +vn 0.482602 0.873152 0.068558 +v -0.050343 -0.044487 0.103218 +vn 0.988709 -0.022544 0.148145 +v -0.050343 -0.044487 0.103218 +vn 0.992928 0.039930 0.111804 +v -0.050343 -0.048687 0.104718 +vn 0.988709 -0.022544 0.148145 +v -0.049143 -0.049687 0.094418 +vn 0.972423 -0.117014 0.201747 +v -0.049143 -0.044687 0.097318 +vn 0.468424 -0.875159 0.121146 +v -0.050343 -0.048687 0.104718 +vn 0.505703 -0.856464 0.103605 +v -0.054043 -0.050787 0.105418 +vn 0.468424 -0.875159 0.121146 +v -0.054043 -0.052287 0.093018 +vn 0.433477 -0.890694 0.136977 +v -0.049143 -0.049687 0.094418 +vn -0.509566 -0.828571 0.231974 +v -0.054043 -0.046287 0.121418 +vn -0.509566 -0.828571 0.231974 +v -0.057743 -0.048687 0.104718 +vn -0.512975 -0.826343 0.232409 +v -0.054043 -0.050787 0.105418 +vn -0.504856 -0.831618 0.231368 +v -0.056743 -0.044787 0.120918 +vn -0.998216 0.018645 0.056713 +v -0.056743 -0.044787 0.120918 +vn -0.998216 0.018645 0.056713 +v -0.057743 -0.044487 0.103218 +vn -0.998183 0.020264 0.056738 +v -0.057743 -0.048687 0.104718 +vn -0.998257 0.016455 0.056678 +v -0.056743 -0.041687 0.120018 +vn -0.513108 0.850827 -0.113198 +v -0.056743 -0.041687 0.120018 +vn -0.513108 0.850827 -0.113198 +v -0.054043 -0.042387 0.102518 +vn -0.506470 0.854908 -0.112338 +v -0.057743 -0.044487 0.103218 +vn -0.522046 0.845217 -0.114353 +v -0.054043 -0.040087 0.119518 +vn 0.513109 0.850826 -0.113198 +v -0.054043 -0.040087 0.119518 +vn 0.513109 0.850826 -0.113198 +v -0.050343 -0.044487 0.103218 +vn 0.506746 0.854312 -0.115583 +v -0.054043 -0.042387 0.102518 +vn 0.521703 0.846013 -0.109948 +v -0.051343 -0.041687 0.120018 +vn 0.998216 0.018645 0.056713 +v -0.051343 -0.041687 0.120018 +vn 0.998216 0.018645 0.056713 +v -0.050343 -0.048687 0.104718 +vn 0.998225 0.020029 0.056080 +v -0.050343 -0.044487 0.103218 +vn 0.998200 0.016720 0.057592 +v -0.051343 -0.044787 0.120918 +vn 0.509567 -0.828571 0.231974 +v -0.051343 -0.044787 0.120918 +vn 0.509567 -0.828571 0.231974 +v -0.054043 -0.050787 0.105418 +vn 0.512937 -0.826840 0.230717 +v -0.050343 -0.048687 0.104718 +vn 0.504908 -0.830934 0.233700 +v -0.054043 -0.046287 0.121418 +vn -0.023802 0.257836 0.965895 +v -0.054043 -0.045287 0.121118 +vn -0.031451 0.220155 0.974958 +v -0.055643 -0.044187 0.120818 +vn -0.023802 0.257836 0.965895 +v -0.056743 -0.044787 0.120918 +vn -0.017737 0.287300 0.957676 +v -0.054043 -0.046287 0.121418 +vn -0.013605 0.299312 0.954058 +v -0.055643 -0.044187 0.120818 +vn 0.064220 0.329668 0.941910 +v -0.055643 -0.042187 0.120118 +vn -0.013605 0.299312 0.954058 +v -0.056743 -0.041687 0.120018 +vn -0.064638 0.278227 0.958338 +v -0.056743 -0.044787 0.120918 +vn 0.065834 0.227432 0.971566 +v -0.055643 -0.042187 0.120118 +vn 0.132970 0.177300 0.975133 +v -0.054043 -0.041187 0.119718 +vn 0.065834 0.227432 0.971566 +v -0.054043 -0.040087 0.119518 +vn 0.027971 0.254854 0.966575 +v -0.056743 -0.041687 0.120018 +vn -0.065834 0.227432 0.971566 +v -0.054043 -0.041187 0.119718 +vn -0.050124 0.300753 0.952384 +v -0.052443 -0.042187 0.120118 +vn -0.065834 0.227432 0.971566 +v -0.051343 -0.041687 0.120018 +vn -0.075970 0.178371 0.981026 +v -0.054043 -0.040087 0.119518 +vn 0.013605 0.299312 0.954058 +v -0.052443 -0.042187 0.120118 +vn 0.093967 0.328888 0.939682 +v -0.052443 -0.044187 0.120818 +vn 0.013605 0.299312 0.954058 +v -0.051343 -0.044787 0.120918 +vn -0.039396 0.278594 0.959601 +v -0.051343 -0.041687 0.120018 +vn 0.023802 0.257836 0.965895 +v -0.052443 -0.044187 0.120818 +vn -0.017951 0.287299 0.957673 +v -0.054043 -0.045287 0.121118 +vn 0.023802 0.257836 0.965895 +v -0.054043 -0.046287 0.121418 +vn 0.044450 0.242994 0.969009 +v -0.051343 -0.044787 0.120918 +vn -0.564766 -0.769834 0.297315 +v -0.054043 -0.042387 0.128518 +vn -0.550294 -0.780444 0.296788 +v -0.055643 -0.041487 0.127918 +vn -0.564766 -0.769834 0.297315 +v -0.055643 -0.044187 0.120818 +vn -0.578117 -0.759700 0.297720 +v -0.054043 -0.045287 0.121118 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.041487 0.127918 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.042187 0.120118 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.044187 0.120818 +vn -1.000000 0.000000 0.000000 +v -0.055643 -0.039787 0.126718 +vn -0.553523 0.783218 -0.283163 +v -0.055643 -0.039787 0.126718 +vn -0.553523 0.783218 -0.283163 +v -0.054043 -0.041187 0.119718 +vn -0.558222 0.779738 -0.283542 +v -0.055643 -0.042187 0.120118 +vn -0.548613 0.786811 -0.282760 +v -0.054043 -0.038887 0.126118 +vn 0.553524 0.783217 -0.283163 +v -0.054043 -0.038887 0.126118 +vn 0.553524 0.783217 -0.283163 +v -0.052443 -0.042187 0.120118 +vn 0.558175 0.780832 -0.280611 +v -0.054043 -0.041187 0.119718 +vn 0.548969 0.785519 -0.285644 +v -0.052443 -0.039787 0.126718 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.039787 0.126718 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.044187 0.120818 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.042187 0.120118 +vn 1.000000 0.000000 0.000000 +v -0.052443 -0.041487 0.127918 +vn 0.564766 -0.769833 0.297314 +v -0.052443 -0.041487 0.127918 +vn 0.551160 -0.776873 0.304450 +v -0.054043 -0.042387 0.128518 +vn 0.564766 -0.769833 0.297314 +v -0.054043 -0.045287 0.121118 +vn 0.578516 -0.762404 0.289928 +v -0.052443 -0.044187 0.120818 +vn -0.578660 -0.286898 0.763441 +v -0.051843 -0.032387 0.134218 +vn -0.578660 -0.286898 0.763441 +v -0.053443 -0.032087 0.133118 +vn -0.578660 -0.286898 0.763441 +v -0.055643 -0.041487 0.127918 +vn -0.493813 -0.346071 0.797736 +v -0.055643 -0.041487 0.127918 +vn -0.493813 -0.346071 0.797736 +v -0.054043 -0.042387 0.128518 +vn -0.493813 -0.346071 0.797736 +v -0.051843 -0.032387 0.134218 +vn -0.976589 0.174675 0.125547 +v -0.053443 -0.032087 0.133118 +vn -0.972660 0.222438 0.066731 +v -0.053443 -0.031487 0.131118 +vn -0.976589 0.174675 0.125547 +v -0.055643 -0.039787 0.126718 +vn -0.975079 0.127943 0.181252 +v -0.055643 -0.041487 0.127918 +vn -0.545043 0.499281 -0.673532 +v -0.053443 -0.031487 0.131118 +vn -0.545043 0.499281 -0.673532 +v -0.054043 -0.038887 0.126118 +vn -0.536663 0.501848 -0.678337 +v -0.055643 -0.039787 0.126718 +vn -0.553001 0.496782 -0.668878 +v -0.051843 -0.031187 0.130018 +vn 0.540952 0.268147 -0.797162 +v -0.051843 -0.031187 0.130018 +vn 0.604651 0.248224 -0.756824 +v -0.050343 -0.031487 0.131118 +vn 0.540952 0.268147 -0.797162 +v -0.052443 -0.039787 0.126718 +vn 0.473511 0.286554 -0.832871 +v -0.054043 -0.038887 0.126118 +vn 0.978603 -0.167079 -0.120088 +v -0.050343 -0.031487 0.131118 +vn 0.980573 -0.187884 -0.056365 +v -0.050343 -0.032087 0.133118 +vn 0.978603 -0.167079 -0.120088 +v -0.052443 -0.041487 0.127918 +vn 0.970014 -0.140163 -0.198563 +v -0.052443 -0.039787 0.126718 +vn 0.557188 -0.497186 0.665092 +v -0.050343 -0.032087 0.133118 +vn 0.575639 -0.496833 0.649459 +v -0.051843 -0.032387 0.134218 +vn 0.557188 -0.497186 0.665092 +v -0.054043 -0.042387 0.128518 +vn 0.535642 -0.497234 0.682529 +v -0.052443 -0.041487 0.127918 +vn -0.555491 0.137895 0.820009 +v -0.049543 -0.015187 0.132918 +vn -0.555491 0.137895 0.820009 +v -0.053443 -0.032087 0.133118 +vn -0.543963 0.135330 0.828125 +v -0.051843 -0.032387 0.134218 +vn -0.568516 0.140788 0.810536 +v -0.051043 -0.015487 0.131918 +vn -0.988936 0.148340 0.000000 +v -0.051043 -0.015487 0.131918 +vn -0.987707 0.150303 -0.042944 +v -0.051043 -0.016087 0.129818 +vn -0.988936 0.148340 0.000000 +v -0.053443 -0.031487 0.131118 +vn -0.988306 0.146055 0.043816 +v -0.053443 -0.032087 0.133118 +vn -0.560337 0.018720 -0.828053 +v -0.051043 -0.016087 0.129818 +vn -0.560337 0.018720 -0.828053 +v -0.051843 -0.031187 0.130018 +vn -0.568873 0.019249 -0.822200 +v -0.053443 -0.031487 0.131118 +vn -0.551253 0.018158 -0.834141 +v -0.049543 -0.016487 0.128818 +vn 0.557507 -0.154794 -0.815613 +v -0.049543 -0.016487 0.128818 +vn 0.557507 -0.154794 -0.815613 +v -0.050343 -0.031487 0.131118 +vn 0.563993 -0.154464 -0.811205 +v -0.051843 -0.031187 0.130018 +vn 0.551179 -0.155105 -0.819844 +v -0.047943 -0.016087 0.129818 +vn 0.988936 -0.148340 0.000000 +v -0.047943 -0.016087 0.129818 +vn 0.989322 -0.140140 0.040040 +v -0.047943 -0.015487 0.131918 +vn 0.988936 -0.148340 0.000000 +v -0.050343 -0.032087 0.133118 +vn 0.986351 -0.157711 -0.047313 +v -0.050343 -0.031487 0.131118 +vn 0.560771 -0.016749 0.827802 +v -0.047943 -0.015487 0.131918 +vn 0.529095 -0.006617 0.848537 +v -0.049543 -0.015187 0.132918 +vn 0.560771 -0.016749 0.827802 +v -0.051843 -0.032387 0.134218 +vn 0.594759 -0.027910 0.803420 +v -0.050343 -0.032087 0.133118 +vn -0.581684 0.407619 0.703911 +v -0.045643 0.018813 0.116518 +vn -0.601862 0.404035 0.688853 +v -0.047143 0.018113 0.115618 +vn -0.581684 0.407619 0.703911 +v -0.051043 -0.015487 0.131918 +vn -0.561176 0.410932 0.718482 +v -0.049543 -0.015187 0.132918 +vn -0.994492 0.095169 -0.043924 +v -0.047143 0.018113 0.115618 +vn -0.994288 0.088803 -0.059202 +v -0.047143 0.016913 0.113818 +vn -0.994492 0.095169 -0.043924 +v -0.051043 -0.016087 0.129818 +vn -0.994427 0.101374 -0.028964 +v -0.051043 -0.015487 0.131918 +vn -0.555458 -0.307129 -0.772747 +v -0.047143 0.016913 0.113818 +vn -0.555458 -0.307129 -0.772747 +v -0.045643 0.016213 0.113018 +vn -0.555458 -0.307129 -0.772747 +v -0.049543 -0.016487 0.128818 +vn -0.583241 -0.297541 -0.755843 +v -0.051043 -0.016087 0.129818 +vn -0.583241 -0.297541 -0.755843 +v -0.047143 0.016913 0.113818 +vn 0.550245 -0.415808 -0.724109 +v -0.045643 0.016213 0.113018 +vn 0.550245 -0.415808 -0.724109 +v -0.047943 -0.016087 0.129818 +vn 0.554573 -0.414721 -0.721426 +v -0.049543 -0.016487 0.128818 +vn 0.545810 -0.416907 -0.726829 +v -0.044043 0.016913 0.113818 +vn 0.994492 -0.095169 0.043924 +v -0.044043 0.016913 0.113818 +vn 0.994490 -0.087223 0.058149 +v -0.044043 0.018113 0.115618 +vn 0.994492 -0.095169 0.043924 +v -0.047943 -0.015487 0.131918 +vn 0.994223 -0.103203 0.029487 +v -0.047943 -0.016087 0.129818 +vn 0.564944 0.306141 0.766235 +v -0.044043 0.018113 0.115618 +vn 0.555116 0.309424 0.772077 +v -0.045643 0.018813 0.116518 +vn 0.555116 0.309424 0.772077 +v -0.047943 -0.015487 0.131918 +vn 0.544890 0.312765 0.777993 +v -0.049543 -0.015187 0.132918 +vn -0.564910 0.585518 0.581417 +v -0.045043 0.038013 0.097618 +vn -0.525876 0.600424 0.602450 +v -0.046643 0.037013 0.097218 +vn -0.564910 0.585518 0.581417 +v -0.047143 0.018113 0.115618 +vn -0.601725 0.569775 0.559717 +v -0.045643 0.018813 0.116518 +vn -0.999809 0.012334 -0.015180 +v -0.046643 0.037013 0.097218 +vn -0.999809 0.012334 -0.015180 +v -0.047143 0.016913 0.113818 +vn -0.999814 0.016040 -0.010693 +v -0.047143 0.018113 0.115618 +vn -0.999761 0.008115 -0.020287 +v -0.046643 0.035013 0.096418 +vn -0.549078 -0.569406 -0.611793 +v -0.046643 0.035013 0.096418 +vn -0.519671 -0.580859 -0.626535 +v -0.045043 0.034013 0.096018 +vn -0.549078 -0.569406 -0.611793 +v -0.045643 0.016213 0.113018 +vn -0.577997 -0.557184 -0.596209 +v -0.047143 0.016913 0.113818 +vn 0.539146 -0.592020 -0.599027 +v -0.045043 0.034013 0.096018 +vn 0.525339 -0.598680 -0.604650 +v -0.043443 0.035013 0.096418 +vn 0.539146 -0.592020 -0.599027 +v -0.044043 0.016913 0.113818 +vn 0.552697 -0.585259 -0.593294 +v -0.045643 0.016213 0.113018 +vn 0.999725 -0.014799 0.018215 +v -0.043443 0.035013 0.096418 +vn 0.999725 -0.014799 0.018215 +v -0.044043 0.018113 0.115618 +vn 0.999705 -0.020196 0.013464 +v -0.044043 0.016913 0.113818 +vn 0.999690 -0.009242 0.023105 +v -0.043443 0.037013 0.097218 +vn 0.551101 0.574816 0.604875 +v -0.043443 0.037013 0.097218 +vn 0.522540 0.589775 0.615725 +v -0.045043 0.038013 0.097618 +vn 0.551101 0.574816 0.604875 +v -0.045643 0.018813 0.116518 +vn 0.578601 0.559438 0.593507 +v -0.044043 0.018113 0.115618 +vn -0.553863 0.828768 0.079874 +v -0.043843 0.040513 0.080318 +vn -0.553863 0.828768 0.079874 +v -0.046643 0.037013 0.097218 +vn -0.543020 0.835599 0.083085 +v -0.045043 0.038013 0.097618 +vn -0.564866 0.821622 0.076571 +v -0.045443 0.039413 0.080318 +vn -0.997387 0.010461 -0.071481 +v -0.045443 0.039413 0.080318 +vn -0.997058 -0.007267 -0.076301 +v -0.045443 0.037313 0.080518 +vn -0.997387 0.010461 -0.071481 +v -0.046643 0.035013 0.096418 +vn -0.997392 0.026806 -0.067014 +v -0.046643 0.037013 0.097218 +vn -0.555492 -0.816098 -0.159415 +v -0.045443 0.037313 0.080518 +vn -0.555492 -0.816098 -0.159415 +v -0.045043 0.034013 0.096018 +vn -0.551631 -0.818590 -0.160045 +v -0.046643 0.035013 0.096418 +vn -0.559342 -0.813588 -0.158781 +v -0.043843 0.036213 0.080518 +vn 0.553716 -0.829183 -0.076510 +v -0.043843 0.036213 0.080518 +vn 0.553716 -0.829183 -0.076510 +v -0.043443 0.035013 0.096418 +vn 0.542170 -0.836753 -0.076791 +v -0.045043 0.034013 0.096018 +vn 0.564880 -0.821645 -0.076222 +v -0.042243 0.037313 0.080518 +vn 0.997387 -0.010461 0.071481 +v -0.042243 0.037313 0.080518 +vn 0.997396 0.006837 0.071792 +v -0.042243 0.039413 0.080318 +vn 0.997387 -0.010461 0.071481 +v -0.043443 0.037013 0.097218 +vn 0.997061 -0.028454 0.071134 +v -0.043443 0.035013 0.096418 +vn 0.559651 0.814039 0.155342 +v -0.042243 0.039413 0.080318 +vn 0.555495 0.816755 0.156003 +v -0.043843 0.040513 0.080318 +vn 0.555495 0.816755 0.156003 +v -0.043443 0.037013 0.097218 +vn 0.551322 0.819452 0.156660 +v -0.045043 0.038013 0.097618 +vn -0.569729 0.717350 -0.401020 +v -0.044343 0.032013 0.065518 +vn -0.569729 0.717350 -0.401020 +v -0.045843 0.031213 0.066218 +vn -0.569729 0.717350 -0.401020 +v -0.045443 0.039413 0.080318 +vn -0.515831 0.750298 -0.413488 +v -0.043843 0.040513 0.080318 +vn -0.515831 0.750298 -0.413488 +v -0.044343 0.032013 0.065518 +vn -0.999669 0.010742 0.023381 +v -0.045843 0.031213 0.066218 +vn -0.999669 0.010742 0.023381 +v -0.045443 0.037313 0.080518 +vn -0.999636 0.002559 0.026870 +v -0.045443 0.039413 0.080318 +vn -0.999625 0.018726 0.019974 +v -0.045843 0.029613 0.067718 +vn -0.548261 -0.705331 0.449352 +v -0.045843 0.029613 0.067718 +vn -0.593907 -0.673505 0.440074 +v -0.044343 0.028813 0.068518 +vn -0.548261 -0.705331 0.449352 +v -0.043843 0.036213 0.080518 +vn -0.503986 -0.733069 0.456736 +v -0.045443 0.037313 0.080518 +vn 0.538514 -0.729177 0.422260 +v -0.044343 0.028813 0.068518 +vn 0.563504 -0.717436 0.409571 +v -0.042743 0.029613 0.067718 +vn 0.538514 -0.729177 0.422260 +v -0.042243 0.037313 0.080518 +vn 0.509829 -0.741570 0.436059 +v -0.043843 0.036213 0.080518 +vn 0.999414 -0.023402 -0.024962 +v -0.042743 0.029613 0.067718 +vn 0.999483 -0.013425 -0.029220 +v -0.042743 0.031213 0.066218 +vn 0.999483 -0.013425 -0.029220 +v -0.042243 0.037313 0.080518 +vn 0.999431 -0.003198 -0.033581 +v -0.042243 0.039413 0.080318 +vn 0.547250 0.717668 -0.430662 +v -0.042743 0.031213 0.066218 +vn 0.547250 0.717668 -0.430662 +v -0.044343 0.032013 0.065518 +vn 0.547250 0.717668 -0.430662 +v -0.043843 0.040513 0.080318 +vn 0.506856 0.737246 -0.446727 +v -0.043843 0.040513 0.080318 +vn 0.506856 0.737246 -0.446727 +v -0.042243 0.039413 0.080318 +vn 0.506856 0.737246 -0.446727 +v -0.042743 0.031213 0.066218 +vn -0.975117 0.176101 0.134666 +v -0.048843 0.020113 0.058418 +vn -0.973370 0.202859 0.106768 +v -0.048843 0.019113 0.060318 +vn -0.975117 0.176101 0.134666 +v -0.045843 0.029613 0.067718 +vn -0.975428 0.150684 0.160730 +v -0.045843 0.031213 0.066218 +vn -0.572750 -0.356558 0.738122 +v -0.048843 0.019113 0.060318 +vn -0.576286 -0.354954 0.736140 +v -0.047243 0.018613 0.061318 +vn -0.576286 -0.354954 0.736140 +v -0.045843 0.029613 0.067718 +vn -0.579928 -0.353291 0.734077 +v -0.044343 0.028813 0.068518 +vn 0.578043 -0.573854 0.580137 +v -0.047243 0.018613 0.061318 +vn 0.577687 -0.573989 0.580357 +v -0.045743 0.019113 0.060318 +vn 0.577687 -0.573989 0.580357 +v -0.044343 0.028813 0.068518 +vn 0.577344 -0.574119 0.580570 +v -0.042743 0.029613 0.067718 +vn 0.975117 -0.176101 -0.134666 +v -0.045743 0.019113 0.060318 +vn 0.976035 -0.192572 -0.101353 +v -0.045743 0.020113 0.058418 +vn 0.975117 -0.176101 -0.134666 +v -0.042743 0.031213 0.066218 +vn 0.972723 -0.158653 -0.169231 +v -0.042743 0.029613 0.067718 +vn 0.000000 0.950853 0.309644 +v -0.065743 0.049013 0.123218 +vn -0.583241 -0.297541 -0.755843 +v -0.049543 -0.016487 0.128818 +vn -0.515831 0.750298 -0.413488 +v -0.045443 0.039413 0.080318 +# 480 vertices, 0 vertices normals + +f 1//1 2//2 3//3 +f 1//1 4//4 2//2 +f 5//5 6//6 7//7 +f 5//5 8//8 6//6 +f 9//9 10//10 11//11 +f 9//9 12//12 10//10 +f 13//13 14//14 15//15 +f 13//13 16//16 14//14 +f 17//17 18//18 19//19 +f 17//17 20//20 18//18 +f 21//21 22//22 23//23 +f 21//21 24//24 22//22 +f 25//25 24//24 21//21 +f 25//25 26//26 24//24 +f 27//27 26//26 25//25 +f 27//27 28//28 26//26 +f 29//29 30//30 31//31 +f 29//29 32//32 30//30 +f 33//33 32//32 29//29 +f 33//33 34//34 32//32 +f 35//35 34//34 33//33 +f 35//35 36//36 34//34 +f 37//37 38//38 39//39 +f 37//37 40//40 38//38 +f 41//41 42//42 43//43 +f 41//41 44//44 42//42 +f 45//45 46//46 47//47 +f 45//45 48//48 46//46 +f 49//49 50//50 51//51 +f 49//49 52//52 50//50 +f 53//53 54//54 55//55 +f 53//53 56//56 54//54 +f 57//57 58//58 59//59 +f 57//57 60//60 58//58 +f 61//61 62//62 63//63 +f 61//61 64//64 62//62 +f 65//65 66//66 67//67 +f 65//65 68//68 66//66 +f 69//69 70//70 71//71 +f 69//69 72//72 70//70 +f 73//73 71//71 74//74 +f 73//73 69//69 71//71 +f 75//75 76//76 77//77 +f 75//75 78//78 76//76 +f 79//79 77//77 80//80 +f 79//79 75//75 77//77 +f 81//81 80//80 82//82 +f 81//81 79//79 80//80 +f 72//72 82//82 70//70 +f 72//72 81//81 82//82 +f 83//83 84//84 85//85 +f 83//83 86//86 84//84 +f 86//86 478//478 84//84 +f 86//86 87//87 478//478 +f 88//88 89//89 90//90 +f 88//88 91//91 89//89 +f 92//92 93//93 94//94 +f 92//92 95//95 93//93 +f 96//96 97//97 98//98 +f 96//96 99//99 97//97 +f 100//100 101//101 102//102 +f 100//100 103//103 101//101 +f 104//104 105//105 106//106 +f 104//104 107//107 105//105 +f 108//108 109//109 110//110 +f 108//108 111//111 109//109 +f 112//112 113//113 114//114 +f 112//112 115//115 113//113 +f 116//116 117//117 118//118 +f 116//116 119//119 117//117 +f 120//120 121//121 122//122 +f 120//120 123//123 121//121 +f 124//124 125//125 126//126 +f 124//124 127//127 125//125 +f 128//128 127//127 124//124 +f 128//128 129//129 127//127 +f 130//130 129//129 128//128 +f 130//130 131//131 129//129 +f 132//132 131//131 130//130 +f 132//132 133//133 131//131 +f 134//134 135//135 136//136 +f 134//134 137//137 135//135 +f 138//138 136//136 139//139 +f 138//138 134//134 136//136 +f 140//140 139//139 141//141 +f 140//140 138//138 139//139 +f 142//142 141//141 143//143 +f 142//142 140//140 141//141 +f 144//144 143//143 145//145 +f 144//144 142//142 143//143 +f 146//146 145//145 147//147 +f 146//146 144//144 145//145 +f 148//148 149//149 150//150 +f 150//150 151//151 148//148 +f 152//152 153//153 154//154 +f 154//154 155//155 152//152 +f 156//156 157//157 158//158 +f 158//158 159//159 156//156 +f 160//160 161//161 162//162 +f 162//162 163//163 160//160 +f 164//164 165//165 166//166 +f 166//166 167//167 164//164 +f 168//168 169//169 170//170 +f 170//170 171//171 168//168 +f 172//172 173//173 174//174 +f 172//172 175//175 173//173 +f 176//176 177//177 178//178 +f 176//176 179//179 177//177 +f 180//180 181//181 182//182 +f 180//180 183//183 181//181 +f 184//184 185//185 186//186 +f 184//184 187//187 185//185 +f 188//188 189//189 190//190 +f 188//188 191//191 189//189 +f 192//192 193//193 194//194 +f 195//195 193//193 192//192 +f 195//195 196//196 193//193 +f 195//195 192//192 197//197 +f 198//198 199//199 200//200 +f 200//200 201//201 198//198 +f 202//202 203//203 204//204 +f 204//204 205//205 202//202 +f 206//206 207//207 208//208 +f 209//209 207//207 206//206 +f 209//209 210//210 207//207 +f 209//209 206//206 211//211 +f 212//212 213//213 214//214 +f 212//212 215//215 213//213 +f 216//216 217//217 218//218 +f 218//218 219//219 216//216 +f 220//220 221//221 222//222 +f 222//222 223//223 220//220 +f 224//224 225//225 226//226 +f 224//224 227//227 225//225 +f 228//228 229//229 230//230 +f 228//228 231//231 229//229 +f 232//232 233//233 234//234 +f 234//234 235//235 232//232 +f 236//236 237//237 238//238 +f 238//238 239//239 236//236 +f 240//240 241//241 242//242 +f 240//240 243//243 241//241 +f 244//244 245//245 246//246 +f 244//244 247//247 245//245 +f 248//248 249//249 250//250 +f 248//248 251//251 249//249 +f 252//252 253//253 254//254 +f 252//252 255//255 253//253 +f 256//256 257//257 258//258 +f 256//256 259//259 257//257 +f 260//260 261//261 262//262 +f 260//260 263//263 261//261 +f 264//264 265//265 266//266 +f 266//266 267//267 264//264 +f 268//268 269//269 270//270 +f 270//270 271//271 268//268 +f 272//272 273//273 274//274 +f 274//274 275//275 272//272 +f 276//276 277//277 278//278 +f 278//278 279//279 276//276 +f 280//280 281//281 282//282 +f 282//282 283//283 280//280 +f 284//284 285//285 286//286 +f 286//286 287//287 284//284 +f 288//288 289//289 290//290 +f 290//290 291//291 288//288 +f 292//292 293//293 294//294 +f 292//292 295//295 293//293 +f 296//296 297//297 298//298 +f 296//296 299//299 297//297 +f 300//300 301//301 302//302 +f 300//300 303//303 301//301 +f 304//304 305//305 306//306 +f 304//304 307//307 305//305 +f 308//308 309//309 310//310 +f 310//310 311//311 308//308 +f 312//312 313//313 314//314 +f 315//315 316//316 317//317 +f 318//318 319//319 320//320 +f 320//320 321//321 318//318 +f 322//322 323//323 324//324 +f 322//322 325//325 323//323 +f 326//326 327//327 328//328 +f 328//328 329//329 326//326 +f 330//330 331//331 332//332 +f 332//332 333//333 330//330 +f 334//334 335//335 336//336 +f 336//336 337//337 334//334 +f 338//338 339//339 340//340 +f 338//338 341//341 339//339 +f 342//342 343//343 344//344 +f 344//344 345//345 342//342 +f 346//346 347//347 348//348 +f 346//346 349//349 347//347 +f 350//350 351//351 352//352 +f 350//350 353//353 351//351 +f 354//354 355//355 356//356 +f 356//356 357//357 354//354 +f 358//358 359//359 360//360 +f 360//360 361//361 358//358 +f 362//362 363//363 364//364 +f 364//364 365//365 362//362 +f 366//366 367//367 368//368 +f 368//368 369//369 366//366 +f 370//370 371//371 372//372 +f 479//479 373//373 374//374 +f 375//375 376//376 377//377 +f 375//375 378//378 376//376 +f 379//379 380//380 381//381 +f 381//381 382//382 379//379 +f 383//383 384//384 385//385 +f 385//385 384//384 386//386 +f 387//387 388//388 389//389 +f 389//389 390//390 387//387 +f 391//391 392//392 393//393 +f 391//391 394//394 392//392 +f 395//395 396//396 397//397 +f 397//397 398//398 395//395 +f 399//399 400//400 401//401 +f 401//401 402//402 399//399 +f 403//403 404//404 405//405 +f 403//403 406//406 404//404 +f 407//407 408//408 409//409 +f 409//409 410//410 407//407 +f 411//411 412//412 413//413 +f 411//411 414//414 412//412 +f 415//415 416//416 417//417 +f 417//417 418//418 415//415 +f 419//419 420//420 421//421 +f 419//419 422//422 420//420 +f 423//423 424//424 425//425 +f 423//423 426//426 424//424 +f 427//427 428//428 429//429 +f 429//429 430//430 427//427 +f 431//431 432//432 433//433 +f 433//433 432//432 434//434 +f 435//435 436//436 437//437 +f 480//480 438//438 439//439 +f 440//440 441//441 442//442 +f 440//440 443//443 441//441 +f 444//444 445//445 446//446 +f 446//446 447//447 444//444 +f 448//448 449//449 450//450 +f 450//450 451//451 448//448 +f 452//452 453//453 454//454 +f 454//454 453//453 455//455 +f 456//456 457//457 458//458 +f 459//459 460//460 461//461 +f 462//462 463//463 464//464 +f 464//464 465//465 462//462 +f 466//466 467//467 468//468 +f 468//468 467//467 469//469 +f 470//470 471//471 472//472 +f 472//472 471//471 473//473 +f 474//474 475//475 476//476 +f 476//476 477//477 474//474 +# 256 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/head_camera_chull.obj b/examples/Atlas/urdf/mesh/head_camera_chull.obj new file mode 100644 index 0000000..31a9e9a --- /dev/null +++ b/examples/Atlas/urdf/mesh/head_camera_chull.obj @@ -0,0 +1,60 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object head_camera_chull.obj +# +# Vertices: 12 +# Faces: 20 +# +#### +vn 0.571672 0.813078 -0.109976 +v 0.017261 0.042257 0.060150 +vn -0.631200 -0.743956 -0.219353 +v -0.063122 -0.053010 0.090709 +vn -0.358407 -0.391624 0.847452 +v -0.054695 -0.037141 0.132992 +vn 0.085056 0.996122 -0.022526 +v -0.071491 0.061612 0.090508 +vn -0.633971 0.232218 -0.737669 +v -0.071685 0.049703 0.053559 +vn -0.374922 -0.342795 -0.861351 +v -0.041643 -0.014687 0.040918 +vn -0.611521 0.555511 0.563426 +v -0.071853 0.051286 0.122934 +vn -0.210462 0.070071 0.975088 +v -0.029502 0.013844 0.141872 +vn 0.336222 0.659369 0.672448 +v 0.003657 0.013913 0.141918 +vn 0.477838 -0.861401 0.172215 +v 0.014964 -0.038497 0.124658 +vn 0.908385 -0.040045 0.416212 +v 0.017298 0.000976 0.137603 +vn 0.607889 -0.391643 -0.690715 +v 0.017270 -0.015643 0.040846 +# 12 vertices, 0 vertices normals + +f 6//6 12//12 2//2 +f 2//2 7//7 5//5 +f 12//12 1//1 11//11 +f 12//12 10//10 2//2 +f 5//5 7//7 4//4 +f 5//5 4//4 1//1 +f 5//5 1//1 12//12 +f 9//9 11//11 1//1 +f 3//3 11//11 9//9 +f 7//7 9//9 1//1 +f 7//7 1//1 4//4 +f 8//8 3//3 9//9 +f 6//6 2//2 5//5 +f 10//10 11//11 3//3 +f 3//3 2//2 10//10 +f 7//7 3//3 8//8 +f 2//2 3//3 7//7 +f 5//5 12//12 6//6 +f 9//9 7//7 8//8 +f 10//10 12//12 11//11 +# 20 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/head_chull.obj b/examples/Atlas/urdf/mesh/head_chull.obj new file mode 100644 index 0000000..8721d93 --- /dev/null +++ b/examples/Atlas/urdf/mesh/head_chull.obj @@ -0,0 +1,60 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object head_chull.obj +# +# Vertices: 12 +# Faces: 20 +# +#### +vn 0.601828 -0.748699 -0.277942 +v -0.122043 0.091413 0.027918 +vn 0.322642 -0.648280 -0.689663 +v -0.103485 0.044761 0.133863 +vn -0.754201 0.469636 -0.458936 +v 0.017040 -0.039897 0.123666 +vn 0.465484 0.829009 -0.309950 +v -0.122043 -0.091487 0.027918 +vn 0.995520 -0.002028 -0.094530 +v -0.152817 -0.021109 0.034219 +vn -0.705624 -0.326670 -0.628794 +v 0.016668 0.010189 0.140757 +vn 0.311227 0.232691 0.921408 +v -0.121874 -0.091572 -0.031941 +vn 0.350520 -0.230470 0.907755 +v -0.121880 0.091522 -0.031931 +vn -0.464662 -0.882237 -0.075806 +v 0.019558 0.135075 -0.013253 +vn -0.377168 0.925873 -0.022451 +v 0.019675 -0.135853 -0.013632 +vn 0.288256 0.631821 -0.719521 +v -0.104376 -0.039239 0.134311 +vn -0.658352 -0.000953 0.752710 +v 0.021025 -0.000136 -0.031756 +# 12 vertices, 0 vertices normals + +f 1//1 2//2 5//5 +f 3//3 11//11 6//6 +f 7//7 8//8 5//5 +f 2//2 1//1 9//9 +f 8//8 1//1 5//5 +f 8//8 9//9 1//1 +f 11//11 5//5 2//2 +f 9//9 12//12 6//6 +f 3//3 12//12 10//10 +f 5//5 11//11 4//4 +f 10//10 11//11 3//3 +f 10//10 4//4 11//11 +f 12//12 9//9 8//8 +f 12//12 8//8 7//7 +f 2//2 9//9 6//6 +f 6//6 11//11 2//2 +f 12//12 3//3 6//6 +f 4//4 10//10 7//7 +f 5//5 4//4 7//7 +f 7//7 10//10 12//12 +# 20 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_foot.obj b/examples/Atlas/urdf/mesh/l_foot.obj new file mode 100644 index 0000000..2778313 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_foot.obj @@ -0,0 +1,871 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_foot.obj +# +# Vertices: 319 +# Faces: 536 +# +#### +v 0.006721 0.023372 -0.026154 +v 0.004797 0.000567 -0.016974 +v 0.008825 0.000567 -0.014058 +v 0.012783 0.023372 -0.014664 +v -0.004495 0.023372 -0.026428 +v -0.003427 0.000567 -0.017521 +v -0.017024 0.023372 -0.020487 +v -0.011218 0.000567 -0.013809 +v -0.018372 0.023372 -0.020170 +v -0.016315 0.000567 -0.012421 +v 0.020293 0.000567 -0.013043 +v 0.021040 0.023372 -0.013649 +v 0.012783 0.023372 -0.029887 +v 0.006721 0.023372 -0.029891 +v -0.004495 0.023372 -0.029891 +v -0.017024 0.023372 -0.029889 +v -0.018372 0.023372 -0.029889 +v 0.021040 0.023372 -0.029886 +v 0.020293 0.000567 -0.020558 +v 0.021040 0.023372 -0.021164 +v 0.006721 -0.022237 -0.026154 +v 0.012783 -0.022237 -0.014664 +v -0.004495 -0.022237 -0.026428 +v -0.017024 -0.022237 -0.020487 +v -0.018372 -0.022237 -0.020170 +v 0.021040 -0.022237 -0.013649 +v 0.006721 -0.022237 -0.029891 +v 0.012783 -0.022237 -0.029887 +v -0.004495 -0.022237 -0.029891 +v -0.017024 -0.022237 -0.029889 +v -0.018372 -0.022237 -0.029889 +v 0.021040 -0.022237 -0.029886 +v 0.021040 -0.022237 -0.021164 +v -0.063258 -0.013124 -0.014953 +v -0.017861 -0.013124 -0.014953 +v -0.017861 -0.010424 -0.004854 +v -0.051059 -0.010424 -0.004854 +v -0.033160 -0.003925 0.009945 +v -0.038459 -0.009324 0.005246 +v -0.017861 -0.009324 0.005246 +v -0.017861 -0.003925 0.009945 +v -0.033160 0.003175 0.010145 +v -0.017861 0.003175 0.010145 +v -0.038459 0.008775 0.005646 +v -0.017861 0.008775 0.005646 +v -0.017861 0.012875 -0.014453 +v -0.063258 0.012875 -0.014453 +v -0.051059 0.010075 -0.004354 +v -0.017861 0.010075 -0.004354 +v -0.069657 -0.023123 -0.019953 +v -0.017861 -0.023123 -0.019953 +v -0.017861 0.022974 -0.019453 +v -0.069657 0.022974 -0.019453 +v -0.069657 -0.023123 -0.029795 +v -0.017861 -0.023123 -0.029795 +v -0.017861 0.022974 -0.029295 +v -0.069657 0.022974 -0.029295 +v 0.055317 0.012752 -0.016871 +v 0.017281 0.012752 -0.014953 +v 0.017281 0.010052 -0.004854 +v 0.049529 0.010052 -0.006606 +v 0.032208 0.003553 0.009945 +v 0.037138 0.008952 0.005245 +v 0.017281 0.008952 0.005245 +v 0.017281 0.003553 0.009945 +v 0.032208 -0.003547 0.010144 +v 0.017281 -0.003547 0.010145 +v 0.037138 -0.009147 0.005645 +v 0.017281 -0.009147 0.005646 +v 0.017281 -0.013247 -0.014453 +v 0.055317 -0.013247 -0.016371 +v 0.049529 -0.010447 -0.006106 +v 0.017281 -0.010447 -0.004354 +v 0.071675 0.022751 -0.019953 +v 0.017281 0.022751 -0.019953 +v 0.017281 -0.023346 -0.019453 +v 0.071675 -0.023346 -0.019453 +v 0.071675 0.022751 -0.029795 +v 0.017281 0.022751 -0.029795 +v 0.017281 -0.023346 -0.029295 +v 0.071675 -0.023346 -0.029295 +v 0.110890 0.066087 -0.050160 +v 0.110890 0.066087 -0.076451 +v -0.063498 0.066087 -0.076451 +v -0.061798 0.066087 -0.050160 +v 0.154187 0.047489 -0.076451 +v 0.135488 0.056788 -0.076451 +v 0.135488 0.056788 -0.058089 +v 0.154187 0.047489 -0.062993 +v -0.087697 -0.012407 -0.076451 +v -0.087697 -0.012407 -0.050160 +v -0.087697 0.015891 -0.050160 +v -0.087697 0.015891 -0.076451 +v 0.110890 -0.062604 -0.050160 +v -0.061498 -0.062604 -0.050160 +v -0.063498 -0.062604 -0.076451 +v 0.110890 -0.062604 -0.076451 +v 0.154187 -0.044005 -0.062993 +v 0.148888 -0.044005 -0.049534 +v 0.127989 -0.053304 -0.039623 +v 0.135488 -0.053304 -0.058089 +v -0.060298 -0.062604 -0.039049 +v -0.085497 -0.040705 -0.039049 +v -0.087697 -0.040705 -0.050160 +v 0.154187 -0.013507 -0.076451 +v 0.135488 -0.016607 -0.076451 +v 0.135488 0.020090 -0.076451 +v 0.154187 0.016991 -0.076451 +v 0.172786 -0.009208 -0.055794 +v 0.172786 -0.009208 -0.066122 +v 0.172786 0.012691 -0.066122 +v 0.172786 0.012691 -0.055794 +v 0.136460 -0.017915 -0.039623 +v 0.154187 -0.013507 -0.049534 +v 0.154187 0.016991 -0.049534 +v 0.136460 0.021399 -0.039623 +v 0.172786 0.034690 -0.076451 +v 0.172786 0.034690 -0.066122 +v 0.127989 0.056788 -0.039623 +v 0.113564 0.066087 -0.039049 +v 0.126652 0.057540 -0.039017 +v 0.172786 -0.031206 -0.066122 +v 0.172786 -0.031206 -0.055794 +v 0.135488 -0.053304 -0.076451 +v 0.110890 -0.019707 -0.076451 +v 0.110890 0.023190 -0.076451 +v 0.172786 0.012691 -0.076451 +v 0.172786 -0.009208 -0.076451 +v 0.148888 0.047489 -0.049534 +v -0.087697 0.044189 -0.076451 +v -0.087697 0.044189 -0.050160 +v 0.154187 -0.044005 -0.076451 +v -0.087697 -0.040705 -0.076451 +v 0.172786 0.034690 -0.055794 +v 0.172786 -0.031206 -0.076451 +v 0.126652 -0.054057 -0.039017 +v 0.113564 -0.062604 -0.039049 +v -0.019401 -0.049105 -0.021890 +v -0.019401 0.051588 -0.021890 +v -0.059399 -0.049105 -0.021890 +v -0.024201 -0.053904 -0.021890 +v -0.054599 -0.053904 -0.021890 +v -0.059399 0.051588 -0.021890 +v -0.054599 0.056388 -0.021890 +v -0.024201 0.056388 -0.021890 +v -0.019401 -0.049105 -0.036621 +v -0.019401 0.051588 -0.036621 +v -0.054599 -0.053904 -0.036621 +v -0.024201 -0.053904 -0.036621 +v -0.059399 0.051588 -0.036621 +v -0.059399 -0.049105 -0.036621 +v -0.024201 0.056388 -0.036621 +v -0.054599 0.056388 -0.036621 +v 0.100891 0.028090 -0.022232 +v 0.100891 0.052089 -0.022232 +v 0.063893 0.028090 -0.022232 +v 0.097591 0.024490 -0.022232 +v 0.067193 0.024490 -0.022232 +v 0.063893 0.052089 -0.022232 +v 0.067193 0.055388 -0.022232 +v 0.097591 0.055388 -0.022232 +v 0.100891 0.028090 -0.035056 +v 0.100891 0.052089 -0.035056 +v 0.067193 0.024490 -0.035056 +v 0.097591 0.024490 -0.035056 +v 0.063893 0.052089 -0.035056 +v 0.063893 0.028090 -0.035056 +v 0.097591 0.055388 -0.035056 +v 0.067193 0.055388 -0.035056 +v 0.100891 -0.050905 -0.022232 +v 0.100891 -0.026906 -0.022232 +v 0.063893 -0.050905 -0.022232 +v 0.097591 -0.054204 -0.022232 +v 0.067193 -0.054204 -0.022232 +v 0.063893 -0.026906 -0.022232 +v 0.067193 -0.023207 -0.022232 +v 0.097591 -0.023207 -0.022232 +v 0.100891 -0.050905 -0.035056 +v 0.100891 -0.026906 -0.035056 +v 0.067193 -0.054204 -0.035056 +v 0.097591 -0.054204 -0.035056 +v 0.063893 -0.026906 -0.035056 +v 0.063893 -0.050905 -0.035056 +v 0.097591 -0.023207 -0.035056 +v 0.067193 -0.023207 -0.035056 +v 0.110090 -0.017507 -0.020801 +v 0.110090 0.017591 -0.020801 +v 0.073793 -0.017507 -0.020801 +v 0.106790 -0.022306 -0.020801 +v 0.077092 -0.022306 -0.020801 +v 0.073792 0.017591 -0.020801 +v 0.077092 0.022890 -0.020801 +v 0.106790 0.022890 -0.020801 +v 0.110090 -0.017507 -0.035838 +v 0.110090 0.017591 -0.035838 +v 0.077092 -0.022306 -0.035838 +v 0.106790 -0.022306 -0.035838 +v 0.073792 0.017591 -0.035838 +v 0.073793 -0.017507 -0.035838 +v 0.106790 0.022890 -0.035838 +v 0.077092 0.022890 -0.035838 +v 0.135602 -0.016858 -0.039017 +v -0.085497 0.015891 -0.039049 +v -0.085497 0.044189 -0.039049 +v 0.059693 0.028090 -0.026931 +v 0.059693 0.052089 -0.026931 +v -0.012202 0.028090 -0.026931 +v 0.056294 0.024490 -0.026931 +v -0.008902 0.024490 -0.026931 +v -0.012202 0.052089 -0.026931 +v -0.008902 0.055388 -0.026931 +v 0.056294 0.055388 -0.026931 +v 0.059693 0.028090 -0.033831 +v 0.059693 0.052089 -0.033831 +v -0.008902 0.024490 -0.033831 +v 0.056294 0.024490 -0.033831 +v -0.012202 0.052089 -0.033831 +v -0.012202 0.028090 -0.033831 +v 0.056294 0.055388 -0.033831 +v -0.008902 0.055388 -0.033831 +v 0.059693 -0.050905 -0.026931 +v 0.059693 -0.026906 -0.026931 +v -0.012202 -0.050905 -0.026931 +v 0.056294 -0.054204 -0.026931 +v -0.008902 -0.054204 -0.026931 +v -0.012202 -0.026906 -0.026931 +v -0.008902 -0.023206 -0.026931 +v 0.056294 -0.023207 -0.026931 +v 0.059693 -0.050905 -0.033831 +v 0.059693 -0.026906 -0.033831 +v -0.008902 -0.054204 -0.033831 +v 0.056294 -0.054204 -0.033831 +v -0.012202 -0.026906 -0.033831 +v -0.012202 -0.050905 -0.033831 +v 0.056294 -0.023207 -0.033831 +v -0.008902 -0.023206 -0.033831 +v -0.060449 0.066087 -0.039049 +v 0.135602 0.020341 -0.039017 +v -0.085497 -0.012407 -0.039049 +v -0.090164 0.025203 -0.039049 +v -0.071747 0.071664 -0.039049 +v -0.071584 -0.068181 -0.039049 +v -0.090164 -0.021719 -0.039049 +v 0.108368 0.071664 -0.039048 +v 0.116658 0.062376 -0.039017 +v 0.135826 0.021953 -0.039017 +v 0.135826 -0.018470 -0.039017 +v -0.090164 -0.006078 -0.039049 +v -0.090164 0.009562 -0.039049 +v 0.108368 -0.068181 -0.039049 +v 0.116659 -0.058893 -0.039017 +v -0.090164 0.025203 -0.028170 +v -0.071747 0.071664 -0.028170 +v -0.071584 -0.068181 -0.028170 +v -0.090164 -0.021719 -0.028170 +v 0.108368 0.071664 -0.028169 +v 0.116659 0.062376 -0.028138 +v 0.135826 0.021953 -0.028138 +v 0.135826 -0.018470 -0.028138 +v -0.090164 -0.006078 -0.028170 +v -0.090164 0.009562 -0.028170 +v 0.108368 -0.068181 -0.028170 +v 0.116658 -0.058893 -0.028138 +v 0.037418 0.032957 -0.007357 +v 0.041405 0.032957 -0.007357 +v 0.041404 0.032957 -0.026011 +v 0.036187 0.032957 -0.009913 +v 0.017412 0.032957 -0.026009 +v 0.033421 0.032957 -0.010545 +v 0.017416 0.032957 -0.014107 +v 0.031203 0.032957 -0.008776 +v 0.027385 0.032957 -0.004100 +v 0.031203 0.032957 -0.005938 +v 0.032478 0.032957 -0.000038 +v 0.033421 0.032957 -0.004169 +v 0.038830 0.032957 -0.001487 +v 0.036187 0.032957 -0.004801 +v 0.037418 0.025219 -0.007357 +v 0.036187 0.025219 -0.009913 +v 0.041404 0.025219 -0.026011 +v 0.041405 0.025219 -0.007357 +v 0.033421 0.025219 -0.010545 +v 0.017412 0.025219 -0.026009 +v 0.031203 0.025219 -0.008776 +v 0.017416 0.025219 -0.014107 +v 0.031203 0.025219 -0.005938 +v 0.027385 0.025219 -0.004100 +v 0.033421 0.025219 -0.004169 +v 0.032478 0.025219 -0.000038 +v 0.036187 0.025219 -0.004801 +v 0.038830 0.025219 -0.001487 +v 0.037418 -0.024718 -0.007357 +v 0.041405 -0.024718 -0.007357 +v 0.041404 -0.024718 -0.026011 +v 0.036187 -0.024718 -0.009913 +v 0.017412 -0.024718 -0.026009 +v 0.033421 -0.024718 -0.010545 +v 0.017416 -0.024718 -0.014107 +v 0.031203 -0.024718 -0.008776 +v 0.027385 -0.024718 -0.004100 +v 0.031203 -0.024718 -0.005938 +v 0.032478 -0.024718 -0.000038 +v 0.033421 -0.024718 -0.004169 +v 0.038830 -0.024718 -0.001487 +v 0.036187 -0.024718 -0.004801 +v 0.037418 -0.032456 -0.007357 +v 0.036187 -0.032456 -0.009913 +v 0.041404 -0.032456 -0.026011 +v 0.041405 -0.032456 -0.007357 +v 0.033421 -0.032456 -0.010545 +v 0.017412 -0.032456 -0.026009 +v 0.031203 -0.032456 -0.008776 +v 0.017416 -0.032456 -0.014107 +v 0.031203 -0.032456 -0.005938 +v 0.027385 -0.032456 -0.004100 +v 0.033421 -0.032456 -0.004169 +v 0.032478 -0.032456 -0.000038 +v 0.036187 -0.032456 -0.004801 +v 0.038830 -0.032456 -0.001487 +# 319 vertices, 0 vertices normals + +f 4 2 3 +f 2 4 1 +f 5 2 1 +f 2 5 6 +f 5 8 6 +f 8 5 7 +f 10 7 9 +f 7 10 8 +f 11 12 4 +f 4 3 11 +f 4 13 1 +f 1 13 14 +f 5 1 14 +f 5 14 15 +f 5 16 7 +f 16 5 15 +f 7 17 9 +f 17 7 16 +f 12 18 4 +f 4 18 13 +f 12 11 19 +f 12 19 20 +f 22 2 21 +f 2 22 3 +f 6 23 2 +f 2 23 21 +f 8 23 6 +f 23 8 24 +f 10 24 8 +f 24 10 25 +f 3 22 11 +f 11 22 26 +f 28 22 21 +f 28 21 27 +f 23 27 21 +f 27 23 29 +f 23 30 29 +f 30 23 24 +f 24 31 30 +f 31 24 25 +f 22 32 26 +f 32 22 28 +f 26 19 11 +f 19 26 33 +f 37 35 36 +f 35 37 34 +f 38 40 41 +f 40 38 39 +f 42 41 43 +f 41 42 38 +f 45 42 43 +f 42 45 44 +f 48 49 46 +f 48 46 47 +f 47 34 48 +f 48 34 37 +f 36 46 49 +f 46 36 35 +f 34 51 35 +f 51 34 50 +f 39 36 40 +f 36 39 37 +f 52 53 47 +f 52 47 46 +f 44 45 49 +f 49 48 44 +f 44 38 42 +f 38 44 37 +f 37 39 38 +f 37 44 48 +f 47 50 34 +f 50 47 53 +f 52 35 51 +f 35 52 46 +f 40 43 41 +f 43 40 49 +f 49 45 43 +f 49 40 36 +f 51 50 54 +f 51 54 55 +f 53 52 56 +f 53 56 57 +f 50 53 57 +f 50 57 54 +f 51 56 52 +f 56 51 55 +f 61 59 60 +f 59 61 58 +f 65 62 64 +f 63 64 62 +f 67 62 65 +f 62 67 66 +f 69 66 67 +f 66 69 68 +f 72 73 70 +f 72 70 71 +f 71 61 72 +f 61 71 58 +f 60 70 73 +f 70 60 59 +f 75 58 74 +f 58 75 59 +f 63 60 64 +f 60 63 61 +f 76 77 71 +f 71 70 76 +f 68 69 73 +f 73 72 68 +f 62 68 61 +f 68 62 66 +f 61 63 62 +f 61 68 72 +f 74 71 77 +f 71 74 58 +f 76 59 75 +f 59 76 70 +f 64 67 65 +f 67 64 73 +f 73 69 67 +f 73 64 60 +f 78 75 74 +f 75 78 79 +f 76 81 77 +f 81 76 80 +f 74 77 81 +f 74 81 78 +f 75 80 76 +f 80 75 79 +f 85 83 84 +f 83 85 82 +f 89 87 88 +f 87 89 86 +f 91 93 90 +f 93 91 92 +f 95 97 94 +f 97 95 96 +f 101 99 100 +f 99 101 98 +f 103 95 102 +f 95 103 104 +f 106 107 105 +f 105 107 108 +f 109 111 112 +f 111 109 110 +f 116 113 115 +f 115 113 114 +f 118 86 89 +f 86 118 117 +f 82 121 119 +f 121 82 120 +f 88 82 119 +f 123 98 122 +f 98 123 99 +f 101 97 124 +f 97 101 94 +f 125 107 106 +f 107 125 126 +f 105 127 128 +f 127 105 108 +f 115 109 112 +f 109 115 114 +f 125 90 93 +f 125 93 126 +f 129 88 119 +f 88 129 89 +f 84 131 85 +f 131 84 130 +f 98 124 132 +f 124 98 101 +f 104 96 95 +f 96 104 133 +f 110 127 111 +f 127 110 128 +f 134 89 129 +f 89 134 118 +f 88 83 82 +f 83 88 87 +f 122 132 135 +f 132 122 98 +f 94 136 137 +f 94 100 136 +f 101 100 94 +f 138 140 141 +f 139 140 138 +f 140 142 141 +f 140 139 143 +f 139 144 143 +f 144 139 145 +f 139 138 146 +f 139 146 147 +f 141 142 148 +f 141 148 149 +f 140 143 150 +f 140 150 151 +f 145 153 144 +f 153 145 152 +f 157 155 156 +f 155 157 154 +f 156 158 157 +f 156 160 159 +f 160 156 155 +f 160 155 161 +f 155 154 162 +f 155 162 163 +f 158 165 157 +f 165 158 164 +f 159 167 156 +f 167 159 166 +f 161 169 160 +f 169 161 168 +f 157 165 154 +f 154 165 162 +f 155 168 161 +f 168 155 163 +f 156 167 158 +f 158 167 164 +f 160 166 159 +f 166 160 169 +f 173 171 172 +f 171 173 170 +f 172 174 173 +f 172 176 175 +f 176 172 171 +f 176 171 177 +f 171 170 178 +f 171 178 179 +f 173 174 180 +f 173 180 181 +f 175 183 172 +f 183 175 182 +f 176 177 184 +f 176 184 185 +f 173 178 170 +f 178 173 181 +f 171 179 177 +f 177 179 184 +f 183 174 172 +f 174 183 180 +f 176 185 175 +f 175 185 182 +f 186 188 189 +f 187 188 186 +f 188 190 189 +f 191 188 187 +f 187 192 191 +f 192 187 193 +f 187 186 194 +f 187 194 195 +f 190 197 189 +f 197 190 196 +f 188 191 198 +f 188 198 199 +f 193 201 192 +f 201 193 200 +f 189 194 186 +f 194 189 197 +f 187 195 193 +f 193 195 200 +f 188 199 190 +f 190 199 196 +f 192 201 191 +f 191 201 198 +f 141 149 138 +f 138 149 146 +f 139 147 145 +f 145 147 152 +f 151 142 140 +f 142 151 148 +f 144 153 143 +f 143 153 150 +f 104 91 133 +f 91 90 133 +f 92 130 93 +f 130 92 131 +f 132 106 105 +f 106 132 124 +f 107 86 108 +f 86 107 87 +f 123 110 109 +f 110 123 122 +f 111 134 112 +f 134 111 118 +f 113 99 114 +f 99 113 100 +f 116 129 119 +f 129 116 115 +f 124 125 106 +f 125 124 97 +f 126 87 107 +f 87 126 83 +f 108 117 127 +f 117 108 86 +f 135 105 128 +f 105 135 132 +f 114 123 109 +f 123 114 99 +f 134 115 112 +f 115 134 129 +f 202 100 113 +f 100 202 136 +f 96 125 97 +f 125 96 133 +f 125 133 90 +f 93 84 83 +f 84 93 130 +f 93 83 126 +f 204 92 203 +f 92 204 131 +f 122 128 110 +f 128 122 135 +f 127 118 111 +f 118 127 117 +f 208 206 207 +f 206 208 205 +f 207 209 208 +f 211 207 206 +f 207 211 210 +f 211 206 212 +f 206 205 213 +f 206 213 214 +f 208 209 215 +f 208 215 216 +f 207 210 217 +f 207 217 218 +f 211 212 219 +f 211 219 220 +f 208 213 205 +f 213 208 216 +f 206 214 212 +f 212 214 219 +f 218 209 207 +f 209 218 215 +f 211 220 210 +f 210 220 217 +f 224 222 223 +f 222 224 221 +f 223 225 224 +f 227 223 222 +f 223 227 226 +f 227 222 228 +f 222 221 229 +f 222 229 230 +f 225 232 224 +f 232 225 231 +f 223 226 233 +f 223 233 234 +f 227 228 235 +f 227 235 236 +f 224 232 221 +f 221 232 229 +f 222 230 228 +f 228 230 235 +f 234 225 223 +f 225 234 231 +f 227 236 226 +f 226 236 233 +f 85 204 237 +f 204 85 131 +f 113 116 202 +f 202 116 238 +f 82 237 120 +f 237 82 85 +f 92 91 203 +f 239 203 91 +f 102 94 137 +f 94 102 95 +f 119 238 116 +f 238 119 121 +f 91 104 239 +f 103 239 104 +f 240 241 237 +f 242 243 102 +f 121 120 245 +f 244 245 120 +f 202 246 247 +f 246 202 238 +f 120 237 244 +f 241 244 237 +f 203 248 249 +f 248 203 239 +f 250 242 102 +f 102 137 250 +f 251 250 137 +f 137 136 251 +f 245 246 121 +f 247 251 136 +f 243 239 103 +f 239 243 248 +f 204 203 240 +f 203 249 240 +f 241 252 253 +f 252 241 240 +f 243 242 255 +f 254 255 242 +f 256 245 244 +f 245 256 257 +f 247 258 259 +f 258 247 246 +f 244 241 256 +f 253 256 241 +f 260 261 248 +f 261 249 248 +f 242 250 254 +f 262 254 250 +f 263 262 251 +f 262 250 251 +f 246 245 258 +f 257 258 245 +f 251 247 263 +f 259 263 247 +f 255 260 243 +f 260 248 243 +f 261 252 249 +f 252 240 249 +f 261 256 253 +f 261 253 252 +f 258 256 261 +f 256 258 257 +f 254 263 261 +f 258 261 263 +f 263 259 258 +f 254 262 263 +f 254 261 260 +f 254 260 255 +f 267 265 266 +f 265 267 264 +f 266 269 267 +f 269 266 268 +f 269 268 270 +f 269 270 271 +f 271 272 273 +f 272 271 270 +f 272 275 273 +f 275 272 274 +f 277 274 276 +f 274 277 275 +f 265 277 276 +f 277 265 264 +f 281 279 280 +f 279 281 278 +f 280 282 283 +f 282 280 279 +f 283 282 285 +f 285 282 284 +f 286 287 284 +f 287 285 284 +f 289 286 288 +f 286 289 287 +f 291 289 288 +f 291 288 290 +f 281 291 290 +f 281 290 278 +f 281 266 265 +f 266 281 280 +f 278 264 267 +f 278 267 279 +f 283 266 280 +f 266 283 268 +f 279 267 269 +f 269 282 279 +f 285 270 268 +f 285 268 283 +f 269 284 282 +f 284 269 271 +f 287 272 270 +f 287 270 285 +f 273 286 284 +f 273 284 271 +f 274 287 289 +f 287 274 272 +f 286 275 288 +f 275 286 273 +f 276 289 291 +f 289 276 274 +f 288 277 290 +f 277 288 275 +f 281 276 291 +f 276 281 265 +f 290 277 264 +f 290 264 278 +f 295 293 294 +f 293 295 292 +f 294 297 295 +f 297 294 296 +f 297 296 298 +f 297 298 299 +f 299 300 301 +f 300 299 298 +f 300 303 301 +f 303 300 302 +f 305 302 304 +f 302 305 303 +f 293 305 304 +f 305 293 292 +f 309 307 308 +f 307 309 306 +f 308 310 311 +f 310 308 307 +f 311 310 313 +f 313 310 312 +f 314 315 312 +f 315 313 312 +f 317 314 316 +f 314 317 315 +f 319 317 316 +f 319 316 318 +f 309 319 318 +f 309 318 306 +f 309 294 293 +f 294 309 308 +f 306 292 295 +f 306 295 307 +f 311 294 308 +f 294 311 296 +f 307 295 297 +f 297 310 307 +f 313 298 296 +f 313 296 311 +f 297 312 310 +f 312 297 299 +f 315 300 298 +f 315 298 313 +f 312 301 314 +f 301 312 299 +f 302 315 317 +f 315 302 300 +f 314 303 316 +f 303 314 301 +f 304 317 319 +f 317 304 302 +f 316 305 318 +f 305 316 303 +f 319 309 304 +f 304 309 293 +f 318 305 292 +f 318 292 306 +# 536 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_foot_chull.obj b/examples/Atlas/urdf/mesh/l_foot_chull.obj new file mode 100644 index 0000000..f8fbdda --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_foot_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_foot_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.032478 -0.032456 -0.000038 +v -0.030949 -0.000206 0.012026 +v 0.029024 -0.000680 0.011616 +v 0.032478 0.032957 -0.000038 +v -0.090794 -0.021605 -0.028558 +v -0.087663 -0.040716 -0.048187 +v -0.087697 -0.040705 -0.076451 +v -0.071584 -0.068181 -0.039049 +v -0.071584 -0.068181 -0.028170 +v 0.135826 0.021953 -0.028138 +v 0.172786 -0.031206 -0.055794 +v 0.172786 0.034690 -0.055794 +v 0.134984 -0.021567 -0.028083 +v -0.087697 0.044189 -0.076451 +v -0.071747 0.071664 -0.039049 +v 0.108368 0.071664 -0.039048 +v 0.111018 0.071299 -0.027900 +v -0.071747 0.071664 -0.028170 +v 0.108368 -0.068181 -0.039049 +v 0.108368 -0.068181 -0.028170 +v -0.063498 -0.062604 -0.076451 +v 0.115396 -0.062582 -0.076451 +v -0.090933 0.030080 -0.029310 +v 0.172699 0.037354 -0.076448 +v 0.172760 -0.033536 -0.076444 +v -0.063498 0.066087 -0.076451 +v 0.110890 0.066087 -0.076451 +# 27 vertices, 0 vertices normals + +f 2 5 23 +f 23 18 2 +f 2 9 5 +f 21 7 8 +f 24 12 17 +f 9 1 20 +f 2 1 9 +f 6 5 9 +f 13 11 20 +f 25 20 11 +f 15 26 27 +f 15 27 16 +f 15 14 26 +f 12 10 17 +f 10 3 17 +f 4 2 18 +f 4 18 17 +f 17 3 4 +f 2 3 1 +f 20 1 3 +f 3 13 20 +f 3 10 13 +f 4 3 2 +f 27 24 16 +f 7 5 6 +f 8 7 6 +f 6 9 8 +f 12 11 10 +f 10 11 13 +f 14 23 5 +f 14 5 7 +f 15 16 17 +f 18 15 17 +f 19 8 9 +f 19 9 20 +f 19 22 21 +f 19 21 8 +f 19 25 22 +f 19 20 25 +f 23 15 18 +f 14 15 23 +f 16 24 17 +f 25 11 12 +f 24 25 12 +f 27 21 22 +f 7 21 27 +f 14 27 26 +f 27 14 7 +f 27 25 24 +f 22 25 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_lglut.obj b/examples/Atlas/urdf/mesh/l_lglut.obj new file mode 100644 index 0000000..2676bb6 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_lglut.obj @@ -0,0 +1,1309 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_lglut.obj +# +# Vertices: 446 +# Faces: 847 +# +#### +v 0.049216 0.014991 -0.015218 +v 0.082320 0.014991 -0.015218 +v 0.082320 0.000322 -0.021294 +v 0.049216 0.000322 -0.021294 +v 0.049216 0.021067 -0.000550 +v 0.082320 0.021067 -0.000550 +v 0.049216 0.014991 0.014119 +v 0.082320 0.014991 0.014119 +v 0.049216 0.000322 0.020195 +v 0.082320 0.000322 0.020195 +v 0.049216 -0.014346 0.014119 +v 0.082320 -0.014346 0.014119 +v 0.049216 -0.020422 -0.000550 +v 0.082320 -0.020422 -0.000550 +v 0.049216 -0.014346 -0.015218 +v 0.082320 -0.014346 -0.015218 +v 0.082320 0.010764 -0.010991 +v 0.082320 0.000322 -0.015316 +v 0.082320 0.015089 -0.000550 +v 0.082320 0.010764 0.009892 +v 0.082320 0.000322 0.014217 +v 0.082320 -0.010119 0.009892 +v 0.082320 -0.014444 -0.000550 +v 0.082320 -0.010119 -0.010991 +v 0.055189 0.007457 -0.007684 +v 0.055189 0.000322 -0.010640 +v 0.055189 0.010412 -0.000550 +v 0.055189 0.007457 0.006585 +v 0.055189 0.000322 0.009540 +v 0.055189 -0.006812 0.006585 +v 0.055189 -0.009768 -0.000550 +v 0.055189 -0.006812 -0.007684 +v 0.049216 0.000322 -0.010346 +v 0.049216 0.007249 -0.007477 +v 0.049216 0.010119 -0.000550 +v 0.049216 0.007249 0.006377 +v 0.049216 0.000322 0.009247 +v 0.049216 -0.006605 0.006377 +v 0.049216 -0.009474 -0.000550 +v 0.049216 -0.006605 -0.007477 +v 0.055284 0.047975 -0.002475 +v 0.071703 0.047975 -0.002475 +v 0.071703 0.047192 -0.010830 +v 0.055284 0.047192 -0.010830 +v 0.055284 0.044597 0.006092 +v 0.071703 0.044597 0.006092 +v 0.055284 0.036029 0.009641 +v 0.071703 0.036029 0.009641 +v 0.055284 0.036029 -0.014591 +v 0.055284 0.036029 -0.007716 +v 0.055284 0.039735 -0.006181 +v 0.071703 0.039735 -0.006181 +v 0.071703 0.036029 -0.007716 +v 0.071703 0.036029 -0.014591 +v 0.055284 0.041270 -0.002475 +v 0.071703 0.041270 -0.002475 +v 0.055284 0.039735 0.001231 +v 0.071703 0.039735 0.001231 +v 0.055284 0.036029 0.002765 +v 0.071703 0.036029 0.002765 +v 0.055284 0.032324 0.001231 +v 0.055284 0.027462 0.006092 +v 0.071703 0.027462 0.006092 +v 0.071703 0.032324 0.001231 +v 0.055284 0.030789 -0.002475 +v 0.055284 0.023913 -0.002475 +v 0.071703 0.023913 -0.002475 +v 0.071703 0.030789 -0.002475 +v 0.055284 0.032324 -0.006181 +v 0.055284 0.027462 -0.011042 +v 0.071703 0.027462 -0.011042 +v 0.071703 0.032324 -0.006181 +v 0.055284 0.046734 -0.017370 +v 0.055284 0.029972 -0.017370 +v 0.071703 0.046734 -0.017407 +v 0.071703 0.029972 -0.017174 +v 0.055284 0.003224 0.018663 +v 0.071703 0.003224 0.018663 +v 0.055284 0.016994 0.008892 +v 0.071703 0.016994 0.008892 +v 0.055284 0.019783 -0.002475 +v 0.071703 0.019783 -0.002475 +v 0.055284 0.011265 -0.017407 +v 0.071703 0.011260 -0.017407 +v 0.080771 0.031831 -0.033083 +v 0.080771 0.046193 -0.033083 +v 0.072395 0.046193 -0.023942 +v 0.072395 0.031831 -0.023942 +v 0.080230 0.031831 -0.045470 +v 0.080230 0.046193 -0.045470 +v 0.070474 0.031831 -0.067285 +v 0.068248 0.031831 -0.046040 +v 0.062213 0.031831 -0.045777 +v 0.058702 0.031831 -0.053306 +v 0.058702 0.046193 -0.053306 +v 0.062213 0.046193 -0.045777 +v 0.068248 0.046193 -0.046040 +v 0.070474 0.046193 -0.067285 +v 0.058132 0.031831 -0.041323 +v 0.050326 0.031831 -0.049531 +v 0.050326 0.046193 -0.049531 +v 0.058132 0.046193 -0.041323 +v 0.058396 0.031831 -0.035289 +v 0.050867 0.031831 -0.031778 +v 0.050867 0.046193 -0.031778 +v 0.058396 0.046193 -0.035289 +v 0.062849 0.031831 -0.031208 +v 0.060008 0.031831 -0.023402 +v 0.060008 0.046193 -0.023402 +v 0.062849 0.046193 -0.031208 +v 0.068884 0.031831 -0.031471 +v 0.068884 0.046193 -0.031471 +v 0.072965 0.031831 -0.035925 +v 0.072965 0.046193 -0.035925 +v 0.072701 0.031831 -0.041959 +v 0.072701 0.046193 -0.041959 +v 0.044195 0.046770 -0.017370 +v 0.043404 0.033375 -0.017370 +v 0.044104 0.031831 -0.031778 +v 0.044658 0.031831 -0.049531 +v 0.044658 0.046193 -0.049531 +v 0.044104 0.046193 -0.031778 +v 0.047869 0.031831 -0.023402 +v 0.047869 0.046193 -0.023402 +v 0.035365 0.046714 -0.031948 +v 0.035365 0.047470 -0.045987 +v 0.035365 0.046385 -0.023528 +v 0.035365 0.046770 -0.017416 +v 0.035365 0.035782 -0.012919 +v 0.035365 0.035782 -0.006900 +v 0.035365 0.039591 -0.005322 +v 0.035365 0.041169 -0.001514 +v 0.035365 0.047188 -0.001514 +v 0.035365 0.039591 0.002295 +v 0.035365 0.043847 0.006551 +v 0.035365 0.035782 0.003872 +v 0.035365 0.035782 0.009892 +v 0.035365 0.031974 0.002295 +v 0.035365 0.027717 0.006551 +v 0.035365 0.030396 -0.001514 +v 0.035365 0.024377 -0.001514 +v 0.035365 0.031974 -0.005322 +v 0.035365 0.020682 -0.010746 +v 0.044195 0.039591 -0.005322 +v 0.044195 0.035782 -0.006900 +v 0.044195 0.041169 -0.001514 +v 0.044195 0.047188 -0.001514 +v 0.044195 0.039591 0.002295 +v 0.044195 0.043847 0.006551 +v 0.044195 0.035782 0.003872 +v 0.044195 0.035782 0.009892 +v 0.044195 0.031974 0.002295 +v 0.044195 0.027717 0.006551 +v 0.044195 0.030396 -0.001514 +v 0.044195 0.024377 -0.001514 +v 0.044195 0.031974 -0.005322 +v 0.044195 0.020682 -0.010746 +v 0.064714 -0.009751 -0.081368 +v 0.060487 -0.009751 -0.077141 +v 0.050046 -0.009751 -0.081466 +v 0.050046 -0.009751 -0.087444 +v 0.070790 -0.009751 -0.066700 +v 0.064812 -0.009751 -0.066700 +v 0.064714 -0.009751 -0.052031 +v 0.060487 -0.009751 -0.056258 +v 0.050046 -0.009751 -0.045955 +v 0.050046 -0.009751 -0.051933 +v 0.035377 -0.009751 -0.052031 +v 0.039604 -0.009751 -0.056258 +v 0.029301 -0.009751 -0.066700 +v 0.035279 -0.009751 -0.066700 +v 0.035377 -0.009751 -0.081368 +v 0.039604 -0.009751 -0.077141 +v 0.050046 0.055819 -0.081466 +v 0.060487 0.055819 -0.077141 +v 0.064714 0.055819 -0.081368 +v 0.050046 0.055819 -0.087444 +v 0.064812 0.055819 -0.066700 +v 0.070790 0.055819 -0.066700 +v 0.060487 0.055819 -0.056258 +v 0.064714 0.055819 -0.052031 +v 0.050046 0.055819 -0.051933 +v 0.050046 0.055819 -0.045955 +v 0.039604 0.055819 -0.056258 +v 0.035377 0.055819 -0.052031 +v 0.035279 0.055819 -0.066700 +v 0.029301 0.055819 -0.066700 +v 0.039604 0.055819 -0.077141 +v 0.035377 0.055819 -0.081368 +v 0.080399 -0.000818 -0.033083 +v 0.080399 0.013543 -0.033083 +v 0.072023 0.013543 -0.023942 +v 0.072023 -0.000818 -0.023942 +v 0.079858 -0.000818 -0.045470 +v 0.079858 0.013544 -0.045470 +v 0.070102 -0.000818 -0.067285 +v 0.067876 -0.000818 -0.046040 +v 0.061841 -0.000818 -0.045777 +v 0.058330 -0.000818 -0.053306 +v 0.058330 0.013544 -0.053306 +v 0.061841 0.013544 -0.045777 +v 0.067876 0.013543 -0.046040 +v 0.070102 0.013543 -0.067285 +v 0.057760 -0.000818 -0.041323 +v 0.049954 -0.000818 -0.049531 +v 0.049954 0.013544 -0.049531 +v 0.057760 0.013544 -0.041323 +v 0.058024 -0.000818 -0.035289 +v 0.050495 -0.000818 -0.031778 +v 0.050495 0.013543 -0.031778 +v 0.058024 0.013543 -0.035289 +v 0.062477 -0.000818 -0.031208 +v 0.059636 -0.000818 -0.023402 +v 0.059636 0.013543 -0.023402 +v 0.062477 0.013543 -0.031208 +v 0.068512 -0.000818 -0.031471 +v 0.068512 0.013543 -0.031471 +v 0.072593 -0.000818 -0.035925 +v 0.072593 0.013543 -0.035925 +v 0.072329 -0.000818 -0.041959 +v 0.072329 0.013544 -0.041959 +v 0.071331 0.014085 -0.017407 +v 0.054912 0.014085 -0.017407 +v 0.071331 -0.002677 -0.017174 +v 0.054912 -0.002677 -0.017174 +v 0.049954 0.033093 -0.049531 +v 0.050495 0.033093 -0.031778 +v 0.059636 0.033093 -0.023402 +v 0.054912 0.033634 -0.017407 +v 0.035365 0.035588 -0.019159 +v 0.035365 0.012325 -0.019303 +v 0.046799 0.012325 -0.019303 +v 0.035365 0.036248 -0.027621 +v 0.035365 -0.001300 -0.030211 +v 0.051187 -0.001300 -0.030211 +v 0.035365 0.037759 -0.045949 +v 0.035365 -0.004202 -0.045979 +v 0.049838 -0.004202 -0.047749 +v 0.043404 0.014434 -0.017370 +v 0.055284 0.011032 -0.017370 +v -0.061574 0.000322 -0.021294 +v -0.061574 0.014991 -0.015218 +v -0.032467 0.014991 -0.015218 +v -0.032467 0.000322 -0.021294 +v -0.061574 0.021067 -0.000550 +v -0.032467 0.021067 -0.000550 +v -0.061574 0.014991 0.014119 +v -0.032467 0.014991 0.014119 +v -0.061574 0.000322 0.020195 +v -0.032467 0.000322 0.020195 +v -0.061574 -0.014346 0.014119 +v -0.032467 -0.014346 0.014119 +v -0.061574 -0.020422 -0.000550 +v -0.032467 -0.020422 -0.000550 +v -0.061574 -0.014346 -0.015218 +v -0.032467 -0.014346 -0.015218 +v -0.061574 0.000322 -0.015316 +v -0.061574 0.010764 -0.010991 +v -0.061574 0.015089 -0.000550 +v -0.061574 0.010764 0.009892 +v -0.061574 0.000322 0.014217 +v -0.061574 -0.010119 0.009892 +v -0.061574 -0.014444 -0.000550 +v -0.061574 -0.010119 -0.010991 +v -0.035239 0.000322 -0.010640 +v -0.035239 0.007457 -0.007684 +v -0.035239 0.010413 -0.000550 +v -0.035239 0.007457 0.006585 +v -0.035239 0.000322 0.009540 +v -0.035239 -0.006812 0.006585 +v -0.035239 -0.009768 -0.000550 +v -0.035239 -0.006812 -0.007684 +v -0.032467 0.007250 -0.007477 +v -0.032467 0.000322 -0.010346 +v -0.032467 0.010119 -0.000550 +v -0.032467 0.007250 0.006377 +v -0.032467 0.000322 0.009247 +v -0.032467 -0.006605 0.006377 +v -0.032467 -0.009474 -0.000550 +v -0.032467 -0.006605 -0.007477 +v -0.052643 0.046087 -0.010830 +v -0.052643 0.047975 -0.002475 +v -0.037053 0.047975 -0.002475 +v -0.037053 0.046087 -0.010830 +v -0.052643 0.044596 0.006092 +v -0.037053 0.044596 0.006092 +v -0.052643 0.036029 0.009641 +v -0.037053 0.036029 0.009641 +v -0.037053 0.039735 -0.006181 +v -0.037053 0.036029 -0.007716 +v -0.037053 0.036029 -0.014591 +v -0.052643 0.036029 -0.007716 +v -0.052643 0.039735 -0.006181 +v -0.052643 0.036029 -0.014591 +v -0.037053 0.041270 -0.002475 +v -0.052643 0.041270 -0.002475 +v -0.037053 0.039735 0.001231 +v -0.052643 0.039735 0.001231 +v -0.037053 0.036029 0.002765 +v -0.052643 0.036029 0.002765 +v -0.037053 0.032323 0.001231 +v -0.037053 0.027462 0.006092 +v -0.052643 0.032323 0.001231 +v -0.052643 0.027462 0.006092 +v -0.037053 0.030788 -0.002475 +v -0.037053 0.023913 -0.002475 +v -0.052643 0.030788 -0.002475 +v -0.052643 0.023913 -0.002475 +v -0.037053 0.032323 -0.006181 +v -0.037053 0.027462 -0.011042 +v -0.052643 0.032323 -0.006181 +v -0.052643 0.027462 -0.011042 +v -0.037053 0.029972 -0.019513 +v -0.037053 0.044453 -0.019512 +v -0.052643 0.044453 -0.019512 +v -0.052643 0.029972 -0.019512 +v -0.052643 0.003224 0.018663 +v -0.037053 0.003224 0.018663 +v -0.037053 0.016994 0.008892 +v -0.052643 0.016994 0.008892 +v -0.037053 0.019783 -0.002475 +v -0.052643 0.019783 -0.002475 +v -0.031870 0.011265 -0.019513 +v -0.052643 0.011260 -0.019512 +v -0.017183 0.039591 -0.005322 +v -0.017183 0.035782 -0.006900 +v -0.017183 0.024061 -0.019003 +v -0.017183 0.044489 -0.019003 +v -0.017183 0.041168 -0.001514 +v -0.017183 0.047188 -0.001514 +v -0.017183 0.039591 0.002295 +v -0.017183 0.043847 0.006551 +v -0.017183 0.035782 0.003872 +v -0.017183 0.035782 0.009892 +v -0.017183 0.031974 0.002295 +v -0.017183 0.027717 0.006551 +v -0.017183 0.030396 -0.001514 +v -0.017183 0.024377 -0.001514 +v -0.017183 0.031974 -0.005322 +v -0.021687 0.012776 -0.019003 +v -0.025691 0.033375 -0.019003 +v -0.026481 0.035782 -0.006900 +v -0.026481 0.039591 -0.005322 +v -0.026482 0.044489 -0.019003 +v -0.026481 0.041168 -0.001514 +v -0.026481 0.047188 -0.001514 +v -0.026481 0.039591 0.002295 +v -0.026481 0.043847 0.006551 +v -0.026481 0.035782 0.003872 +v -0.026481 0.035782 0.009892 +v -0.026481 0.031974 0.002295 +v -0.026481 0.027717 0.006551 +v -0.026481 0.030396 -0.001514 +v -0.026481 0.024377 -0.001514 +v -0.026481 0.031974 -0.005322 +v -0.026481 0.012776 -0.019003 +v -0.037625 0.037254 -0.043660 +v -0.050721 0.037254 -0.043660 +v -0.050721 0.022773 -0.043660 +v -0.050721 0.011406 -0.043656 +v -0.020934 0.037290 -0.043651 +v -0.028745 0.037290 -0.043651 +v -0.020934 0.016861 -0.043651 +v -0.024186 0.005981 -0.043601 +v -0.028745 0.004732 -0.038559 +v -0.024717 0.004732 -0.038559 +v -0.021687 0.002344 -0.025170 +v -0.026481 0.002344 -0.025170 +v -0.050720 0.005978 -0.043688 +v -0.032442 0.005978 -0.043672 +v -0.031869 -0.009851 -0.019545 +v -0.052642 -0.009856 -0.019545 +v -0.028745 0.005981 -0.043655 +v -0.031985 0.002344 -0.025170 +v -0.034248 0.004732 -0.038559 +v -0.031985 0.012776 -0.019003 +v -0.034248 0.006022 -0.043655 +v -0.034742 0.037254 -0.052930 +v -0.047639 0.037254 -0.055204 +v -0.047639 0.022773 -0.055204 +v -0.047639 0.011406 -0.055200 +v -0.018306 0.037290 -0.050023 +v -0.025998 0.037290 -0.051379 +v -0.018306 0.016861 -0.050023 +v -0.019751 0.005981 -0.049493 +v -0.025997 0.005981 -0.051384 +v -0.047633 0.005978 -0.055232 +v -0.029632 0.005978 -0.052058 +v -0.032363 0.037254 -0.063888 +v -0.047229 0.037254 -0.072471 +v -0.047229 0.022773 -0.072471 +v -0.047231 0.011406 -0.072467 +v -0.014210 0.037290 -0.054305 +v -0.022286 0.037290 -0.058060 +v -0.013419 0.016861 -0.052941 +v -0.014588 0.005981 -0.053024 +v -0.022284 0.005981 -0.058064 +v -0.047214 0.005978 -0.072495 +v -0.026464 0.005978 -0.060515 +v -0.011960 0.037254 -0.077426 +v -0.019187 0.037254 -0.097281 +v -0.019187 0.022773 -0.097281 +v -0.019187 0.011406 -0.097281 +v -0.005553 0.037290 -0.060729 +v -0.008928 0.037290 -0.068912 +v -0.002749 0.016861 -0.053048 +v -0.003204 0.005981 -0.053055 +v -0.007059 0.005981 -0.063962 +v -0.019186 0.005978 -0.097280 +v -0.009099 0.005978 -0.069566 +v 0.009065 0.037254 -0.077391 +v 0.009065 0.037254 -0.097203 +v 0.009065 0.022773 -0.097203 +v 0.009064 0.011406 -0.097203 +v 0.009375 0.037290 -0.060626 +v 0.009002 0.037290 -0.068918 +v 0.009382 0.016861 -0.052959 +v 0.008957 0.005981 -0.053111 +v 0.009064 0.005981 -0.063957 +v 0.009065 0.005978 -0.097201 +v 0.009065 0.005978 -0.069549 +v 0.021910 0.042610 -0.072008 +v 0.021910 0.042610 -0.087439 +v 0.021910 0.023802 -0.087439 +v 0.021910 0.009038 -0.087439 +v 0.022221 0.042657 -0.058949 +v 0.021848 0.042657 -0.065408 +v 0.022228 0.016124 -0.052977 +v 0.021803 0.002469 -0.053096 +v 0.021910 0.002469 -0.061544 +v 0.021911 0.001870 -0.087438 +v 0.021911 0.001870 -0.065899 +v 0.045781 0.050122 -0.070876 +v 0.049775 0.050122 -0.085781 +v 0.049775 0.026108 -0.085781 +v 0.049775 0.007258 -0.085781 +v 0.042701 0.050182 -0.058182 +v 0.044013 0.050182 -0.064517 +v 0.041162 0.016305 -0.052412 +v 0.040782 -0.001130 -0.052636 +v 0.043073 -0.001130 -0.060768 +v 0.049775 -0.001894 -0.085780 +v 0.044201 -0.001894 -0.064975 +v 0.046522 0.047470 -0.050409 +v 0.046522 0.037759 -0.050371 +v 0.049198 -0.004202 -0.047692 +# 446 vertices, 0 vertices normals + +f 3 4 1 +f 3 1 2 +f 5 6 2 +f 5 2 1 +f 7 8 6 +f 7 6 5 +f 8 7 9 +f 8 9 10 +f 10 9 11 +f 10 11 12 +f 12 11 13 +f 12 13 14 +f 14 13 15 +f 14 15 16 +f 16 15 4 +f 16 4 3 +f 3 17 18 +f 17 3 2 +f 2 19 17 +f 19 2 6 +f 6 8 19 +f 19 8 20 +f 8 10 20 +f 20 10 21 +f 12 21 10 +f 22 21 12 +f 12 14 22 +f 22 14 23 +f 14 24 23 +f 24 14 16 +f 18 16 3 +f 16 18 24 +f 25 18 17 +f 18 25 26 +f 19 27 25 +f 19 25 17 +f 28 19 20 +f 19 28 27 +f 21 29 28 +f 21 28 20 +f 30 21 22 +f 21 30 29 +f 30 22 23 +f 30 23 31 +f 23 32 31 +f 32 23 24 +f 18 26 32 +f 18 32 24 +f 4 33 34 +f 34 1 4 +f 5 34 35 +f 34 5 1 +f 7 35 36 +f 35 7 5 +f 9 36 37 +f 36 9 7 +f 11 37 38 +f 37 11 9 +f 39 13 11 +f 39 11 38 +f 13 40 15 +f 40 13 39 +f 4 40 33 +f 40 4 15 +f 34 26 25 +f 26 34 33 +f 27 35 34 +f 27 34 25 +f 36 27 28 +f 27 36 35 +f 29 37 36 +f 29 36 28 +f 38 29 30 +f 29 38 37 +f 30 31 38 +f 38 31 39 +f 31 40 39 +f 40 31 32 +f 26 33 40 +f 26 40 32 +f 41 42 43 +f 41 43 44 +f 45 46 42 +f 45 42 41 +f 45 48 46 +f 48 45 47 +f 49 50 51 +f 51 44 49 +f 54 52 53 +f 52 54 43 +f 41 51 55 +f 51 41 44 +f 42 52 43 +f 52 42 56 +f 57 45 41 +f 57 41 55 +f 42 58 56 +f 58 42 46 +f 47 57 59 +f 57 47 45 +f 46 48 58 +f 58 48 60 +f 62 47 61 +f 61 47 59 +f 48 64 60 +f 64 48 63 +f 65 66 62 +f 65 62 61 +f 63 68 64 +f 68 63 67 +f 70 65 69 +f 65 70 66 +f 67 71 68 +f 68 71 72 +f 49 69 50 +f 69 49 70 +f 54 53 72 +f 72 71 54 +f 51 53 52 +f 53 51 50 +f 53 50 69 +f 53 69 72 +f 65 68 72 +f 65 72 69 +f 61 64 68 +f 61 68 65 +f 64 61 59 +f 64 59 60 +f 60 59 57 +f 60 57 58 +f 58 57 55 +f 58 55 56 +f 56 55 51 +f 56 51 52 +f 73 74 49 +f 49 44 73 +f 43 73 44 +f 73 43 75 +f 54 75 43 +f 75 54 76 +f 47 78 48 +f 78 47 77 +f 47 79 77 +f 79 47 62 +f 48 78 80 +f 48 80 63 +f 62 81 79 +f 81 62 66 +f 63 80 82 +f 63 82 67 +f 66 70 81 +f 81 70 83 +f 71 82 84 +f 82 71 67 +f 49 74 70 +f 74 83 70 +f 54 71 76 +f 84 76 71 +f 88 85 87 +f 87 85 86 +f 85 89 86 +f 86 89 90 +f 92 94 91 +f 94 92 93 +f 97 98 95 +f 97 95 96 +f 93 100 94 +f 100 93 99 +f 95 101 96 +f 96 101 102 +f 104 99 103 +f 99 104 100 +f 105 102 101 +f 105 106 102 +f 103 107 104 +f 107 108 104 +f 105 110 106 +f 110 105 109 +f 88 107 111 +f 107 88 108 +f 87 110 109 +f 110 87 112 +f 85 111 113 +f 111 85 88 +f 112 87 86 +f 112 86 114 +f 85 115 89 +f 85 113 115 +f 86 116 114 +f 116 86 90 +f 91 89 92 +f 92 89 115 +f 90 97 116 +f 97 90 98 +f 107 106 110 +f 106 107 103 +f 106 103 99 +f 106 99 102 +f 102 99 93 +f 102 93 96 +f 92 97 96 +f 96 93 92 +f 115 116 97 +f 97 92 115 +f 114 115 113 +f 115 114 116 +f 112 113 111 +f 113 112 114 +f 111 110 112 +f 110 111 107 +f 84 83 76 +f 83 74 76 +f 73 75 109 +f 109 75 87 +f 75 88 87 +f 88 75 76 +f 76 108 88 +f 108 76 74 +f 73 118 74 +f 118 73 117 +f 104 120 100 +f 120 104 119 +f 121 122 105 +f 105 101 121 +f 123 104 108 +f 104 123 119 +f 105 124 109 +f 124 105 122 +f 73 124 117 +f 124 73 109 +f 122 126 125 +f 126 122 121 +f 127 122 125 +f 122 127 124 +f 117 127 128 +f 127 117 124 +f 129 130 131 +f 131 128 129 +f 133 131 132 +f 131 133 128 +f 135 133 134 +f 134 133 132 +f 135 136 137 +f 135 134 136 +f 139 136 138 +f 136 139 137 +f 141 138 140 +f 138 141 139 +f 142 143 141 +f 142 141 140 +f 129 142 130 +f 142 129 143 +f 145 117 144 +f 117 145 118 +f 147 144 117 +f 144 147 146 +f 147 149 148 +f 147 148 146 +f 148 149 150 +f 149 151 150 +f 153 150 151 +f 150 153 152 +f 155 152 153 +f 152 155 154 +f 157 156 155 +f 155 156 154 +f 118 156 157 +f 156 118 145 +f 148 134 132 +f 148 132 146 +f 146 132 131 +f 146 131 144 +f 130 144 131 +f 144 130 145 +f 145 130 142 +f 145 142 156 +f 140 154 156 +f 140 156 142 +f 138 152 154 +f 138 154 140 +f 138 150 152 +f 150 138 136 +f 136 148 150 +f 148 136 134 +f 147 117 133 +f 133 117 128 +f 135 149 147 +f 135 147 133 +f 135 151 149 +f 151 135 137 +f 137 139 151 +f 151 139 153 +f 139 141 153 +f 153 141 155 +f 141 143 155 +f 155 143 157 +f 161 158 160 +f 160 158 159 +f 162 159 158 +f 159 162 163 +f 162 165 163 +f 165 162 164 +f 164 167 165 +f 167 164 166 +f 168 167 166 +f 169 167 168 +f 168 170 169 +f 169 170 171 +f 170 173 171 +f 173 170 172 +f 160 172 161 +f 172 160 173 +f 176 174 175 +f 174 176 177 +f 179 176 175 +f 179 175 178 +f 179 180 181 +f 180 179 178 +f 181 182 183 +f 182 181 180 +f 182 184 185 +f 185 183 182 +f 187 185 184 +f 187 184 186 +f 187 188 189 +f 188 187 186 +f 174 189 188 +f 189 174 177 +f 158 177 176 +f 177 158 161 +f 172 177 161 +f 177 172 189 +f 187 172 170 +f 172 187 189 +f 185 170 168 +f 170 185 187 +f 183 168 166 +f 168 183 185 +f 164 181 183 +f 183 166 164 +f 181 164 162 +f 181 162 179 +f 179 162 158 +f 179 158 176 +f 174 173 160 +f 173 174 188 +f 159 175 174 +f 174 160 159 +f 178 159 163 +f 159 178 175 +f 180 163 165 +f 163 180 178 +f 165 182 180 +f 182 165 167 +f 169 182 167 +f 182 169 184 +f 184 169 171 +f 184 171 186 +f 186 171 173 +f 186 173 188 +f 193 190 192 +f 192 190 191 +f 190 194 191 +f 191 194 195 +f 197 199 196 +f 199 197 198 +f 202 203 200 +f 202 200 201 +f 198 205 199 +f 205 198 204 +f 200 206 201 +f 201 206 207 +f 209 204 208 +f 204 209 205 +f 210 207 206 +f 210 211 207 +f 208 212 209 +f 212 213 209 +f 210 215 211 +f 215 210 214 +f 193 212 216 +f 212 193 213 +f 192 215 214 +f 215 192 217 +f 190 216 218 +f 216 190 193 +f 217 192 191 +f 217 191 219 +f 194 218 220 +f 218 194 190 +f 191 195 219 +f 219 195 221 +f 196 194 197 +f 197 194 220 +f 195 202 221 +f 202 195 203 +f 208 215 212 +f 215 208 211 +f 211 208 204 +f 211 204 207 +f 204 201 207 +f 201 204 198 +f 202 198 197 +f 198 202 201 +f 220 221 202 +f 202 197 220 +f 219 220 218 +f 220 219 221 +f 216 217 219 +f 216 219 218 +f 212 217 216 +f 217 212 215 +f 223 222 214 +f 214 222 192 +f 222 193 192 +f 193 222 224 +f 224 213 193 +f 213 224 225 +f 195 194 203 +f 194 196 203 +f 89 98 90 +f 98 89 91 +f 206 227 210 +f 227 206 226 +f 214 227 228 +f 227 214 210 +f 223 228 229 +f 228 223 214 +f 128 230 129 +f 230 128 127 +f 230 143 129 +f 143 230 231 +f 231 157 143 +f 157 231 232 +f 127 233 230 +f 233 127 125 +f 233 231 230 +f 231 233 234 +f 234 232 231 +f 232 234 235 +f 125 236 233 +f 236 125 126 +f 234 236 237 +f 236 234 233 +f 235 237 238 +f 237 235 234 +f 74 239 240 +f 239 74 118 +f 209 240 239 +f 240 209 213 +f 225 83 213 +f 83 225 81 +f 241 243 244 +f 243 241 242 +f 243 242 246 +f 245 246 242 +f 246 245 248 +f 247 248 245 +f 248 249 250 +f 249 248 247 +f 250 251 252 +f 251 250 249 +f 251 254 252 +f 254 251 253 +f 253 256 254 +f 256 253 255 +f 255 244 256 +f 244 255 241 +f 258 241 257 +f 241 258 242 +f 242 259 245 +f 259 242 258 +f 247 245 259 +f 247 259 260 +f 260 249 247 +f 249 260 261 +f 261 262 251 +f 251 249 261 +f 253 251 262 +f 253 262 263 +f 253 264 255 +f 264 253 263 +f 257 255 264 +f 255 257 241 +f 257 266 258 +f 266 257 265 +f 258 266 259 +f 267 259 266 +f 259 268 260 +f 268 259 267 +f 260 268 261 +f 269 261 268 +f 261 270 262 +f 270 261 269 +f 270 263 262 +f 263 270 271 +f 263 272 264 +f 272 263 271 +f 264 272 257 +f 265 257 272 +f 274 244 273 +f 244 243 273 +f 246 273 243 +f 273 246 275 +f 248 275 246 +f 275 248 276 +f 276 250 277 +f 250 276 248 +f 252 277 250 +f 277 252 278 +f 252 254 279 +f 252 279 278 +f 256 280 254 +f 254 280 279 +f 280 244 274 +f 244 280 256 +f 273 265 274 +f 265 273 266 +f 273 275 267 +f 267 266 273 +f 276 267 275 +f 267 276 268 +f 276 277 269 +f 269 268 276 +f 278 269 277 +f 269 278 270 +f 278 271 270 +f 271 278 279 +f 271 280 272 +f 280 271 279 +f 280 274 265 +f 265 272 280 +f 284 281 283 +f 282 283 281 +f 283 282 286 +f 285 286 282 +f 286 287 288 +f 287 286 285 +f 290 291 289 +f 291 284 289 +f 293 294 292 +f 294 293 281 +f 283 289 284 +f 289 283 295 +f 281 293 282 +f 282 293 296 +f 283 286 297 +f 283 297 295 +f 282 298 285 +f 298 282 296 +f 297 288 299 +f 288 297 286 +f 298 287 285 +f 287 298 300 +f 301 288 302 +f 288 301 299 +f 303 287 300 +f 287 303 304 +f 302 306 305 +f 302 305 301 +f 304 307 308 +f 307 304 303 +f 310 305 306 +f 305 310 309 +f 307 312 308 +f 312 307 311 +f 309 291 290 +f 291 309 310 +f 292 294 311 +f 294 312 311 +f 289 292 290 +f 292 289 293 +f 290 311 309 +f 311 290 292 +f 309 311 305 +f 307 305 311 +f 305 307 301 +f 303 301 307 +f 303 299 301 +f 299 303 300 +f 300 297 299 +f 297 300 298 +f 298 295 297 +f 295 298 296 +f 296 289 295 +f 289 296 293 +f 314 284 291 +f 291 313 314 +f 281 284 314 +f 281 314 315 +f 315 294 281 +f 294 315 316 +f 287 318 288 +f 318 287 317 +f 288 319 302 +f 319 288 318 +f 320 287 304 +f 317 287 320 +f 302 321 306 +f 321 302 319 +f 320 304 322 +f 304 308 322 +f 321 323 310 +f 321 310 306 +f 312 322 308 +f 322 312 324 +f 313 291 310 +f 310 323 313 +f 316 312 294 +f 316 324 312 +f 328 326 327 +f 326 328 325 +f 330 325 328 +f 325 330 329 +f 330 332 331 +f 330 331 329 +f 331 332 333 +f 332 334 333 +f 336 333 334 +f 333 336 335 +f 336 338 337 +f 336 337 335 +f 340 339 338 +f 338 339 337 +f 339 327 326 +f 327 339 340 +f 342 344 341 +f 344 342 343 +f 346 343 345 +f 343 346 344 +f 348 346 347 +f 347 346 345 +f 348 349 350 +f 348 347 349 +f 352 349 351 +f 349 352 350 +f 353 354 352 +f 353 352 351 +f 355 356 354 +f 355 354 353 +f 341 355 342 +f 355 341 356 +f 347 329 331 +f 329 347 345 +f 345 325 329 +f 325 345 343 +f 343 326 325 +f 326 343 342 +f 342 339 326 +f 339 342 355 +f 339 353 337 +f 353 339 355 +f 337 353 335 +f 351 335 353 +f 351 333 335 +f 333 351 349 +f 349 331 333 +f 331 349 347 +f 346 328 344 +f 328 346 330 +f 348 332 346 +f 332 330 346 +f 348 334 332 +f 334 348 350 +f 350 336 334 +f 336 350 352 +f 352 338 336 +f 338 352 354 +f 354 340 338 +f 340 354 356 +f 321 322 324 +f 324 323 321 +f 314 341 344 +f 341 314 313 +f 313 356 341 +f 356 313 323 +f 314 358 315 +f 358 314 357 +f 315 358 316 +f 316 358 359 +f 316 359 324 +f 324 359 360 +f 328 361 344 +f 344 361 362 +f 327 361 328 +f 361 327 363 +f 340 363 327 +f 363 340 364 +f 368 366 367 +f 366 368 365 +f 372 369 371 +f 371 369 370 +f 344 362 314 +f 314 362 357 +f 323 373 356 +f 373 323 370 +f 371 370 323 +f 369 372 324 +f 324 360 369 +f 356 368 340 +f 340 368 367 +f 340 366 364 +f 366 340 367 +f 366 365 373 +f 366 373 364 +f 374 365 368 +f 365 374 375 +f 376 368 356 +f 368 376 374 +f 375 373 365 +f 373 375 377 +f 357 379 358 +f 379 357 378 +f 358 380 359 +f 380 358 379 +f 359 381 360 +f 381 359 380 +f 361 383 362 +f 383 361 382 +f 361 363 384 +f 361 384 382 +f 363 364 385 +f 363 385 384 +f 373 386 364 +f 364 386 385 +f 362 378 357 +f 378 362 383 +f 369 387 370 +f 370 387 388 +f 370 388 373 +f 373 388 386 +f 360 381 369 +f 369 381 387 +f 390 379 389 +f 379 378 389 +f 379 390 380 +f 380 390 391 +f 380 392 381 +f 392 380 391 +f 394 382 393 +f 382 394 383 +f 393 384 395 +f 384 393 382 +f 396 395 384 +f 384 385 396 +f 397 385 386 +f 397 396 385 +f 389 383 394 +f 383 389 378 +f 387 399 388 +f 399 387 398 +f 381 392 387 +f 387 392 398 +f 401 389 400 +f 389 401 390 +f 390 401 391 +f 402 391 401 +f 391 403 392 +f 403 391 402 +f 405 393 404 +f 393 405 394 +f 404 395 406 +f 395 404 393 +f 406 395 407 +f 395 396 407 +f 407 396 408 +f 396 397 408 +f 400 394 405 +f 394 400 389 +f 409 399 398 +f 409 410 399 +f 392 403 398 +f 409 398 403 +f 412 400 411 +f 400 412 401 +f 401 413 402 +f 413 401 412 +f 402 414 403 +f 414 402 413 +f 416 404 415 +f 404 416 405 +f 415 406 417 +f 406 415 404 +f 417 406 418 +f 406 407 418 +f 418 407 419 +f 407 408 419 +f 411 405 416 +f 405 411 400 +f 421 410 420 +f 410 409 420 +f 403 414 409 +f 420 409 414 +f 411 423 412 +f 423 411 422 +f 424 412 423 +f 412 424 413 +f 425 414 424 +f 414 413 424 +f 415 427 416 +f 427 415 426 +f 428 426 415 +f 415 417 428 +f 428 418 429 +f 418 428 417 +f 429 418 430 +f 418 419 430 +f 416 422 411 +f 422 416 427 +f 432 421 431 +f 421 420 431 +f 421 432 419 +f 430 419 432 +f 414 425 420 +f 431 420 425 +f 433 423 422 +f 423 433 434 +f 435 423 434 +f 423 435 424 +f 436 424 435 +f 424 436 425 +f 437 427 426 +f 427 437 438 +f 437 426 439 +f 426 428 439 +f 439 429 440 +f 429 439 428 +f 430 440 429 +f 440 430 441 +f 438 422 427 +f 422 438 433 +f 431 443 432 +f 443 431 442 +f 432 441 430 +f 441 432 443 +f 425 436 431 +f 442 431 436 +f 408 421 419 +f 421 408 410 +f 397 410 408 +f 410 397 399 +f 399 386 388 +f 386 399 397 +f 445 126 444 +f 126 445 236 +f 445 446 237 +f 237 236 445 +# 847 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_lglut_chull.obj b/examples/Atlas/urdf/mesh/l_lglut_chull.obj new file mode 100644 index 0000000..2b18669 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_lglut_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_lglut_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.047214 0.005978 -0.072495 +v 0.080771 0.046193 -0.033083 +v -0.061619 0.018901 -0.008717 +v -0.047229 0.037254 -0.072471 +v 0.047750 -0.009657 -0.088147 +v -0.052643 0.044596 0.006092 +v 0.081138 -0.003391 -0.041163 +v -0.061574 -0.020422 -0.000550 +v 0.082320 -0.020422 -0.000550 +v 0.071703 0.047975 -0.002475 +v 0.071640 0.043892 0.007485 +v -0.052643 0.047975 -0.002475 +v 0.009065 0.037254 -0.097203 +v 0.050046 0.055819 -0.087444 +v 0.064714 -0.009751 -0.081368 +v 0.064714 0.055819 -0.081368 +v -0.019187 0.005978 -0.097281 +v -0.019187 0.037254 -0.097281 +v 0.082320 -0.014346 0.014119 +v -0.061574 -0.014346 0.014119 +v -0.062227 0.000404 0.020197 +v 0.082320 0.000322 0.020195 +v 0.063418 0.057590 -0.056243 +v 0.035377 0.055819 -0.081368 +v 0.080317 0.045790 -0.045336 +v -0.061555 -0.011575 -0.021117 +v 0.082666 0.015243 0.012511 +# 27 vertices, 0 vertices normals + +f 6 12 3 +f 11 12 6 +f 24 14 18 +f 1 26 4 +f 17 8 26 +f 17 26 1 +f 3 21 6 +f 27 2 11 +f 10 23 12 +f 2 10 11 +f 10 2 23 +f 18 14 13 +f 15 9 5 +f 12 24 4 +f 4 3 12 +f 4 24 18 +f 18 1 4 +f 17 5 8 +f 17 1 18 +f 11 22 27 +f 23 24 12 +f 15 25 7 +f 25 27 7 +f 25 2 27 +f 25 23 2 +f 25 16 23 +f 3 4 26 +f 5 17 13 +f 6 21 11 +f 9 15 7 +f 5 9 8 +f 10 12 11 +f 13 14 5 +f 15 14 16 +f 14 15 5 +f 18 13 17 +f 21 20 19 +f 19 22 21 +f 19 8 9 +f 19 20 8 +f 16 14 23 +f 14 24 23 +f 25 15 16 +f 8 3 26 +f 20 3 8 +f 3 20 21 +f 21 22 11 +f 19 7 22 +f 7 27 22 +f 7 19 9 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_lleg.obj b/examples/Atlas/urdf/mesh/l_lleg.obj new file mode 100644 index 0000000..2531fd2 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_lleg.obj @@ -0,0 +1,2319 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_lleg.obj +# +# Vertices: 809 +# Faces: 1494 +# +#### +v -0.014057 0.011209 -0.114512 +v -0.040907 0.011209 -0.115410 +v -0.041007 0.003223 -0.123695 +v -0.018749 0.003223 -0.123695 +v -0.030527 0.003223 -0.147550 +v -0.030527 0.011209 -0.147550 +v -0.029528 0.011209 -0.144556 +v -0.029528 0.003223 -0.144556 +v -0.041207 0.003223 -0.147550 +v -0.041107 0.011209 -0.135773 +v -0.027632 0.040354 -0.140863 +v -0.036316 0.040354 -0.140863 +v -0.036016 0.040354 -0.130582 +v -0.022342 0.040354 -0.130582 +v -0.029528 0.031571 -0.144556 +v -0.041107 0.031571 -0.140863 +v -0.027632 0.031571 -0.140863 +v -0.030527 0.031571 -0.147550 +v -0.041207 0.031571 -0.147550 +v -0.041007 0.031571 -0.130582 +v -0.041007 0.035962 -0.130582 +v -0.041107 0.035962 -0.140863 +v -0.022342 0.031571 -0.130582 +v -0.041007 0.031571 -0.123695 +v -0.018749 0.031571 -0.123695 +v -0.041307 0.024284 -0.153739 +v -0.041107 0.024284 -0.135773 +v -0.030527 0.024284 -0.147550 +v -0.032623 0.024284 -0.154139 +v -0.032623 0.011209 -0.154139 +v -0.041307 0.011209 -0.153739 +v -0.040907 0.024284 -0.115410 +v -0.014057 0.024284 -0.114512 +v -0.029528 0.024284 -0.144556 +v -0.020135 0.050041 0.002602 +v 0.000826 0.050041 0.022066 +v 0.030271 0.050041 0.021267 +v -0.019836 0.050041 -0.037024 +v -0.014346 0.050041 0.015478 +v -0.014645 0.050041 -0.078148 +v -0.007359 0.050041 -0.061578 +v 0.011406 0.050041 -0.038920 +v -0.012150 0.050041 -0.079046 +v 0.009909 0.028780 -0.418514 +v 0.005717 0.024189 -0.430092 +v -0.008157 0.026684 -0.425801 +v -0.016043 0.039560 -0.325288 +v 0.021188 0.040359 -0.334471 +v 0.021188 0.040359 -0.345151 +v -0.015643 0.039560 -0.368707 +v -0.015444 0.035967 -0.392862 +v -0.023229 0.035967 -0.390467 +v -0.031913 0.039560 -0.360821 +v -0.040797 0.033072 -0.317103 +v -0.041894 0.033072 -0.264201 +v -0.016342 0.039560 -0.269192 +v -0.017739 0.050041 -0.105297 +v 0.032966 0.050041 -0.122565 +v 0.026877 0.050041 -0.139234 +v -0.010952 0.050041 -0.139633 +v 0.021188 0.050041 -0.173370 +v 0.021188 0.050041 -0.254819 +v -0.009754 0.050041 -0.255817 +v -0.010553 0.050041 -0.184150 +v 0.021188 0.040359 -0.270989 +v 0.004918 0.035967 -0.395058 +v 0.010708 0.039560 -0.375195 +v -0.041695 0.041756 -0.166982 +v -0.038900 0.050041 -0.139933 +v -0.041695 0.032873 -0.192834 +v 0.047539 0.038762 -0.254619 +v 0.039454 0.039860 -0.254719 +v 0.039953 0.039860 -0.239747 +v 0.047539 0.038762 -0.240745 +v 0.039454 0.027283 -0.255617 +v 0.047539 0.000134 -0.254619 +v 0.047539 0.000134 -0.240745 +v 0.039480 0.014107 -0.239747 +v 0.039480 0.000134 -0.239747 +v 0.025779 0.040359 -0.333572 +v 0.025779 0.040359 -0.345151 +v 0.025680 0.040359 -0.271288 +v 0.020789 0.039860 -0.239846 +v 0.025181 0.039860 -0.254719 +v 0.021188 0.039959 -0.254819 +v 0.029373 0.032773 -0.331276 +v 0.029173 0.032673 -0.271588 +v 0.039454 0.024388 -0.264501 +v 0.037857 0.024788 -0.330777 +v 0.029373 0.032873 -0.342456 +v 0.039654 0.020096 -0.338064 +v 0.058918 0.024388 -0.264800 +v 0.059018 0.024788 -0.330777 +v 0.031369 0.031475 -0.351838 +v 0.021188 0.033072 -0.356230 +v 0.039654 0.020096 -0.374596 +v 0.031369 0.031276 -0.374995 +v 0.021188 0.032573 -0.375095 +v 0.029173 0.032673 -0.258911 +v 0.058918 0.019897 -0.260009 +v 0.041051 0.019897 -0.259710 +v 0.058918 0.012710 -0.260009 +v 0.041151 0.012710 -0.259710 +v 0.058918 0.008618 -0.265000 +v 0.041151 0.008618 -0.264601 +v 0.058918 0.008119 -0.275480 +v 0.041151 0.008119 -0.275181 +v 0.058918 0.000134 -0.279672 +v 0.037258 0.000134 -0.279373 +v 0.035561 0.000134 -0.255617 +v 0.036360 0.000134 -0.264800 +v 0.059018 0.020096 -0.337465 +v 0.039654 0.013109 -0.338064 +v 0.059018 0.013109 -0.337465 +v 0.039654 0.008119 -0.330977 +v 0.059018 0.008119 -0.330378 +v 0.039654 0.013109 -0.374596 +v 0.039654 0.008119 -0.321894 +v 0.059018 0.008119 -0.321295 +v 0.035761 0.000134 -0.317602 +v 0.059018 0.000134 -0.317003 +v 0.039654 0.000134 -0.330977 +v 0.031169 0.013109 -0.374596 +v 0.021188 0.013109 -0.374596 +v 0.031169 0.000134 -0.374596 +v 0.021188 0.000134 -0.374596 +v 0.021188 0.039560 -0.356230 +v 0.010708 0.030577 -0.375195 +v -0.008157 0.017801 -0.425801 +v 0.005717 0.017701 -0.430092 +v 0.009909 0.018100 -0.418514 +v -0.023229 0.017900 -0.390467 +v 0.004918 0.020496 -0.393361 +v -0.029018 0.012012 -0.374396 +v -0.031913 0.017401 -0.360821 +v -0.031913 0.000134 -0.360821 +v -0.040797 0.000134 -0.317103 +v 0.030271 0.044651 0.021267 +v 0.000826 0.044651 0.022066 +v -0.011351 0.050041 -0.050000 +v -0.019836 0.044651 -0.037024 +v -0.020135 0.044651 0.002602 +v -0.014346 0.044651 0.015478 +v 0.045343 0.050041 0.016177 +v -0.027122 0.050041 -0.102003 +v 0.030471 0.031675 -0.139334 +v 0.039480 0.023590 -0.139434 +v 0.039480 0.023590 -0.147718 +v 0.039480 0.023590 -0.216790 +v 0.030471 0.031675 -0.239846 +v 0.039480 0.023590 -0.239747 +v 0.020789 0.033072 -0.239846 +v 0.021188 0.033072 -0.173370 +v 0.026877 0.033072 -0.139234 +v 0.039480 0.014507 -0.147718 +v 0.039480 0.016803 -0.143625 +v 0.046740 0.016703 -0.143625 +v 0.046740 0.014207 -0.147518 +v 0.039480 0.014507 -0.139434 +v 0.046740 0.014207 -0.139633 +v 0.039480 0.014507 -0.216889 +v 0.046740 0.000134 -0.147518 +v 0.039480 0.000134 -0.147718 +v 0.039480 0.000134 -0.224775 +v 0.031668 0.021394 -0.137836 +v 0.031668 0.021394 -0.122066 +v 0.039654 0.044950 0.018073 +v 0.048537 0.026684 0.013881 +v 0.039654 0.020695 0.018073 +v 0.016297 0.026684 -0.038920 +v 0.057820 0.020096 0.007892 +v 0.071195 0.020096 -0.009974 +v -0.010453 0.036566 -0.085833 +v -0.003965 0.026684 -0.072159 +v 0.048038 0.032673 -0.098509 +v 0.062611 0.019996 -0.072059 +v 0.075986 0.020096 -0.031335 +v 0.046740 0.000134 -0.139633 +v 0.031668 0.000134 -0.122165 +v 0.048038 0.000134 -0.098509 +v 0.062611 0.000134 -0.072059 +v 0.075986 0.000134 -0.031335 +v 0.073291 0.000134 -0.018958 +v 0.072393 0.010714 -0.015265 +v 0.071195 0.014906 -0.009974 +v 0.057820 0.014906 0.007892 +v 0.039654 0.015405 0.018073 +v 0.030171 0.015405 0.021667 +v 0.030171 0.020695 0.021667 +v 0.001225 0.015405 0.021667 +v 0.001225 0.020695 0.021667 +v -0.014745 0.015405 0.015678 +v -0.014745 0.020695 0.015678 +v -0.019736 0.015405 0.002702 +v -0.019736 0.020695 0.002702 +v -0.019836 0.015106 -0.037024 +v -0.019836 0.021094 -0.037024 +v -0.041695 0.000134 -0.192834 +v -0.041695 0.000134 -0.166982 +v -0.038900 0.000134 -0.139933 +v -0.014645 0.000134 -0.078148 +v -0.012848 0.000134 -0.074055 +v -0.007359 0.015106 -0.061578 +v -0.011351 0.015106 -0.050000 +v -0.027122 0.000134 -0.102003 +v -0.041894 0.000134 -0.264201 +v -0.001769 0.012111 -0.374995 +v -0.001769 0.000134 -0.374695 +v 0.039654 0.000134 -0.374596 +v -0.029917 0.000134 -0.371502 +v 0.040153 0.000134 -0.139533 +v 0.031668 0.000134 -0.138036 +v 0.030271 -0.049773 0.021267 +v 0.000826 -0.049773 0.022066 +v -0.020135 -0.049773 0.002602 +v -0.019836 -0.049773 -0.037024 +v -0.014346 -0.049773 0.015478 +v 0.011406 -0.049773 -0.038920 +v -0.007359 -0.049773 -0.061578 +v -0.014645 -0.049773 -0.078148 +v -0.012150 -0.049773 -0.079046 +v 0.005717 -0.023922 -0.430092 +v 0.009909 -0.028513 -0.418514 +v -0.008157 -0.026517 -0.425801 +v 0.021188 -0.040092 -0.345151 +v 0.021188 -0.040092 -0.334471 +v -0.016043 -0.039293 -0.325288 +v -0.015643 -0.039293 -0.368707 +v -0.015444 -0.035800 -0.392862 +v -0.023229 -0.035800 -0.390467 +v -0.031913 -0.039293 -0.360821 +v -0.041894 -0.032805 -0.264201 +v -0.040797 -0.032805 -0.317103 +v -0.016342 -0.039293 -0.269192 +v 0.026877 -0.049773 -0.139234 +v 0.032966 -0.049773 -0.122565 +v -0.017739 -0.049773 -0.105297 +v -0.010952 -0.049773 -0.139633 +v -0.009754 -0.049773 -0.255817 +v 0.021188 -0.049773 -0.254819 +v 0.021188 -0.049773 -0.173370 +v -0.010553 -0.049773 -0.184150 +v 0.021188 -0.040092 -0.270989 +v 0.004918 -0.035800 -0.395058 +v 0.010707 -0.039293 -0.375195 +v -0.038900 -0.049773 -0.139933 +v -0.041695 -0.041489 -0.166982 +v -0.041695 -0.032606 -0.192834 +v 0.039953 -0.039692 -0.239747 +v 0.039454 -0.039692 -0.254719 +v 0.047539 -0.038495 -0.254619 +v 0.047539 -0.038495 -0.240745 +v 0.039454 -0.027116 -0.255617 +v 0.039480 -0.013840 -0.239747 +v 0.025779 -0.040092 -0.333572 +v 0.025779 -0.040092 -0.345151 +v 0.025680 -0.040092 -0.271288 +v 0.025181 -0.039692 -0.254719 +v 0.020789 -0.039692 -0.239846 +v 0.021188 -0.039692 -0.254819 +v 0.039454 -0.024121 -0.264501 +v 0.029173 -0.032406 -0.271588 +v 0.029373 -0.032506 -0.331276 +v 0.037857 -0.024520 -0.330777 +v 0.029373 -0.032606 -0.342456 +v 0.039654 -0.019829 -0.338064 +v 0.058918 -0.024121 -0.264800 +v 0.059018 -0.024521 -0.330777 +v 0.021188 -0.032805 -0.356230 +v 0.031369 -0.031308 -0.351838 +v 0.039654 -0.019829 -0.374596 +v 0.021188 -0.032406 -0.375095 +v 0.031369 -0.031009 -0.374995 +v 0.029173 -0.032406 -0.258911 +v 0.058918 -0.019630 -0.260009 +v 0.041051 -0.019630 -0.259710 +v 0.058918 -0.012543 -0.260009 +v 0.041151 -0.012543 -0.259710 +v 0.058918 -0.008351 -0.265000 +v 0.041151 -0.008351 -0.264601 +v 0.058918 -0.007852 -0.275480 +v 0.041151 -0.007852 -0.275181 +v 0.059018 -0.019829 -0.337465 +v 0.039654 -0.012842 -0.338064 +v 0.059018 -0.012842 -0.337465 +v 0.039654 -0.007852 -0.330977 +v 0.059018 -0.007852 -0.330378 +v 0.039653 -0.012842 -0.374596 +v 0.039654 -0.007852 -0.321894 +v 0.059018 -0.007852 -0.321295 +v 0.031169 -0.012842 -0.374596 +v 0.021188 -0.012842 -0.374596 +v 0.021188 -0.039293 -0.356230 +v 0.010708 -0.030310 -0.375195 +v -0.008157 -0.017534 -0.425801 +v 0.005717 -0.017434 -0.430092 +v 0.009909 -0.017833 -0.418514 +v -0.023229 -0.017633 -0.390467 +v 0.004918 -0.020228 -0.393361 +v -0.029018 -0.011744 -0.374396 +v -0.031913 -0.017134 -0.360821 +v 0.030271 -0.044384 0.021267 +v 0.000826 -0.044384 0.022066 +v -0.019836 -0.044384 -0.037024 +v -0.011351 -0.049773 -0.050000 +v -0.020135 -0.044384 0.002602 +v -0.014346 -0.044384 0.015478 +v 0.045343 -0.049773 0.016177 +v -0.027122 -0.049773 -0.102003 +v 0.039480 -0.023323 -0.139434 +v 0.030471 -0.031408 -0.139334 +v 0.039480 -0.023323 -0.147718 +v 0.030471 -0.031408 -0.239846 +v 0.039480 -0.023323 -0.216790 +v 0.039480 -0.023323 -0.239747 +v 0.020789 -0.032805 -0.239846 +v 0.021188 -0.032805 -0.173370 +v 0.026877 -0.032805 -0.139234 +v 0.046740 -0.016436 -0.143625 +v 0.039480 -0.016536 -0.143625 +v 0.039480 -0.014240 -0.147718 +v 0.046740 -0.013940 -0.147518 +v 0.046740 -0.013940 -0.139633 +v 0.039480 -0.014240 -0.139434 +v 0.039480 -0.014240 -0.216889 +v 0.031668 -0.021127 -0.137836 +v 0.031668 -0.021127 -0.122066 +v 0.039654 -0.044683 0.018073 +v 0.048537 -0.026417 0.013881 +v 0.039654 -0.020428 0.018073 +v 0.016297 -0.026417 -0.038920 +v 0.057820 -0.019829 0.007892 +v 0.071195 -0.019829 -0.009974 +v 0.048038 -0.032406 -0.098509 +v -0.003965 -0.026417 -0.072159 +v -0.010453 -0.036299 -0.085833 +v 0.062611 -0.019730 -0.072059 +v 0.075986 -0.019829 -0.031335 +v 0.072393 -0.010447 -0.015265 +v 0.071195 -0.014639 -0.009974 +v 0.057820 -0.014739 0.007892 +v 0.039654 -0.015138 0.018073 +v 0.030171 -0.015138 0.021667 +v 0.030171 -0.020428 0.021667 +v 0.001225 -0.015138 0.021667 +v 0.001225 -0.020428 0.021667 +v -0.014745 -0.015138 0.015678 +v -0.014745 -0.020428 0.015678 +v -0.019736 -0.015138 0.002702 +v -0.019736 -0.020428 0.002702 +v -0.019836 -0.014838 -0.037024 +v -0.019836 -0.020828 -0.037024 +v -0.007359 -0.014838 -0.061578 +v -0.011351 -0.014838 -0.050000 +v -0.001769 -0.011844 -0.374995 +v -0.041007 -0.003162 -0.123695 +v -0.040907 -0.011147 -0.115410 +v -0.014057 -0.011147 -0.114512 +v -0.018749 -0.003162 -0.123695 +v -0.029528 -0.011147 -0.144556 +v -0.030527 -0.011147 -0.147550 +v -0.030527 -0.003162 -0.147550 +v -0.029528 -0.003162 -0.144556 +v -0.041207 -0.003162 -0.147550 +v -0.041107 -0.011147 -0.135773 +v -0.036016 -0.040292 -0.130582 +v -0.036316 -0.040292 -0.140863 +v -0.027632 -0.040292 -0.140863 +v -0.022342 -0.040292 -0.130582 +v -0.041107 -0.031509 -0.140863 +v -0.029528 -0.031509 -0.144556 +v -0.027632 -0.031509 -0.140863 +v -0.041207 -0.031509 -0.147550 +v -0.030527 -0.031509 -0.147550 +v -0.041107 -0.035901 -0.140863 +v -0.041007 -0.035901 -0.130582 +v -0.041007 -0.031509 -0.130582 +v -0.022342 -0.031509 -0.130582 +v -0.018749 -0.031509 -0.123695 +v -0.041007 -0.031509 -0.123695 +v -0.041107 -0.024222 -0.135773 +v -0.041307 -0.024222 -0.153739 +v -0.032623 -0.024222 -0.154139 +v -0.030527 -0.024222 -0.147550 +v -0.032623 -0.011147 -0.154139 +v -0.041307 -0.011147 -0.153739 +v -0.040907 -0.024222 -0.115410 +v -0.014057 -0.024222 -0.114512 +v -0.029528 -0.024222 -0.144556 +v 0.094851 0.000134 -0.040118 +v 0.094751 0.000134 -0.109988 +v 0.091757 0.005424 -0.109789 +v 0.091856 0.005424 -0.045409 +v 0.085668 0.005424 -0.109489 +v 0.085668 0.005424 -0.045409 +v 0.082574 0.000134 -0.109290 +v 0.082674 0.000134 -0.040118 +v 0.085668 -0.005157 -0.109489 +v 0.085668 -0.005157 -0.045409 +v 0.091757 -0.005157 -0.109789 +v 0.091857 -0.005157 -0.045409 +v 0.067302 0.005424 -0.343454 +v 0.070097 0.000134 -0.349143 +v 0.061214 0.005424 -0.342855 +v 0.057920 0.000134 -0.347846 +v 0.061213 -0.005157 -0.342855 +v 0.067302 -0.005157 -0.343454 +v 0.012005 0.042455 -0.365912 +v 0.006416 0.042455 -0.364615 +v 0.006915 0.044850 -0.363816 +v 0.011805 0.044850 -0.364914 +v 0.002623 0.042455 -0.359324 +v 0.003621 0.044850 -0.359125 +v 0.004419 0.042455 -0.353036 +v 0.005118 0.044850 -0.353635 +v 0.009210 0.042455 -0.349942 +v 0.009310 0.044850 -0.350840 +v 0.039354 0.042455 -0.361021 +v 0.039155 0.044850 -0.360023 +v 0.049635 0.042455 -0.357029 +v 0.049036 0.044850 -0.356330 +v 0.047539 0.042455 -0.345450 +v 0.052130 0.042455 -0.350640 +v 0.051132 0.044850 -0.350840 +v 0.047239 0.044850 -0.346348 +v 0.036559 0.042455 -0.345250 +v 0.036659 0.044850 -0.346249 +v 0.006914 -0.044583 -0.363816 +v 0.006415 -0.042288 -0.364615 +v 0.012005 -0.042288 -0.365912 +v 0.011805 -0.044583 -0.364914 +v 0.003621 -0.044583 -0.359125 +v 0.002623 -0.042288 -0.359324 +v 0.005118 -0.044583 -0.353635 +v 0.004419 -0.042288 -0.353036 +v 0.009310 -0.044583 -0.350840 +v 0.009210 -0.042288 -0.349942 +v 0.039354 -0.042288 -0.361021 +v 0.039155 -0.044583 -0.360023 +v 0.049635 -0.042288 -0.357029 +v 0.049036 -0.044583 -0.356330 +v 0.051132 -0.044583 -0.350840 +v 0.052131 -0.042288 -0.350640 +v 0.047539 -0.042288 -0.345450 +v 0.047239 -0.044583 -0.346348 +v 0.036659 -0.044583 -0.346249 +v 0.036559 -0.042288 -0.345250 +v 0.023284 -0.050772 -0.224176 +v 0.020888 -0.050772 -0.224176 +v 0.020888 -0.048875 -0.229067 +v 0.023284 -0.048875 -0.229067 +v 0.020889 -0.043286 -0.231562 +v 0.023284 -0.043286 -0.231562 +v 0.020889 -0.037696 -0.229067 +v 0.023284 -0.037696 -0.229067 +v 0.020889 -0.035800 -0.224176 +v 0.023284 -0.035800 -0.224176 +v 0.023384 -0.035800 -0.173271 +v 0.020988 -0.035800 -0.173271 +v 0.020988 -0.037696 -0.168479 +v 0.023384 -0.037696 -0.168479 +v 0.020988 -0.043286 -0.165884 +v 0.023384 -0.043286 -0.165884 +v 0.020988 -0.048875 -0.168479 +v 0.023384 -0.048875 -0.168479 +v 0.020988 -0.050772 -0.173271 +v 0.023384 -0.050772 -0.173271 +v 0.020889 0.049142 -0.229067 +v 0.020889 0.051039 -0.224176 +v 0.023284 0.051039 -0.224176 +v 0.023284 0.049142 -0.229067 +v 0.020889 0.043553 -0.231562 +v 0.023284 0.043553 -0.231562 +v 0.020889 0.037963 -0.229067 +v 0.023284 0.037963 -0.229067 +v 0.020889 0.036067 -0.224176 +v 0.023284 0.036067 -0.224176 +v 0.020988 0.037963 -0.168479 +v 0.020988 0.036067 -0.173271 +v 0.023384 0.036067 -0.173271 +v 0.023384 0.037963 -0.168479 +v 0.020988 0.043553 -0.165884 +v 0.023384 0.043553 -0.165884 +v 0.020988 0.049142 -0.168479 +v 0.023384 0.049142 -0.168479 +v 0.020988 0.051039 -0.173271 +v 0.023384 0.051039 -0.173271 +v 0.042947 0.052037 -0.015464 +v 0.049336 0.052037 -0.004485 +v 0.049336 0.050440 -0.004485 +v 0.042947 0.050440 -0.015464 +v 0.027277 0.052037 0.011086 +v 0.027277 0.050440 0.011086 +v 0.008911 0.052037 0.018672 +v 0.008911 0.050440 0.018672 +v -0.018139 0.052037 0.002502 +v -0.016242 0.052037 -0.009375 +v -0.016242 0.050440 -0.009375 +v -0.018139 0.050440 0.002502 +v -0.013547 0.052037 0.013582 +v -0.013547 0.050440 0.013582 +v -0.003067 0.052037 0.019371 +v -0.003067 0.050440 0.019371 +v -0.005762 0.052037 -0.028540 +v -0.005762 0.050440 -0.028540 +v 0.018493 0.052037 -0.057586 +v 0.018493 0.050440 -0.057586 +v 0.025280 0.052037 -0.045907 +v 0.025280 0.050440 -0.045907 +v 0.034563 0.052037 -0.016961 +v 0.034563 0.050440 -0.016961 +v 0.025380 0.052037 -0.025645 +v 0.025380 0.050440 -0.025645 +v 0.022486 0.052037 -0.037823 +v 0.022486 0.050440 -0.037823 +v -0.011252 0.050041 -0.003087 +v -0.002168 0.050041 -0.012170 +v -0.002168 0.052037 -0.012170 +v -0.011252 0.052037 -0.003087 +v -0.007858 0.050041 0.009390 +v -0.007858 0.052037 0.009390 +v 0.004619 0.050041 0.012584 +v 0.004619 0.052037 0.012584 +v 0.013702 0.050041 0.003501 +v 0.013702 0.052037 0.003501 +v 0.010308 0.050041 -0.008876 +v 0.010308 0.052037 -0.008876 +v 0.049336 -0.050173 -0.004485 +v 0.049336 -0.051770 -0.004485 +v 0.042947 -0.051770 -0.015464 +v 0.042947 -0.050173 -0.015464 +v 0.027277 -0.050173 0.011086 +v 0.027277 -0.051770 0.011086 +v 0.008911 -0.050173 0.018672 +v 0.008911 -0.051770 0.018672 +v -0.016242 -0.050173 -0.009375 +v -0.016242 -0.051770 -0.009375 +v -0.018139 -0.051770 0.002502 +v -0.018139 -0.050173 0.002502 +v -0.013547 -0.051770 0.013582 +v -0.013547 -0.050173 0.013582 +v -0.003067 -0.051770 0.019371 +v -0.003067 -0.050173 0.019371 +v -0.005762 -0.050173 -0.028540 +v -0.005762 -0.051770 -0.028540 +v 0.018493 -0.050173 -0.057586 +v 0.018493 -0.051770 -0.057586 +v 0.025280 -0.050173 -0.045907 +v 0.025280 -0.051770 -0.045907 +v 0.034563 -0.051770 -0.016961 +v 0.034563 -0.050173 -0.016961 +v 0.025380 -0.051770 -0.025645 +v 0.025380 -0.050173 -0.025645 +v 0.022486 -0.051770 -0.037823 +v 0.022486 -0.050173 -0.037823 +v -0.002168 -0.051770 -0.012170 +v -0.002168 -0.049774 -0.012170 +v -0.011252 -0.049774 -0.003087 +v -0.011252 -0.051770 -0.003087 +v -0.007858 -0.049774 0.009390 +v -0.007858 -0.051770 0.009390 +v 0.004619 -0.049774 0.012584 +v 0.004619 -0.051770 0.012584 +v 0.013702 -0.049774 0.003501 +v 0.013702 -0.051770 0.003501 +v 0.010308 -0.049774 -0.008876 +v 0.010308 -0.051770 -0.008876 +v 0.094651 0.000134 -0.037224 +v 0.094352 0.000134 -0.040418 +v 0.094152 0.000134 -0.043612 +v 0.088962 0.028281 -0.032932 +v 0.088064 0.029978 -0.038920 +v 0.088363 0.000134 -0.046307 +v 0.082773 0.028281 -0.041915 +v 0.083173 0.000134 -0.042613 +v 0.078282 0.025087 -0.038920 +v 0.084470 0.025087 -0.029937 +v 0.072293 0.048444 -0.021553 +v 0.069498 0.043253 -0.019556 +v 0.070696 0.050839 -0.027142 +v 0.066204 0.047945 -0.030736 +v 0.063409 0.042654 -0.028740 +v 0.079180 0.023390 -0.032932 +v 0.065106 0.040259 -0.023250 +v 0.049336 0.057926 -0.011971 +v 0.052829 0.055031 -0.007778 +v 0.046541 0.054632 -0.016862 +v 0.045443 0.048544 -0.015963 +v 0.050933 0.045549 -0.013268 +v 0.051232 0.049043 -0.006581 +v 0.032667 0.058126 -0.000592 +v 0.031070 0.054732 0.007693 +v 0.024681 0.054333 -0.001390 +v 0.027676 0.051837 0.010188 +v 0.049036 0.052037 -0.004884 +v 0.043347 0.051438 -0.014266 +v 0.021288 0.051438 0.001205 +v 0.089361 0.000134 -0.033630 +v 0.083472 0.000134 -0.039519 +v 0.083672 0.000134 -0.036325 +v 0.088064 -0.029711 -0.038920 +v 0.088962 -0.028114 -0.032932 +v 0.082773 -0.028014 -0.041915 +v 0.078282 -0.024820 -0.038920 +v 0.072293 -0.048276 -0.021553 +v 0.084470 -0.024820 -0.029937 +v 0.069498 -0.042986 -0.019556 +v 0.070696 -0.050572 -0.027142 +v 0.066204 -0.047677 -0.030736 +v 0.063409 -0.042387 -0.028740 +v 0.065106 -0.039992 -0.023250 +v 0.079180 -0.023223 -0.032932 +v 0.051232 -0.048776 -0.006581 +v 0.052829 -0.054764 -0.007778 +v 0.049336 -0.057659 -0.011971 +v 0.046541 -0.054365 -0.016862 +v 0.045443 -0.048276 -0.015963 +v 0.050933 -0.045282 -0.013268 +v 0.032667 -0.057859 -0.000592 +v 0.031070 -0.054465 0.007693 +v 0.024681 -0.054066 -0.001390 +v 0.049036 -0.051770 -0.004884 +v 0.027676 -0.051570 0.010188 +v 0.043347 -0.051171 -0.014266 +v 0.021288 -0.051271 0.001205 +v 0.093254 0.000134 -0.114380 +v 0.092755 0.000134 -0.117574 +v 0.092256 0.000134 -0.120668 +v 0.074489 0.034769 -0.099907 +v 0.074489 0.037664 -0.105497 +v 0.086267 0.000134 -0.122864 +v 0.069698 0.036466 -0.109589 +v 0.081376 0.000134 -0.118772 +v 0.065106 0.032374 -0.108092 +v 0.069897 0.030777 -0.098410 +v 0.046042 0.054233 -0.071560 +v 0.044944 0.048044 -0.071959 +v 0.042349 0.058126 -0.074754 +v 0.037558 0.055830 -0.078347 +v 0.036460 0.049641 -0.078746 +v 0.065206 0.029579 -0.102502 +v 0.040153 0.045749 -0.075552 +v 0.024781 0.057926 -0.055689 +v 0.027975 0.055031 -0.051098 +v 0.021687 0.054632 -0.060480 +v 0.020789 0.048543 -0.059382 +v 0.025979 0.045549 -0.057386 +v 0.026678 0.049043 -0.049501 +v 0.005717 0.058126 -0.032432 +v 0.006116 0.054732 -0.023948 +v -0.002268 0.054333 -0.031135 +v 0.003421 0.051837 -0.020654 +v 0.024981 0.052037 -0.047405 +v 0.019192 0.051438 -0.057286 +v -0.004863 0.051438 -0.027841 +v 0.088363 0.000134 -0.110388 +v 0.081975 0.000134 -0.115677 +v 0.082474 0.000134 -0.112583 +v 0.074489 -0.037397 -0.105497 +v 0.074489 -0.034502 -0.099907 +v 0.069698 -0.036199 -0.109589 +v 0.065106 -0.032206 -0.108092 +v 0.046042 -0.053966 -0.071560 +v 0.069897 -0.030510 -0.098410 +v 0.044944 -0.047777 -0.071959 +v 0.042349 -0.057859 -0.074754 +v 0.037558 -0.055563 -0.078347 +v 0.036460 -0.049474 -0.078746 +v 0.040153 -0.045482 -0.075552 +v 0.065206 -0.029312 -0.102502 +v 0.024781 -0.057659 -0.055689 +v 0.027975 -0.054764 -0.051098 +v 0.021687 -0.054365 -0.060480 +v 0.020789 -0.048276 -0.059382 +v 0.025979 -0.045282 -0.057386 +v 0.026678 -0.048776 -0.049501 +v 0.005717 -0.057859 -0.032432 +v 0.006116 -0.054465 -0.023948 +v -0.002268 -0.054066 -0.031135 +v 0.024981 -0.051770 -0.047405 +v 0.003421 -0.051570 -0.020654 +v 0.019192 -0.051171 -0.057286 +v -0.004863 -0.051271 -0.027841 +v 0.046142 0.054233 -0.074055 +v 0.066803 0.041756 -0.175666 +v 0.061214 0.043952 -0.176365 +v 0.040851 0.056728 -0.075752 +v 0.056422 0.040159 -0.176864 +v 0.036659 0.053334 -0.078646 +v 0.057321 0.034170 -0.176564 +v 0.037757 0.047446 -0.079844 +v 0.063010 0.031974 -0.175866 +v 0.043047 0.044950 -0.078148 +v 0.067701 0.035767 -0.175466 +v 0.047239 0.048344 -0.075153 +v 0.052330 0.036466 -0.345450 +v 0.058020 0.034470 -0.350341 +v 0.047639 0.032573 -0.345250 +v 0.048737 0.026584 -0.349942 +v 0.054526 0.024488 -0.344252 +v 0.059117 0.028481 -0.344552 +v 0.061214 -0.043785 -0.176365 +v 0.066803 -0.041489 -0.175666 +v 0.046142 -0.053966 -0.074055 +v 0.040851 -0.056461 -0.075752 +v 0.056422 -0.039892 -0.176864 +v 0.036659 -0.053068 -0.078646 +v 0.057321 -0.033903 -0.176564 +v 0.037757 -0.047179 -0.079844 +v 0.063010 -0.031707 -0.175866 +v 0.043047 -0.044683 -0.078148 +v 0.067701 -0.035500 -0.175466 +v 0.047240 -0.048077 -0.075153 +v 0.052330 -0.036199 -0.345450 +v 0.058020 -0.034203 -0.350341 +v 0.047639 -0.032306 -0.345250 +v 0.048737 -0.026317 -0.349942 +v 0.054526 -0.024321 -0.344252 +v 0.059117 -0.028214 -0.344552 +v 0.023084 0.037564 -0.176664 +v 0.023084 0.042854 -0.179758 +v 0.060315 0.037963 -0.178261 +v 0.056822 0.032673 -0.175167 +v 0.023084 0.037564 -0.170575 +v 0.057421 0.032274 -0.169178 +v 0.023084 0.042854 -0.167581 +v 0.061413 0.037065 -0.166084 +v 0.023084 0.048144 -0.170575 +v 0.064907 0.042355 -0.169078 +v 0.023084 0.048144 -0.176664 +v 0.064408 0.042754 -0.175167 +v 0.077483 0.000134 -0.192635 +v 0.072493 0.000134 -0.188343 +v 0.073890 0.000134 -0.182353 +v 0.080278 0.000134 -0.180657 +v 0.085269 0.000134 -0.184949 +v 0.083871 0.000134 -0.190938 +v 0.060315 -0.037696 -0.178261 +v 0.023084 -0.042587 -0.179758 +v 0.023084 -0.037297 -0.176664 +v 0.056822 -0.032506 -0.175167 +v 0.023084 -0.037297 -0.170575 +v 0.057421 -0.032007 -0.169178 +v 0.023084 -0.042587 -0.167581 +v 0.061413 -0.036798 -0.166084 +v 0.023084 -0.047877 -0.170575 +v 0.064907 -0.042088 -0.169078 +v 0.023084 -0.047877 -0.176664 +v 0.064408 -0.042487 -0.175167 +v 0.023084 0.037564 -0.227370 +v 0.023084 0.042854 -0.230464 +v 0.056123 0.034370 -0.240845 +v 0.052630 0.029180 -0.237750 +v 0.023084 0.037564 -0.221281 +v 0.053228 0.028680 -0.231762 +v 0.023084 0.042854 -0.218287 +v 0.057321 0.033471 -0.228667 +v 0.023084 0.048144 -0.221281 +v 0.060715 0.038762 -0.231662 +v 0.023084 0.048144 -0.227370 +v 0.060215 0.039161 -0.237750 +v 0.070896 0.000134 -0.251824 +v 0.065905 0.000134 -0.247532 +v 0.067202 0.000134 -0.241444 +v 0.073690 0.000134 -0.239747 +v 0.078681 0.000134 -0.244039 +v 0.077284 0.000134 -0.250028 +v 0.056123 -0.034103 -0.240845 +v 0.023084 -0.042587 -0.230464 +v 0.023084 -0.037297 -0.227370 +v 0.052630 -0.028913 -0.237750 +v 0.023084 -0.037297 -0.221281 +v 0.053228 -0.028413 -0.231762 +v 0.023084 -0.042587 -0.218287 +v 0.057321 -0.033205 -0.228667 +v 0.023084 -0.047877 -0.221281 +v 0.060715 -0.038495 -0.231662 +v 0.023084 -0.047877 -0.227370 +v 0.060215 -0.038994 -0.237750 +v 0.047239 0.042056 -0.356829 +v 0.052230 0.042056 -0.350341 +v 0.060914 0.031874 -0.350042 +v 0.058020 0.030377 -0.355731 +v 0.035162 0.042056 -0.358825 +v 0.052230 0.028281 -0.355531 +v 0.028075 0.042056 -0.354433 +v 0.049436 0.027682 -0.349642 +v 0.033066 0.042056 -0.347946 +v 0.052230 0.029180 -0.343853 +v 0.045143 0.042056 -0.345949 +v 0.058020 0.031276 -0.344053 +v 0.069897 0.000134 -0.348744 +v 0.066803 0.000134 -0.354433 +v 0.060615 0.000134 -0.354234 +v 0.057520 0.000134 -0.348345 +v 0.060615 0.000134 -0.342555 +v 0.066803 0.000134 -0.342755 +v 0.060914 -0.031607 -0.350042 +v 0.052230 -0.041789 -0.350341 +v 0.047239 -0.041789 -0.356829 +v 0.058020 -0.030110 -0.355731 +v 0.035162 -0.041789 -0.358825 +v 0.052230 -0.028014 -0.355531 +v 0.028075 -0.041789 -0.354433 +v 0.049436 -0.027415 -0.349642 +v 0.033066 -0.041789 -0.347946 +v 0.052230 -0.028913 -0.343853 +v 0.045143 -0.041789 -0.345949 +v 0.058020 -0.031009 -0.344053 +# 809 vertices, 0 vertices normals + +f 2 4 1 +f 4 2 3 +f 7 8 5 +f 7 5 6 +f 3 8 4 +f 8 3 9 +f 2 10 3 +f 14 11 13 +f 13 11 12 +f 3 10 9 +f 9 5 8 +f 15 16 17 +f 18 16 15 +f 16 18 19 +f 21 22 20 +f 20 22 16 +f 20 14 13 +f 20 13 21 +f 23 14 20 +f 14 23 17 +f 14 17 11 +f 11 16 12 +f 12 16 22 +f 16 11 17 +f 21 12 22 +f 12 21 13 +f 23 24 25 +f 24 23 20 +f 27 19 26 +f 19 27 16 +f 28 29 18 +f 5 9 30 +f 9 31 30 +f 32 33 25 +f 32 25 24 +f 15 34 28 +f 15 28 18 +f 19 29 26 +f 29 19 18 +f 27 24 20 +f 24 27 32 +f 20 16 27 +f 26 10 27 +f 10 26 31 +f 28 6 30 +f 28 30 29 +f 32 1 33 +f 1 32 2 +f 34 7 6 +f 34 6 28 +f 31 26 30 +f 30 26 29 +f 2 32 27 +f 2 27 10 +f 31 9 10 +f 6 5 30 +f 35 37 38 +f 37 35 36 +f 35 39 36 +f 41 43 40 +f 42 43 41 +f 44 45 46 +f 47 49 50 +f 47 48 49 +f 51 46 52 +f 50 52 53 +f 52 50 51 +f 56 54 55 +f 54 56 47 +f 58 60 57 +f 60 58 59 +f 64 62 63 +f 62 64 61 +f 60 61 64 +f 61 60 59 +f 65 63 62 +f 63 65 56 +f 47 53 54 +f 53 47 50 +f 66 46 51 +f 46 66 44 +f 67 51 50 +f 51 67 66 +f 68 69 60 +f 65 47 56 +f 47 65 48 +f 60 69 57 +f 70 63 55 +f 63 70 64 +f 64 68 60 +f 68 64 70 +f 56 55 63 +f 74 72 73 +f 72 74 71 +f 72 71 75 +f 74 77 76 +f 74 76 71 +f 78 79 77 +f 48 81 49 +f 81 48 80 +f 82 80 65 +f 65 80 48 +f 73 84 83 +f 83 84 85 +f 87 89 86 +f 89 87 88 +f 86 89 90 +f 89 91 90 +f 88 93 89 +f 93 88 92 +f 81 95 49 +f 95 81 94 +f 91 94 90 +f 91 96 94 +f 95 97 98 +f 97 95 94 +f 97 94 96 +f 81 90 94 +f 80 90 81 +f 90 80 86 +f 82 86 80 +f 86 82 87 +f 99 82 84 +f 82 99 87 +f 84 65 85 +f 65 84 82 +f 99 88 87 +f 72 84 73 +f 92 101 100 +f 101 92 88 +f 103 100 101 +f 100 103 102 +f 105 102 103 +f 102 105 104 +f 104 107 106 +f 107 104 105 +f 109 108 107 +f 106 107 108 +f 72 75 84 +f 76 75 71 +f 75 76 110 +f 88 99 75 +f 101 88 75 +f 75 110 103 +f 75 103 101 +f 110 105 103 +f 105 110 111 +f 112 91 93 +f 89 93 91 +f 114 91 112 +f 91 114 113 +f 115 114 116 +f 114 115 113 +f 96 91 113 +f 113 117 96 +f 118 116 119 +f 116 118 115 +f 121 118 119 +f 118 121 120 +f 118 120 122 +f 118 122 115 +f 104 100 102 +f 100 104 92 +f 99 84 75 +f 92 104 106 +f 93 119 116 +f 106 93 92 +f 93 106 119 +f 106 121 119 +f 121 106 108 +f 93 114 112 +f 114 93 116 +f 124 97 123 +f 97 124 98 +f 125 126 123 +f 126 124 123 +f 123 97 96 +f 50 127 67 +f 127 50 49 +f 95 67 127 +f 67 95 128 +f 129 45 130 +f 45 129 46 +f 131 45 44 +f 45 131 130 +f 52 46 132 +f 132 46 129 +f 133 44 66 +f 44 133 131 +f 128 66 67 +f 66 128 133 +f 134 53 52 +f 134 52 132 +f 53 135 54 +f 135 53 134 +f 137 135 136 +f 135 137 54 +f 139 138 36 +f 37 36 138 +f 140 141 38 +f 35 141 142 +f 141 35 38 +f 143 36 39 +f 36 143 139 +f 39 35 143 +f 143 35 142 +f 140 144 42 +f 145 40 57 +f 43 57 40 +f 69 145 57 +f 146 147 148 +f 146 149 150 +f 149 146 148 +f 150 149 151 +f 146 150 153 +f 152 153 150 +f 153 154 146 +f 158 156 157 +f 156 158 155 +f 157 156 160 +f 159 160 156 +f 83 150 73 +f 150 83 152 +f 73 151 74 +f 151 73 150 +f 62 85 65 +f 83 85 62 +f 153 83 61 +f 83 153 152 +f 62 61 83 +f 61 59 154 +f 154 153 61 +f 148 156 155 +f 159 156 147 +f 147 156 148 +f 149 148 155 +f 155 161 149 +f 151 149 161 +f 161 78 151 +f 151 77 74 +f 77 151 78 +f 158 162 155 +f 162 163 155 +f 158 157 160 +f 163 164 161 +f 164 78 161 +f 78 164 79 +f 155 163 161 +f 159 147 165 +f 147 146 165 +f 154 165 146 +f 58 154 59 +f 166 154 58 +f 144 37 167 +f 37 138 167 +f 168 144 167 +f 167 169 168 +f 170 168 171 +f 170 171 172 +f 173 175 58 +f 175 173 174 +f 57 173 58 +f 176 174 177 +f 176 175 174 +f 177 170 172 +f 170 177 174 +f 43 173 57 +f 42 174 43 +f 174 42 170 +f 174 173 43 +f 168 42 144 +f 42 168 170 +f 169 171 168 +f 160 178 162 +f 160 162 158 +f 165 154 166 +f 180 166 175 +f 166 180 179 +f 180 176 181 +f 176 180 175 +f 176 177 182 +f 182 181 176 +f 182 184 183 +f 184 182 177 +f 186 172 171 +f 172 186 185 +f 187 171 169 +f 171 187 186 +f 188 169 189 +f 169 188 187 +f 189 191 190 +f 189 190 188 +f 191 193 192 +f 191 192 190 +f 192 195 194 +f 195 192 193 +f 196 194 195 +f 195 197 196 +f 190 192 194 +f 188 194 196 +f 194 188 190 +f 199 70 198 +f 70 199 68 +f 200 68 199 +f 68 200 69 +f 203 201 202 +f 201 203 40 +f 40 203 41 +f 204 140 41 +f 204 41 203 +f 140 204 197 +f 140 197 141 +f 205 69 200 +f 69 205 145 +f 70 206 198 +f 206 70 55 +f 55 137 206 +f 137 55 54 +f 201 145 205 +f 145 201 40 +f 196 197 204 +f 188 196 187 +f 204 187 196 +f 185 204 203 +f 204 185 186 +f 186 187 204 +f 140 37 144 +f 37 140 38 +f 195 193 191 +f 189 195 191 +f 195 189 197 +f 138 142 141 +f 142 138 139 +f 143 142 139 +f 197 189 169 +f 141 167 138 +f 167 141 197 +f 167 197 169 +f 172 184 177 +f 184 172 185 +f 127 49 95 +f 128 95 98 +f 207 128 124 +f 207 126 208 +f 126 207 124 +f 130 131 129 +f 132 129 131 +f 134 132 207 +f 207 132 133 +f 133 132 131 +f 58 175 166 +f 117 123 96 +f 113 115 117 +f 115 209 117 +f 209 115 122 +f 209 123 117 +f 123 209 125 +f 134 208 210 +f 208 134 207 +f 128 207 133 +f 98 124 128 +f 140 42 41 +f 136 134 210 +f 134 136 135 +f 160 211 178 +f 211 160 159 +f 212 159 165 +f 159 212 211 +f 179 165 166 +f 165 179 212 +f 202 183 203 +f 184 203 183 +f 216 213 215 +f 215 213 214 +f 217 215 214 +f 221 219 220 +f 221 218 219 +f 222 223 224 +f 228 225 227 +f 226 227 225 +f 224 229 230 +f 228 230 229 +f 230 228 231 +f 234 233 227 +f 233 234 232 +f 236 238 235 +f 238 236 237 +f 242 240 241 +f 240 242 239 +f 238 241 235 +f 241 238 242 +f 239 243 240 +f 243 239 234 +f 227 231 228 +f 231 227 233 +f 229 224 244 +f 244 224 223 +f 245 229 244 +f 229 245 228 +f 246 247 238 +f 243 227 226 +f 227 243 234 +f 246 238 237 +f 248 239 242 +f 239 248 232 +f 242 247 248 +f 247 242 238 +f 232 234 239 +f 252 250 251 +f 250 252 249 +f 251 250 253 +f 77 251 76 +f 251 77 252 +f 79 254 77 +f 226 256 255 +f 256 226 225 +f 255 257 243 +f 243 226 255 +f 258 249 259 +f 259 260 258 +f 262 264 261 +f 264 262 263 +f 264 263 265 +f 265 266 264 +f 261 268 267 +f 268 261 264 +f 225 269 256 +f 256 269 270 +f 270 266 265 +f 271 266 270 +f 269 273 270 +f 273 269 272 +f 270 273 271 +f 265 256 270 +f 255 265 263 +f 265 255 256 +f 257 263 262 +f 263 257 255 +f 258 257 274 +f 274 257 262 +f 243 258 260 +f 258 243 257 +f 261 274 262 +f 258 250 249 +f 276 267 275 +f 267 276 261 +f 278 275 277 +f 275 278 276 +f 277 280 278 +f 280 277 279 +f 279 282 280 +f 282 279 281 +f 108 109 282 +f 108 282 281 +f 253 250 258 +f 76 251 253 +f 253 110 76 +f 274 261 253 +f 261 276 253 +f 278 253 276 +f 110 253 278 +f 110 280 111 +f 280 110 278 +f 268 264 266 +f 268 266 283 +f 266 285 283 +f 285 266 284 +f 286 287 285 +f 286 285 284 +f 266 288 284 +f 288 266 271 +f 289 290 287 +f 289 287 286 +f 289 121 290 +f 121 289 120 +f 289 122 120 +f 122 289 286 +f 279 275 267 +f 275 279 277 +f 258 274 253 +f 279 267 281 +f 290 268 287 +f 281 268 290 +f 268 281 267 +f 281 121 108 +f 121 281 290 +f 268 285 287 +f 285 268 283 +f 273 292 291 +f 292 273 272 +f 126 291 292 +f 291 126 125 +f 273 291 271 +f 228 293 225 +f 293 228 245 +f 245 269 293 +f 269 245 294 +f 222 224 295 +f 222 295 296 +f 297 222 296 +f 222 297 223 +f 224 230 298 +f 298 295 224 +f 299 223 297 +f 223 299 244 +f 244 294 245 +f 294 244 299 +f 231 300 230 +f 300 298 230 +f 301 231 233 +f 231 301 300 +f 137 301 233 +f 301 137 136 +f 303 213 302 +f 213 303 214 +f 304 305 216 +f 216 215 306 +f 306 304 216 +f 303 307 217 +f 303 217 214 +f 217 306 215 +f 306 217 307 +f 308 305 218 +f 237 221 220 +f 237 220 309 +f 309 246 237 +f 310 311 312 +f 311 314 312 +f 314 311 313 +f 314 313 315 +f 313 311 317 +f 317 316 313 +f 318 317 311 +f 320 322 319 +f 322 320 321 +f 323 324 320 +f 323 320 319 +f 259 313 316 +f 313 259 249 +f 315 249 252 +f 249 315 313 +f 260 240 243 +f 260 259 240 +f 317 259 316 +f 259 317 241 +f 241 240 259 +f 235 241 318 +f 318 241 317 +f 320 312 321 +f 320 324 310 +f 320 310 312 +f 312 314 321 +f 321 314 325 +f 314 315 325 +f 325 315 254 +f 77 315 252 +f 315 77 254 +f 321 163 322 +f 322 163 162 +f 319 322 323 +f 164 163 325 +f 164 254 79 +f 254 164 325 +f 163 321 325 +f 311 310 326 +f 324 326 310 +f 326 318 311 +f 318 236 235 +f 318 327 236 +f 328 302 213 +f 328 213 308 +f 330 328 329 +f 308 329 328 +f 329 331 332 +f 332 331 333 +f 334 336 236 +f 336 334 335 +f 336 237 236 +f 335 337 338 +f 334 337 335 +f 338 331 335 +f 331 338 333 +f 336 221 237 +f 218 335 331 +f 335 218 221 +f 336 335 221 +f 308 218 329 +f 329 218 331 +f 332 330 329 +f 322 162 323 +f 178 323 162 +f 318 326 327 +f 180 327 179 +f 327 180 334 +f 337 180 181 +f 180 337 334 +f 338 337 182 +f 182 337 181 +f 339 182 183 +f 182 339 338 +f 341 333 340 +f 333 341 332 +f 342 332 341 +f 332 342 330 +f 344 330 343 +f 342 343 330 +f 346 343 345 +f 343 346 344 +f 348 346 347 +f 345 347 346 +f 347 349 348 +f 348 349 350 +f 349 351 350 +f 350 351 352 +f 347 345 349 +f 349 343 351 +f 343 349 345 +f 199 248 247 +f 248 199 198 +f 200 247 246 +f 247 200 199 +f 201 353 202 +f 353 201 220 +f 353 220 219 +f 353 219 354 +f 305 354 219 +f 354 305 352 +f 352 305 304 +f 205 200 309 +f 309 200 246 +f 198 206 248 +f 248 206 232 +f 206 137 232 +f 232 137 233 +f 220 201 205 +f 220 205 309 +f 352 351 354 +f 342 354 351 +f 342 351 343 +f 354 340 353 +f 340 354 341 +f 342 341 354 +f 213 305 308 +f 305 213 216 +f 348 350 346 +f 344 350 352 +f 350 344 346 +f 306 302 304 +f 302 306 303 +f 306 307 303 +f 344 352 330 +f 328 304 302 +f 352 328 330 +f 328 352 304 +f 339 333 338 +f 333 339 340 +f 225 293 269 +f 269 294 272 +f 294 355 292 +f 355 126 292 +f 126 355 208 +f 297 296 295 +f 295 298 297 +f 355 298 300 +f 298 355 299 +f 298 299 297 +f 334 236 327 +f 291 288 271 +f 286 284 288 +f 286 209 122 +f 209 286 288 +f 291 125 288 +f 288 125 209 +f 300 208 355 +f 208 300 210 +f 355 294 299 +f 292 272 294 +f 218 305 219 +f 136 300 301 +f 300 136 210 +f 211 323 178 +f 323 211 324 +f 212 324 211 +f 324 212 326 +f 179 326 212 +f 326 179 327 +f 340 339 353 +f 353 183 202 +f 183 353 339 +f 185 203 184 +f 111 282 109 +f 111 280 282 +f 111 107 105 +f 111 109 107 +f 359 357 358 +f 357 359 356 +f 360 362 363 +f 362 360 361 +f 363 356 359 +f 356 363 364 +f 365 357 356 +f 369 366 368 +f 368 366 367 +f 365 356 364 +f 362 364 363 +f 370 371 372 +f 370 374 371 +f 374 370 373 +f 375 376 377 +f 377 370 375 +f 369 377 366 +f 366 377 376 +f 369 378 377 +f 378 369 372 +f 369 368 372 +f 370 368 367 +f 370 367 375 +f 368 370 372 +f 376 367 366 +f 367 376 375 +f 380 378 379 +f 378 380 377 +f 381 373 370 +f 373 381 382 +f 383 384 374 +f 386 364 385 +f 385 364 362 +f 388 387 379 +f 379 387 380 +f 371 384 389 +f 384 371 374 +f 373 383 374 +f 383 373 382 +f 381 380 387 +f 380 381 377 +f 370 377 381 +f 365 382 381 +f 382 365 386 +f 383 385 384 +f 361 384 385 +f 357 388 358 +f 388 357 387 +f 389 361 360 +f 361 389 384 +f 383 382 385 +f 382 386 385 +f 387 365 381 +f 365 387 357 +f 364 386 365 +f 362 361 385 +f 393 391 392 +f 391 393 390 +f 393 394 395 +f 394 393 392 +f 396 397 395 +f 396 395 394 +f 399 396 398 +f 396 399 397 +f 401 398 400 +f 398 401 399 +f 391 390 401 +f 391 401 400 +f 402 392 391 +f 391 403 402 +f 394 402 404 +f 402 394 392 +f 396 404 405 +f 404 396 394 +f 406 398 396 +f 396 405 406 +f 407 400 398 +f 398 406 407 +f 391 407 403 +f 407 391 400 +f 408 409 410 +f 408 410 411 +f 412 410 409 +f 410 412 413 +f 412 414 415 +f 415 413 412 +f 415 416 417 +f 416 415 414 +f 408 419 418 +f 419 408 411 +f 418 421 420 +f 421 418 419 +f 425 423 424 +f 423 425 422 +f 423 421 424 +f 421 423 420 +f 417 426 427 +f 426 417 416 +f 425 427 426 +f 425 426 422 +f 413 415 410 +f 414 408 416 +f 408 414 409 +f 417 427 411 +f 427 419 411 +f 427 425 419 +f 425 421 419 +f 423 422 420 +f 412 409 414 +f 426 416 408 +f 426 408 418 +f 426 418 422 +f 418 420 422 +f 415 411 410 +f 411 415 417 +f 424 421 425 +f 428 430 431 +f 430 428 429 +f 433 428 432 +f 428 433 429 +f 435 433 434 +f 434 433 432 +f 434 437 435 +f 437 434 436 +f 439 430 438 +f 430 439 431 +f 438 441 439 +f 441 438 440 +f 445 443 444 +f 443 445 442 +f 441 443 442 +f 443 441 440 +f 436 447 437 +f 447 436 446 +f 446 445 447 +f 444 447 445 +f 434 432 428 +f 435 430 429 +f 430 435 437 +f 446 436 431 +f 446 431 439 +f 445 446 439 +f 439 441 445 +f 444 443 440 +f 429 433 435 +f 437 447 430 +f 447 438 430 +f 438 447 444 +f 444 440 438 +f 434 431 436 +f 431 434 428 +f 441 442 445 +f 449 450 448 +f 448 450 451 +f 450 452 451 +f 451 452 453 +f 452 454 453 +f 453 454 455 +f 457 455 456 +f 456 455 454 +f 458 460 461 +f 460 458 459 +f 460 462 461 +f 461 462 463 +f 462 465 463 +f 465 462 464 +f 464 466 465 +f 465 466 467 +f 466 448 467 +f 448 466 449 +f 458 457 459 +f 459 457 456 +f 448 455 457 +f 455 448 451 +f 464 462 460 +f 459 456 466 +f 466 456 449 +f 466 460 459 +f 460 466 464 +f 449 454 450 +f 454 449 456 +f 454 452 450 +f 467 457 458 +f 457 467 448 +f 451 453 455 +f 461 463 465 +f 467 461 465 +f 461 467 458 +f 468 469 470 +f 470 471 468 +f 472 471 473 +f 471 472 468 +f 474 473 475 +f 473 474 472 +f 476 475 477 +f 475 476 474 +f 478 480 481 +f 480 478 479 +f 482 481 483 +f 481 482 478 +f 484 483 485 +f 483 484 482 +f 486 484 485 +f 485 487 486 +f 486 470 469 +f 470 486 487 +f 479 477 480 +f 477 479 476 +f 477 471 470 +f 471 477 475 +f 482 484 478 +f 486 476 479 +f 476 486 469 +f 478 484 486 +f 478 486 479 +f 476 469 468 +f 476 468 474 +f 472 474 468 +f 470 487 480 +f 480 477 470 +f 473 471 475 +f 483 481 485 +f 481 487 485 +f 487 481 480 +f 488 489 490 +f 490 491 488 +f 492 490 489 +f 490 492 493 +f 492 494 495 +f 492 495 493 +f 496 498 499 +f 498 496 497 +f 501 496 499 +f 496 501 500 +f 502 500 501 +f 502 501 503 +f 494 502 503 +f 494 503 495 +f 498 504 505 +f 504 498 497 +f 504 507 505 +f 507 504 506 +f 506 508 509 +f 509 507 506 +f 491 511 510 +f 491 510 488 +f 511 513 512 +f 511 512 510 +f 514 512 513 +f 513 515 514 +f 508 514 515 +f 515 509 508 +f 518 519 516 +f 518 516 517 +f 520 519 521 +f 519 520 516 +f 522 520 521 +f 522 521 523 +f 522 525 524 +f 525 522 523 +f 526 524 525 +f 525 527 526 +f 527 518 517 +f 527 517 526 +f 521 496 500 +f 496 521 519 +f 496 519 497 +f 502 521 500 +f 521 502 523 +f 502 494 523 +f 497 518 504 +f 518 497 519 +f 492 525 494 +f 525 523 494 +f 527 510 512 +f 510 527 525 +f 518 512 514 +f 512 518 527 +f 506 514 508 +f 504 514 506 +f 514 504 518 +f 489 488 510 +f 510 492 489 +f 492 510 525 +f 490 511 491 +f 507 509 515 +f 515 505 507 +f 505 515 517 +f 511 493 524 +f 493 511 490 +f 511 526 513 +f 526 511 524 +f 517 513 526 +f 513 517 515 +f 517 498 505 +f 498 517 516 +f 499 498 516 +f 493 495 524 +f 524 495 522 +f 495 503 522 +f 520 503 501 +f 503 520 522 +f 520 499 516 +f 499 520 501 +f 529 530 528 +f 528 530 531 +f 532 529 528 +f 529 532 533 +f 534 533 532 +f 533 534 535 +f 539 536 538 +f 538 536 537 +f 541 539 540 +f 540 539 538 +f 543 540 542 +f 540 543 541 +f 534 542 535 +f 542 534 543 +f 544 537 536 +f 537 544 545 +f 546 545 544 +f 545 546 547 +f 549 547 548 +f 548 547 546 +f 551 531 550 +f 530 550 531 +f 553 551 552 +f 550 552 551 +f 552 554 553 +f 553 554 555 +f 554 549 555 +f 555 549 548 +f 559 556 558 +f 557 558 556 +f 561 559 560 +f 560 559 558 +f 561 562 563 +f 562 561 560 +f 565 562 564 +f 562 565 563 +f 564 566 565 +f 565 566 567 +f 556 567 557 +f 566 557 567 +f 561 538 559 +f 538 561 540 +f 559 538 537 +f 561 542 540 +f 542 561 563 +f 535 542 563 +f 556 537 545 +f 537 556 559 +f 565 533 535 +f 565 535 563 +f 550 567 552 +f 567 550 565 +f 556 552 567 +f 552 556 554 +f 554 547 549 +f 554 545 547 +f 545 554 556 +f 530 529 550 +f 550 533 565 +f 533 550 529 +f 551 528 531 +f 548 546 555 +f 544 555 546 +f 555 544 557 +f 551 532 528 +f 532 551 564 +f 566 551 553 +f 551 566 564 +f 557 553 555 +f 553 557 566 +f 536 557 544 +f 557 536 558 +f 536 539 558 +f 564 534 532 +f 534 564 562 +f 543 534 562 +f 543 560 541 +f 560 543 562 +f 560 539 541 +f 539 560 558 +f 571 569 570 +f 569 571 568 +f 572 571 570 +f 573 572 570 +f 572 573 574 +f 575 576 573 +f 573 576 574 +f 571 579 577 +f 579 571 578 +f 572 580 571 +f 571 580 578 +f 580 574 581 +f 574 580 572 +f 581 574 582 +f 582 574 576 +f 583 582 576 +f 582 583 584 +f 583 579 584 +f 579 583 577 +f 580 585 578 +f 585 586 578 +f 581 585 580 +f 585 581 587 +f 587 582 588 +f 582 587 581 +f 582 589 588 +f 584 589 582 +f 579 589 584 +f 589 579 590 +f 585 591 586 +f 591 592 586 +f 587 591 585 +f 591 587 593 +f 586 592 595 +f 595 592 594 +f 596 597 593 +f 596 593 587 +f 579 586 590 +f 586 579 578 +f 588 589 590 +f 590 596 588 +f 596 590 595 +f 591 593 592 +f 597 592 593 +f 592 597 594 +f 595 597 596 +f 597 595 594 +f 568 577 598 +f 577 568 571 +f 576 599 583 +f 599 576 575 +f 600 583 599 +f 583 600 577 +f 600 598 577 +f 601 570 569 +f 569 602 601 +f 569 568 602 +f 573 601 603 +f 601 573 570 +f 573 604 575 +f 604 573 603 +f 602 607 605 +f 607 602 606 +f 608 601 602 +f 602 605 608 +f 603 608 609 +f 608 603 601 +f 610 604 603 +f 603 609 610 +f 612 610 611 +f 610 612 604 +f 607 606 612 +f 607 612 611 +f 607 613 614 +f 614 605 607 +f 615 608 605 +f 605 614 615 +f 609 615 616 +f 615 609 608 +f 610 616 617 +f 616 610 609 +f 618 611 610 +f 610 617 618 +f 607 618 613 +f 618 607 611 +f 619 615 614 +f 614 620 619 +f 616 619 621 +f 619 616 615 +f 622 623 620 +f 620 614 622 +f 625 624 621 +f 616 621 624 +f 618 617 613 +f 613 624 622 +f 624 613 617 +f 621 619 620 +f 620 625 621 +f 625 620 623 +f 625 622 624 +f 622 625 623 +f 568 606 602 +f 606 568 598 +f 599 612 600 +f 612 599 604 +f 575 604 599 +f 600 606 598 +f 606 600 612 +f 586 595 590 +f 588 596 587 +f 613 622 614 +f 616 624 617 +f 629 626 627 +f 628 629 627 +f 630 629 628 +f 631 630 628 +f 630 631 632 +f 632 633 634 +f 633 632 631 +f 629 637 635 +f 637 629 636 +f 636 629 638 +f 630 638 629 +f 638 632 639 +f 632 638 630 +f 639 632 640 +f 640 632 634 +f 640 641 642 +f 641 640 634 +f 641 637 642 +f 635 637 641 +f 644 636 643 +f 638 643 636 +f 643 638 645 +f 639 645 638 +f 645 640 646 +f 640 645 639 +f 640 647 646 +f 647 640 642 +f 637 647 642 +f 647 637 648 +f 650 644 649 +f 643 649 644 +f 645 649 643 +f 649 645 651 +f 652 653 650 +f 644 650 653 +f 651 645 654 +f 654 655 651 +f 644 637 636 +f 637 644 648 +f 646 647 648 +f 648 654 646 +f 654 648 653 +f 649 651 650 +f 655 650 651 +f 650 655 652 +f 653 655 654 +f 655 653 652 +f 626 629 656 +f 635 656 629 +f 634 657 641 +f 657 634 633 +f 658 641 657 +f 656 635 658 +f 641 658 635 +f 644 653 648 +f 646 654 645 +f 659 628 627 +f 627 660 659 +f 627 626 660 +f 631 659 661 +f 659 631 628 +f 633 661 662 +f 661 633 631 +f 660 665 663 +f 665 660 664 +f 666 659 660 +f 666 660 663 +f 661 666 667 +f 666 661 659 +f 668 662 661 +f 661 667 668 +f 670 668 669 +f 668 670 662 +f 665 664 670 +f 670 669 665 +f 671 666 663 +f 663 672 671 +f 673 667 666 +f 666 671 673 +f 673 668 667 +f 668 673 674 +f 668 674 675 +f 668 675 669 +f 675 665 669 +f 665 675 676 +f 677 671 672 +f 672 678 677 +f 673 677 679 +f 677 673 671 +f 680 681 678 +f 678 672 680 +f 683 682 679 +f 673 679 682 +f 672 665 676 +f 665 672 663 +f 675 674 676 +f 682 676 674 +f 676 682 680 +f 679 677 678 +f 678 683 679 +f 683 678 681 +f 683 680 682 +f 680 683 681 +f 656 660 626 +f 660 656 664 +f 657 662 658 +f 658 662 670 +f 633 662 657 +f 664 656 658 +f 664 658 670 +f 680 672 676 +f 682 674 673 +f 687 685 686 +f 685 687 684 +f 689 686 688 +f 686 689 687 +f 688 691 689 +f 691 688 690 +f 692 691 690 +f 691 692 693 +f 694 693 692 +f 693 694 695 +f 695 685 684 +f 685 695 694 +f 696 686 685 +f 685 697 696 +f 688 696 698 +f 696 688 686 +f 690 698 699 +f 698 690 688 +f 700 692 690 +f 690 699 700 +f 701 694 692 +f 692 700 701 +f 685 701 697 +f 701 685 694 +f 705 703 704 +f 703 705 702 +f 707 702 705 +f 702 707 706 +f 709 706 707 +f 706 709 708 +f 711 710 709 +f 709 710 708 +f 713 712 711 +f 711 712 710 +f 704 703 713 +f 713 703 712 +f 702 714 703 +f 703 714 715 +f 706 714 702 +f 714 706 716 +f 708 716 706 +f 716 708 717 +f 717 708 718 +f 710 718 708 +f 718 710 719 +f 712 719 710 +f 719 703 715 +f 703 719 712 +f 721 723 720 +f 723 721 722 +f 724 723 725 +f 723 724 720 +f 727 726 725 +f 725 726 724 +f 729 728 727 +f 727 728 726 +f 731 728 729 +f 728 731 730 +f 730 722 721 +f 722 730 731 +f 723 732 733 +f 722 732 723 +f 734 723 733 +f 723 734 725 +f 735 727 734 +f 734 727 725 +f 727 735 736 +f 727 736 729 +f 736 731 729 +f 731 736 737 +f 737 722 731 +f 722 737 732 +f 739 741 738 +f 741 739 740 +f 742 743 741 +f 742 741 740 +f 743 742 744 +f 744 745 743 +f 745 744 746 +f 746 747 745 +f 746 749 747 +f 749 746 748 +f 748 738 749 +f 738 748 739 +f 741 733 732 +f 741 732 738 +f 734 741 743 +f 741 734 733 +f 734 745 735 +f 745 734 743 +f 745 736 735 +f 747 736 745 +f 736 749 737 +f 749 736 747 +f 737 738 732 +f 738 737 749 +f 751 753 750 +f 753 751 752 +f 755 750 753 +f 750 755 754 +f 757 756 755 +f 755 756 754 +f 759 758 757 +f 757 758 756 +f 761 760 759 +f 758 759 760 +f 760 752 751 +f 752 760 761 +f 753 762 763 +f 752 762 753 +f 764 753 763 +f 753 764 755 +f 765 757 764 +f 764 757 755 +f 757 765 766 +f 757 766 759 +f 766 761 759 +f 761 766 767 +f 767 752 761 +f 752 767 762 +f 769 771 768 +f 771 769 770 +f 773 770 772 +f 770 773 771 +f 773 772 774 +f 774 775 773 +f 775 774 776 +f 776 777 775 +f 777 776 778 +f 777 778 779 +f 778 768 779 +f 768 778 769 +f 771 763 762 +f 771 762 768 +f 764 771 773 +f 771 764 763 +f 764 775 765 +f 775 764 773 +f 775 766 765 +f 777 766 775 +f 766 779 767 +f 779 766 777 +f 767 768 762 +f 768 767 779 +f 781 782 780 +f 782 783 780 +f 785 780 783 +f 780 785 784 +f 784 787 786 +f 787 784 785 +f 789 788 787 +f 787 788 786 +f 791 790 789 +f 788 789 790 +f 790 791 781 +f 791 782 781 +f 793 783 792 +f 782 792 783 +f 794 783 793 +f 783 794 785 +f 787 794 795 +f 794 787 785 +f 796 789 787 +f 796 787 795 +f 791 796 797 +f 796 791 789 +f 791 797 792 +f 791 792 782 +f 798 799 800 +f 800 801 798 +f 803 800 802 +f 800 803 801 +f 805 802 804 +f 802 805 803 +f 806 807 805 +f 806 805 804 +f 807 806 808 +f 808 809 807 +f 809 808 799 +f 799 798 809 +f 792 798 801 +f 792 801 793 +f 801 794 793 +f 794 801 803 +f 805 795 794 +f 805 794 803 +f 795 805 796 +f 807 796 805 +f 796 809 797 +f 809 796 807 +f 809 792 797 +f 792 809 798 +# 1494 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_lleg_chull.obj b/examples/Atlas/urdf/mesh/l_lleg_chull.obj new file mode 100644 index 0000000..8732272 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_lleg_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_lleg_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.005717 -0.057859 -0.032432 +v 0.071035 -0.050665 -0.021669 +v 0.021705 0.060052 -0.007531 +v 0.071030 0.050931 -0.021748 +v -0.000814 -0.047260 -0.310515 +v 0.043715 -0.060881 0.014841 +v -0.038900 0.050041 -0.139933 +v -0.041571 0.038541 -0.333141 +v -0.038900 -0.049773 -0.139933 +v -0.006041 0.046179 -0.353100 +v 0.042349 0.058126 -0.074754 +v 0.088630 -0.029596 -0.032856 +v 0.060798 -0.031624 -0.351242 +v 0.050900 -0.044557 -0.353980 +v 0.050900 0.044824 -0.353980 +v 0.060798 0.031891 -0.351242 +v 0.088625 0.029867 -0.032878 +v 0.094751 0.000134 -0.109988 +v 0.069972 0.000134 -0.350335 +v 0.038932 0.051877 0.020755 +v 0.092434 0.000115 -0.031037 +v -0.016805 -0.051585 0.020840 +v -0.017081 0.051836 0.019069 +v -0.038098 -0.039358 -0.331344 +v -0.001230 0.023728 -0.438277 +v -0.002300 -0.024724 -0.439154 +v -0.041639 -0.011187 -0.118129 +# 27 vertices, 0 vertices normals + +f 1 6 5 +f 8 10 7 +f 9 1 5 +f 1 9 22 +f 9 27 22 +f 21 17 18 +f 14 6 2 +f 14 2 12 +f 21 18 12 +f 6 1 22 +f 3 11 4 +f 3 23 7 +f 10 3 7 +f 11 3 10 +f 4 17 20 +f 21 20 17 +f 13 26 14 +f 24 5 26 +f 24 9 5 +f 21 12 6 +f 6 12 2 +f 3 4 20 +f 20 6 22 +f 15 17 4 +f 11 15 4 +f 5 6 14 +f 14 26 5 +f 7 23 27 +f 27 8 7 +f 26 8 24 +f 10 8 25 +f 19 25 26 +f 19 26 13 +f 20 23 3 +f 27 24 8 +f 9 24 27 +f 10 15 11 +f 25 15 10 +f 19 16 25 +f 16 15 25 +f 18 19 13 +f 12 18 13 +f 13 14 12 +f 15 16 17 +f 16 18 17 +f 16 19 18 +f 20 21 6 +f 27 23 22 +f 20 22 23 +f 25 8 26 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_talus.obj b/examples/Atlas/urdf/mesh/l_talus.obj new file mode 100644 index 0000000..a3c1fe5 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_talus.obj @@ -0,0 +1,92 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_talus.obj +# +# Vertices: 28 +# Faces: 48 +# +#### +v 0.006590 -0.015904 -0.008474 +v 0.006590 0.016747 -0.008474 +v 0.010622 0.016747 -0.000100 +v 0.010622 -0.015904 -0.000100 +v -0.002471 -0.015904 -0.010542 +v -0.002471 0.016747 -0.010542 +v -0.009737 -0.015904 -0.004747 +v -0.009737 0.016747 -0.004747 +v -0.009737 -0.015904 0.004546 +v -0.009737 0.016747 0.004546 +v -0.002471 -0.015904 0.010341 +v -0.002471 0.016747 0.010341 +v 0.006590 -0.015904 0.008273 +v 0.006590 0.016747 0.008273 +v -0.016413 -0.006858 -0.009229 +v 0.016238 -0.006858 -0.009229 +v 0.016238 -0.011254 -0.000100 +v -0.016413 -0.011254 -0.000100 +v -0.016413 0.003020 -0.011484 +v 0.016238 0.003020 -0.011484 +v -0.016413 0.010941 -0.005166 +v 0.016238 0.010941 -0.005166 +v -0.016413 0.010941 0.004966 +v 0.016238 0.010941 0.004966 +v -0.016413 0.003020 0.011283 +v 0.016238 0.003020 0.011283 +v -0.016413 -0.006858 0.009028 +v 0.016238 -0.006858 0.009028 +# 28 vertices, 0 vertices normals + +f 3 4 1 +f 3 1 2 +f 5 2 1 +f 2 5 6 +f 7 6 5 +f 6 7 8 +f 9 10 8 +f 9 8 7 +f 11 12 10 +f 10 9 11 +f 13 14 12 +f 12 11 13 +f 14 13 4 +f 14 4 3 +f 4 7 5 +f 4 5 1 +f 7 11 9 +f 11 7 4 +f 11 4 13 +f 8 12 14 +f 12 8 10 +f 14 2 6 +f 14 6 8 +f 2 14 3 +f 17 18 15 +f 17 15 16 +f 19 16 15 +f 16 19 20 +f 21 20 19 +f 20 21 22 +f 23 24 22 +f 23 22 21 +f 24 23 25 +f 24 25 26 +f 26 25 27 +f 26 27 28 +f 28 27 18 +f 28 18 17 +f 21 15 18 +f 15 21 19 +f 21 25 23 +f 25 21 18 +f 25 18 27 +f 28 22 24 +f 28 24 26 +f 16 22 28 +f 22 16 20 +f 16 28 17 +# 48 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_uglut.obj b/examples/Atlas/urdf/mesh/l_uglut.obj new file mode 100644 index 0000000..4934433 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_uglut.obj @@ -0,0 +1,740 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_uglut.obj +# +# Vertices: 238 +# Faces: 486 +# +#### +v 0.033190 0.017127 0.011995 +v 0.049145 0.017127 0.011995 +v 0.049145 0.020554 -0.003462 +v 0.039190 0.020554 -0.003462 +v 0.049145 0.012047 -0.016815 +v 0.039190 0.012047 -0.016815 +v 0.049145 -0.003410 -0.020242 +v 0.039190 -0.003410 -0.020242 +v 0.049145 -0.016764 -0.011735 +v 0.039190 -0.016763 -0.011735 +v 0.049145 -0.020190 0.003722 +v 0.039190 -0.020190 0.003722 +v 0.040715 0.005330 0.003734 +v 0.040715 0.001273 0.006319 +v 0.039190 0.003774 0.020502 +v 0.040715 -0.006007 0.001221 +v 0.040715 -0.004966 -0.003475 +v 0.040715 -0.003422 0.005278 +v 0.039190 -0.011683 0.017075 +v 0.047621 0.001377 0.006907 +v 0.047621 0.005819 0.004077 +v 0.049145 0.003774 0.020502 +v 0.047621 0.006959 -0.001065 +v 0.047621 0.004129 -0.005507 +v 0.047621 -0.001013 -0.006647 +v 0.047621 -0.005455 -0.003817 +v 0.047621 -0.006595 0.001325 +v 0.047621 -0.003765 0.005767 +v 0.049145 -0.011683 0.017075 +v 0.040715 -0.000909 -0.006059 +v 0.040715 0.003786 -0.005018 +v 0.040715 0.006371 -0.000961 +v 0.036381 0.002679 0.127511 +v 0.049145 0.002679 0.127511 +v 0.049145 0.012205 0.121443 +v 0.036381 0.012205 0.121443 +v 0.049145 0.014649 0.110416 +v 0.036381 0.014649 0.110416 +v 0.036381 -0.014172 0.104141 +v 0.049145 -0.014172 0.104141 +v 0.049145 -0.014416 0.115541 +v 0.036381 -0.014416 0.115541 +v 0.049145 -0.008348 0.125067 +v 0.036381 -0.008348 0.125067 +v 0.037906 0.006522 0.117464 +v 0.037906 0.001474 0.120680 +v 0.037906 0.007817 0.111621 +v 0.037906 0.004602 0.106573 +v 0.036381 0.008581 0.100890 +v 0.037906 -0.001241 0.105278 +v 0.036381 -0.002446 0.098446 +v 0.037906 -0.006289 0.108493 +v 0.037906 -0.007585 0.114337 +v 0.037906 -0.004369 0.119384 +v 0.047621 0.001603 0.121411 +v 0.047621 0.007131 0.117890 +v 0.047621 0.008549 0.111492 +v 0.047621 0.005028 0.105965 +v 0.049145 0.008581 0.100890 +v 0.047621 -0.001370 0.104546 +v 0.049145 -0.002446 0.098446 +v 0.047621 -0.006898 0.108067 +v 0.047621 -0.008316 0.114466 +v 0.047621 -0.004795 0.119993 +v 0.030808 0.018549 0.071550 +v 0.049145 0.018549 0.071550 +v 0.049145 0.006586 0.067529 +v 0.049145 -0.006280 0.064677 +v 0.049145 -0.016670 0.062467 +v 0.030808 -0.016670 0.062467 +v 0.030808 -0.006279 0.064677 +v 0.030808 0.006586 0.067529 +v 0.011414 0.017418 -0.019670 +v 0.020040 0.003878 -0.019670 +v 0.020040 0.003878 -0.040319 +v 0.011414 0.017418 -0.040319 +v -0.004260 0.020893 -0.019670 +v -0.004260 0.020893 -0.040319 +v -0.017800 0.012267 -0.019670 +v -0.017800 0.012267 -0.040319 +v -0.021275 -0.003407 -0.019670 +v -0.021275 -0.003407 -0.040319 +v -0.012649 -0.016947 -0.019670 +v -0.012649 -0.016947 -0.040319 +v 0.003025 -0.020422 -0.019670 +v 0.003025 -0.020422 -0.040319 +v 0.016565 -0.011795 -0.019670 +v 0.016565 -0.011795 -0.040319 +v 0.020040 0.003878 -0.012050 +v 0.011414 0.017418 -0.012050 +v -0.004260 0.020893 -0.012050 +v -0.017800 0.012267 -0.012050 +v -0.021275 -0.003407 -0.012050 +v -0.012649 -0.016947 -0.012050 +v 0.003025 -0.020422 -0.012050 +v 0.016565 -0.011795 -0.012050 +v 0.010271 0.002156 -0.040319 +v 0.005724 0.009292 -0.040319 +v 0.005724 0.009292 -0.012050 +v 0.010271 0.002156 -0.012050 +v -0.002537 0.011124 -0.040319 +v -0.002537 0.011124 -0.012050 +v -0.009674 0.006577 -0.040319 +v -0.009674 0.006577 -0.012050 +v -0.011505 -0.001684 -0.040319 +v -0.011505 -0.001684 -0.012050 +v -0.006959 -0.008821 -0.040319 +v -0.006959 -0.008821 -0.012050 +v 0.001303 -0.010652 -0.040319 +v 0.001303 -0.010652 -0.012050 +v 0.008439 -0.006105 -0.040319 +v 0.008439 -0.006105 -0.012050 +v -0.033234 0.020554 -0.003462 +v -0.033234 0.017127 0.011995 +v -0.014469 0.017127 0.011995 +v -0.020469 0.020554 -0.003462 +v -0.033234 0.012047 -0.016815 +v -0.020469 0.012047 -0.016815 +v -0.033234 -0.003410 -0.020242 +v -0.020469 -0.003410 -0.020242 +v -0.033234 -0.016764 -0.011735 +v -0.020469 -0.016764 -0.011735 +v -0.033234 -0.020190 0.003722 +v -0.020469 -0.020190 0.003722 +v -0.020469 0.003774 0.020502 +v -0.021994 0.001273 0.006319 +v -0.021994 0.005330 0.003734 +v -0.021994 -0.004966 -0.003475 +v -0.021994 -0.006007 0.001221 +v -0.021994 -0.003422 0.005278 +v -0.020469 -0.011683 0.017075 +v -0.031709 0.005819 0.004077 +v -0.031709 0.001377 0.006907 +v -0.033234 0.003774 0.020502 +v -0.031709 0.006959 -0.001065 +v -0.031709 0.004129 -0.005507 +v -0.031709 -0.001013 -0.006647 +v -0.031709 -0.005455 -0.003817 +v -0.031709 -0.006595 0.001325 +v -0.033234 -0.011683 0.017075 +v -0.031709 -0.003765 0.005767 +v -0.021994 -0.000909 -0.006059 +v -0.021994 0.003786 -0.005018 +v -0.021994 0.006371 -0.000961 +v -0.033234 0.012205 0.121443 +v -0.033234 0.002679 0.127511 +v -0.020469 0.002679 0.127511 +v -0.020469 0.012205 0.121443 +v -0.033234 0.014649 0.110416 +v -0.020469 0.014649 0.110416 +v -0.033234 -0.014416 0.115541 +v -0.033234 -0.014172 0.104141 +v -0.020469 -0.014172 0.104141 +v -0.020469 -0.014416 0.115541 +v -0.033234 -0.008348 0.125067 +v -0.020469 -0.008348 0.125067 +v -0.021994 0.001474 0.120680 +v -0.021994 0.006522 0.117464 +v -0.021994 0.007817 0.111621 +v -0.021994 0.004602 0.106573 +v -0.020469 0.008581 0.100890 +v -0.021994 -0.001241 0.105278 +v -0.020469 -0.002446 0.098446 +v -0.021994 -0.006289 0.108493 +v -0.021994 -0.007585 0.114337 +v -0.021994 -0.004369 0.119384 +v -0.031709 0.007131 0.117890 +v -0.031709 0.001603 0.121411 +v -0.031709 0.008549 0.111492 +v -0.033234 0.008581 0.100890 +v -0.031709 0.005028 0.105965 +v -0.033234 -0.002446 0.098446 +v -0.031709 -0.001370 0.104546 +v -0.031709 -0.006898 0.108067 +v -0.031709 -0.008316 0.114466 +v -0.031709 -0.004795 0.119993 +v -0.011116 0.071649 -0.018766 +v -0.011116 0.069725 -0.009324 +v 0.029909 0.068424 -0.009304 +v 0.029909 0.071825 -0.016749 +v -0.011564 0.066874 -0.026261 +v 0.029909 0.068424 -0.024960 +v -0.011954 0.058198 -0.028184 +v 0.030746 0.060214 -0.028361 +v 0.033903 0.060214 -0.005138 +v 0.033903 0.060214 -0.011239 +v 0.031685 0.064110 -0.012853 +v -0.012893 0.064727 -0.013589 +v -0.015110 0.061171 -0.011323 +v -0.015110 0.062230 -0.005314 +v 0.030804 0.065724 -0.016749 +v -0.011564 0.065640 -0.017706 +v 0.031685 0.064110 -0.020646 +v -0.012893 0.063374 -0.021263 +v 0.033903 0.060214 -0.022259 +v -0.015110 0.059257 -0.022176 +v 0.033903 0.056318 -0.020646 +v 0.033903 0.052003 -0.024960 +v -0.015110 0.050702 -0.023410 +v -0.015110 0.055700 -0.019910 +v 0.033903 0.054704 -0.016749 +v 0.033903 0.048602 -0.016749 +v -0.015110 0.048779 -0.014733 +v -0.015110 0.054787 -0.015793 +v 0.033903 0.056318 -0.012853 +v 0.033903 0.052003 -0.008539 +v -0.015110 0.053554 -0.007238 +v -0.015110 0.057053 -0.012236 +v -0.033234 0.018549 0.071550 +v -0.014896 0.018549 0.071550 +v -0.033234 0.006586 0.067529 +v -0.033234 -0.006280 0.064677 +v -0.033234 -0.016670 0.062467 +v -0.014896 -0.016670 0.062467 +v -0.014896 -0.006279 0.064677 +v -0.014896 0.006586 0.067529 +v 0.040267 0.017744 0.072430 +v 0.035253 0.017741 0.041350 +v -0.016460 0.017782 0.040815 +v -0.021475 0.017771 0.072429 +v 0.030746 0.017797 -0.040884 +v -0.011954 0.017797 -0.040897 +v 0.033903 0.017748 -0.040918 +v -0.015110 0.017748 -0.040809 +v 0.033903 0.017723 -0.009967 +v -0.015110 0.017723 -0.009762 +v 0.033903 0.017712 0.007381 +v -0.015110 0.017744 0.011325 +v -0.004782 0.065845 -0.003319 +v 0.023493 0.064645 -0.003312 +v 0.034488 0.017742 0.072430 +v -0.015789 0.021476 0.072427 +v -0.009782 0.028919 0.008095 +v 0.028493 0.027719 0.008100 +v 0.034298 0.018152 0.072431 +v -0.015587 0.019352 0.072431 +v 0.029407 0.023693 -0.011774 +v -0.010665 0.024397 -0.011822 +# 238 vertices, 0 vertices normals + +f 2 4 1 +f 4 2 3 +f 4 3 5 +f 4 5 6 +f 8 5 7 +f 5 8 6 +f 10 7 9 +f 7 10 8 +f 12 10 11 +f 11 10 9 +f 1 14 15 +f 14 1 13 +f 16 10 12 +f 10 16 17 +f 19 16 12 +f 16 19 18 +f 15 14 19 +f 19 14 18 +f 21 22 20 +f 22 21 2 +f 3 21 23 +f 21 3 2 +f 3 23 5 +f 5 23 24 +f 25 5 24 +f 5 25 7 +f 7 26 9 +f 26 7 25 +f 9 27 11 +f 27 9 26 +f 11 28 29 +f 28 11 27 +f 28 22 29 +f 22 28 20 +f 27 17 16 +f 17 27 26 +f 25 17 26 +f 17 25 30 +f 24 31 25 +f 31 30 25 +f 23 31 24 +f 31 23 32 +f 21 13 23 +f 13 32 23 +f 20 13 21 +f 13 20 14 +f 28 18 20 +f 18 14 20 +f 18 27 16 +f 27 18 28 +f 33 35 36 +f 35 33 34 +f 36 35 37 +f 36 37 38 +f 42 39 41 +f 41 39 40 +f 44 42 43 +f 43 42 41 +f 33 44 34 +f 34 44 43 +f 36 46 33 +f 46 36 45 +f 45 38 47 +f 38 45 36 +f 49 47 38 +f 47 49 48 +f 49 51 50 +f 49 50 48 +f 50 51 52 +f 51 39 52 +f 42 52 39 +f 52 42 53 +f 44 53 42 +f 53 44 54 +f 44 33 46 +f 44 46 54 +f 56 34 55 +f 34 56 35 +f 37 56 57 +f 56 37 35 +f 37 57 59 +f 59 57 58 +f 60 59 58 +f 59 60 61 +f 62 61 60 +f 61 62 40 +f 41 40 62 +f 41 62 63 +f 43 41 63 +f 43 63 64 +f 43 55 34 +f 55 43 64 +f 63 52 53 +f 52 63 62 +f 60 52 62 +f 52 60 50 +f 58 48 60 +f 48 50 60 +f 57 48 58 +f 48 57 47 +f 56 45 57 +f 45 47 57 +f 55 45 56 +f 45 55 46 +f 64 54 55 +f 54 46 55 +f 54 63 53 +f 63 54 64 +f 1 65 66 +f 66 2 1 +f 66 22 2 +f 22 66 67 +f 68 22 67 +f 22 68 29 +f 69 29 68 +f 29 69 11 +f 69 12 11 +f 12 69 70 +f 70 19 12 +f 19 70 71 +f 71 15 19 +f 15 71 72 +f 65 15 72 +f 15 65 1 +f 37 66 38 +f 38 66 65 +f 66 59 67 +f 59 66 37 +f 61 67 59 +f 67 61 68 +f 61 69 68 +f 69 61 40 +f 39 69 40 +f 69 39 70 +f 51 70 39 +f 70 51 71 +f 51 72 71 +f 72 51 49 +f 49 65 72 +f 65 49 38 +f 73 74 75 +f 73 75 76 +f 77 73 76 +f 77 76 78 +f 79 77 78 +f 79 78 80 +f 81 79 80 +f 81 80 82 +f 83 81 82 +f 83 82 84 +f 85 83 84 +f 85 84 86 +f 87 85 86 +f 87 86 88 +f 74 87 88 +f 74 88 75 +f 89 73 90 +f 73 89 74 +f 90 77 91 +f 77 90 73 +f 91 79 92 +f 79 91 77 +f 92 81 93 +f 81 92 79 +f 93 83 94 +f 83 93 81 +f 94 85 95 +f 85 94 83 +f 95 87 96 +f 87 95 85 +f 96 74 89 +f 74 96 87 +f 76 97 98 +f 97 76 75 +f 100 89 90 +f 100 90 99 +f 78 76 101 +f 101 76 98 +f 90 102 99 +f 102 90 91 +f 78 103 80 +f 78 101 103 +f 104 91 92 +f 91 104 102 +f 82 103 105 +f 103 82 80 +f 92 93 104 +f 104 93 106 +f 107 84 82 +f 107 82 105 +f 93 108 106 +f 108 93 94 +f 84 109 86 +f 109 84 107 +f 94 110 108 +f 110 94 95 +f 88 109 111 +f 109 88 86 +f 95 96 110 +f 110 96 112 +f 111 97 88 +f 97 75 88 +f 96 100 112 +f 100 96 89 +f 97 100 99 +f 99 98 97 +f 111 112 100 +f 100 97 111 +f 109 110 112 +f 112 111 109 +f 107 108 110 +f 110 109 107 +f 105 106 108 +f 108 107 105 +f 103 104 106 +f 106 105 103 +f 101 102 104 +f 104 103 101 +f 98 99 102 +f 102 101 98 +f 114 116 113 +f 116 114 115 +f 113 116 117 +f 116 118 117 +f 120 117 118 +f 117 120 119 +f 122 119 120 +f 119 122 121 +f 123 122 124 +f 122 123 121 +f 115 126 127 +f 126 115 125 +f 124 122 129 +f 129 122 128 +f 131 129 130 +f 129 131 124 +f 131 126 125 +f 126 131 130 +f 132 134 114 +f 134 132 133 +f 114 113 132 +f 132 113 135 +f 117 135 113 +f 135 117 136 +f 137 117 119 +f 117 137 136 +f 119 138 137 +f 138 119 121 +f 121 139 138 +f 139 121 123 +f 123 141 139 +f 141 123 140 +f 140 134 141 +f 141 134 133 +f 128 139 129 +f 139 128 138 +f 137 128 142 +f 128 137 138 +f 143 136 137 +f 143 137 142 +f 135 143 144 +f 143 135 136 +f 127 132 135 +f 127 135 144 +f 133 127 126 +f 127 133 132 +f 130 141 133 +f 130 133 126 +f 130 139 141 +f 139 130 129 +f 145 147 148 +f 147 145 146 +f 145 148 149 +f 148 150 149 +f 151 153 154 +f 153 151 152 +f 155 154 156 +f 154 155 151 +f 146 156 147 +f 156 146 155 +f 148 157 158 +f 157 148 147 +f 158 150 148 +f 150 158 159 +f 161 159 160 +f 159 161 150 +f 163 161 162 +f 162 161 160 +f 163 162 164 +f 164 153 163 +f 154 164 165 +f 164 154 153 +f 156 165 166 +f 165 156 154 +f 156 157 147 +f 157 156 166 +f 146 167 168 +f 167 146 145 +f 145 149 167 +f 167 149 169 +f 170 169 149 +f 169 170 171 +f 173 170 172 +f 170 173 171 +f 172 174 173 +f 174 172 152 +f 151 174 152 +f 174 151 175 +f 151 155 175 +f 175 155 176 +f 155 168 176 +f 168 155 146 +f 164 175 165 +f 175 164 174 +f 173 164 162 +f 164 173 174 +f 160 171 173 +f 160 173 162 +f 169 160 159 +f 160 169 171 +f 158 167 169 +f 158 169 159 +f 168 158 157 +f 158 168 167 +f 166 176 168 +f 166 168 157 +f 166 175 176 +f 175 166 165 +f 180 178 179 +f 178 180 177 +f 182 177 180 +f 177 182 181 +f 184 181 182 +f 181 184 183 +f 179 185 187 +f 187 185 186 +f 178 188 189 +f 178 189 190 +f 191 180 179 +f 191 179 187 +f 178 177 188 +f 188 177 192 +f 182 191 193 +f 191 182 180 +f 181 192 177 +f 192 181 194 +f 184 182 195 +f 195 182 193 +f 181 196 194 +f 196 181 183 +f 184 195 197 +f 197 198 184 +f 183 200 196 +f 200 183 199 +f 202 198 201 +f 201 198 197 +f 203 200 199 +f 200 203 204 +f 206 201 205 +f 201 206 202 +f 203 208 204 +f 208 203 207 +f 185 205 186 +f 205 185 206 +f 207 190 208 +f 208 190 189 +f 205 204 208 +f 204 205 201 +f 201 200 204 +f 200 201 197 +f 196 197 195 +f 197 196 200 +f 195 194 196 +f 194 195 193 +f 192 193 191 +f 193 192 194 +f 187 188 192 +f 187 192 191 +f 186 189 188 +f 186 188 187 +f 208 186 205 +f 186 208 189 +f 210 114 209 +f 114 210 115 +f 209 134 211 +f 134 209 114 +f 212 134 140 +f 134 212 211 +f 213 140 123 +f 140 213 212 +f 213 124 214 +f 124 213 123 +f 214 131 215 +f 131 214 124 +f 215 125 216 +f 125 215 131 +f 210 125 115 +f 125 210 216 +f 150 209 149 +f 209 150 210 +f 209 170 149 +f 170 209 211 +f 211 172 170 +f 172 211 212 +f 172 213 152 +f 213 172 212 +f 213 153 152 +f 153 213 214 +f 163 214 215 +f 214 163 153 +f 163 216 161 +f 216 163 215 +f 210 161 216 +f 161 210 150 +f 4 116 1 +f 1 116 115 +f 13 115 127 +f 115 13 1 +f 127 32 13 +f 32 127 144 +f 144 31 32 +f 31 144 143 +f 143 30 31 +f 30 143 142 +f 142 17 30 +f 17 142 128 +f 17 122 10 +f 122 17 128 +f 10 120 8 +f 120 10 122 +f 120 6 8 +f 6 120 118 +f 6 116 4 +f 116 6 118 +f 179 217 185 +f 185 217 218 +f 190 220 178 +f 220 190 219 +f 221 222 183 +f 221 183 184 +f 221 184 198 +f 183 222 199 +f 224 199 222 +f 223 202 225 +f 202 223 198 +f 226 199 224 +f 199 226 203 +f 206 225 202 +f 225 206 227 +f 226 207 203 +f 228 207 226 +f 185 227 206 +f 227 185 218 +f 207 219 190 +f 219 207 228 +f 178 230 179 +f 230 178 229 +f 230 231 217 +f 217 179 230 +f 220 229 178 +f 229 220 232 +f 229 233 230 +f 230 233 234 +f 231 230 234 +f 233 232 236 +f 232 233 229 +f 233 219 228 +f 237 238 222 +f 237 222 221 +f 235 218 231 +f 218 217 231 +f 234 218 235 +f 237 223 225 +f 223 237 221 +f 238 224 222 +f 224 238 226 +f 233 226 238 +f 226 233 228 +f 237 234 233 +f 237 233 238 +f 234 225 227 +f 225 234 237 +f 220 219 232 +f 219 236 232 +f 233 236 219 +f 234 227 218 +# 486 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_uglut_chull.obj b/examples/Atlas/urdf/mesh/l_uglut_chull.obj new file mode 100644 index 0000000..215151e --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_uglut_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_uglut_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.010540 0.072586 -0.015884 +v 0.008666 -0.020440 -0.040398 +v -0.011564 0.066874 -0.026261 +v 0.029909 0.071825 -0.016749 +v 0.030404 0.068126 -0.025919 +v -0.015552 0.018895 -0.040910 +v 0.033903 0.017748 -0.040918 +v -0.012649 -0.016947 -0.040319 +v -0.021275 -0.003407 -0.040319 +v -0.033234 0.002679 0.127511 +v 0.049145 0.002679 0.127511 +v 0.049145 -0.008348 0.125067 +v -0.033234 -0.008348 0.125067 +v -0.033234 -0.016764 -0.011735 +v -0.033234 -0.014416 0.115541 +v -0.034605 0.005463 -0.017709 +v -0.033234 0.018549 0.071550 +v -0.033234 0.020557 -0.003451 +v -0.033234 -0.020190 0.003722 +v -0.033418 0.012464 0.120868 +v 0.049145 -0.014416 0.115541 +v 0.049145 0.018549 0.071550 +v 0.049138 0.020625 -0.012668 +v 0.049503 0.012256 0.121327 +v 0.049145 -0.003410 -0.020242 +v 0.049145 -0.020190 0.003722 +v 0.049145 -0.016764 -0.011735 +# 27 vertices, 0 vertices normals + +f 1 24 20 +f 24 1 4 +f 16 3 18 +f 24 4 22 +f 1 5 4 +f 3 5 1 +f 1 18 3 +f 23 5 7 +f 26 27 2 +f 18 1 17 +f 20 17 1 +f 25 7 2 +f 25 2 27 +f 25 23 7 +f 23 22 4 +f 6 7 5 +f 6 5 3 +f 9 6 16 +f 3 16 6 +f 14 9 16 +f 2 19 26 +f 5 23 4 +f 2 7 6 +f 8 14 19 +f 8 19 2 +f 14 8 9 +f 2 6 8 +f 8 6 9 +f 10 24 11 +f 10 20 24 +f 11 12 10 +f 10 12 13 +f 14 10 13 +f 14 13 15 +f 18 17 14 +f 14 16 18 +f 15 19 14 +f 20 14 17 +f 20 10 14 +f 23 21 22 +f 21 11 24 +f 21 24 22 +f 23 25 21 +f 21 12 11 +f 27 26 21 +f 21 25 27 +f 21 15 13 +f 12 21 13 +f 21 19 15 +f 21 26 19 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_uleg.obj b/examples/Atlas/urdf/mesh/l_uleg.obj new file mode 100644 index 0000000..da133af --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_uleg.obj @@ -0,0 +1,3726 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_uleg.obj +# +# Vertices: 1246 +# Faces: 2464 +# +#### +v -0.051197 0.012924 -0.061447 +v -0.053869 0.013386 -0.062289 +v -0.053523 0.000258 -0.061604 +v -0.052277 0.000258 -0.060385 +v -0.056009 0.025629 -0.065658 +v -0.051081 0.025783 -0.064644 +v -0.062193 0.038587 -0.072882 +v -0.050952 0.041471 -0.071773 +v -0.068221 0.049687 -0.078694 +v -0.050893 0.052294 -0.079492 +v -0.074112 0.059783 -0.086318 +v -0.051295 0.059860 -0.086896 +v -0.058806 0.064420 -0.091399 +v -0.070524 0.063277 -0.090561 +v -0.091589 0.045259 -0.090589 +v -0.081116 0.051490 -0.086567 +v -0.092010 0.054892 -0.093867 +v -0.072426 0.046407 -0.081524 +v -0.083531 0.037447 -0.087634 +v -0.067736 0.037117 -0.078015 +v -0.075572 0.031713 -0.083426 +v -0.065413 0.023452 -0.076014 +v -0.093507 0.013433 -0.091059 +v -0.109342 0.016306 -0.094825 +v -0.109939 0.000258 -0.094752 +v -0.094009 0.000258 -0.091158 +v -0.064488 0.012006 -0.075089 +v -0.063777 0.000258 -0.074354 +v -0.078702 0.012855 -0.085273 +v -0.078792 0.000258 -0.085356 +v -0.101816 0.029781 -0.092876 +v -0.090005 0.026374 -0.090065 +v -0.076961 0.024270 -0.084033 +v -0.106569 0.036275 -0.096463 +v -0.115328 0.019401 -0.100672 +v -0.117667 0.000258 -0.101490 +v -0.120738 0.000258 -0.110085 +v -0.117031 0.023168 -0.108534 +v -0.105552 0.044647 -0.105575 +v -0.085972 0.062474 -0.101808 +v -0.060860 0.069421 -0.099940 +v -0.051265 0.069191 -0.099502 +v -0.061901 0.072533 -0.112494 +v -0.051525 0.073867 -0.113498 +v -0.086224 0.063887 -0.115244 +v -0.105663 0.046639 -0.117205 +v -0.118758 0.023574 -0.119546 +v -0.122704 0.000258 -0.121204 +v -0.125285 0.000258 -0.139711 +v -0.121061 0.024254 -0.137744 +v -0.107642 0.047121 -0.133799 +v -0.087362 0.064054 -0.132521 +v -0.063073 0.073049 -0.132773 +v -0.050562 0.073988 -0.133170 +v -0.063504 0.073055 -0.164836 +v -0.051023 0.074267 -0.164841 +v -0.087476 0.064844 -0.162812 +v -0.108671 0.048428 -0.160118 +v -0.122347 0.025920 -0.160064 +v -0.126781 0.000258 -0.158457 +v -0.127756 0.000258 -0.184270 +v -0.123377 0.025396 -0.183655 +v -0.109617 0.048197 -0.184420 +v -0.088284 0.064576 -0.187759 +v -0.095422 0.060197 -0.209259 +v -0.110649 0.046802 -0.199318 +v -0.067714 0.071726 -0.189989 +v -0.051254 0.074258 -0.190996 +v -0.064912 0.072865 -0.208364 +v -0.050825 0.074239 -0.208502 +v -0.075506 0.070050 -0.208934 +v -0.083843 0.066469 -0.224522 +v -0.068850 0.071266 -0.233928 +v -0.050862 0.073833 -0.228241 +v -0.063342 0.069308 -0.257286 +v -0.051135 0.071451 -0.253097 +v -0.060669 0.061239 -0.288781 +v -0.051079 0.063646 -0.284915 +v -0.050628 0.056429 -0.303569 +v -0.055637 0.056462 -0.302933 +v -0.070700 0.065682 -0.266290 +v -0.051051 0.068488 -0.267879 +v -0.061096 0.044083 -0.287938 +v -0.070259 0.044281 -0.268612 +v -0.081772 0.065346 -0.247192 +v -0.080877 0.044165 -0.251290 +v -0.093618 0.059921 -0.232955 +v -0.089176 0.039671 -0.239523 +v -0.107492 0.048563 -0.217962 +v -0.099493 0.028445 -0.228028 +v -0.123276 0.023812 -0.202756 +v -0.103974 0.013178 -0.222541 +v -0.127144 0.000258 -0.199854 +v -0.105319 0.000258 -0.221239 +v -0.054376 0.051196 -0.316434 +v -0.050364 0.051026 -0.315899 +v -0.056045 0.044167 -0.302012 +v -0.054571 0.044953 -0.316470 +v -0.051197 -0.012408 -0.061447 +v -0.053869 -0.012870 -0.062289 +v -0.056009 -0.025113 -0.065658 +v -0.051081 -0.025267 -0.064644 +v -0.062193 -0.038071 -0.072882 +v -0.050952 -0.040955 -0.071773 +v -0.068221 -0.049171 -0.078694 +v -0.050893 -0.051777 -0.079491 +v -0.074112 -0.059267 -0.086318 +v -0.070524 -0.062760 -0.090561 +v -0.058806 -0.063904 -0.091399 +v -0.051295 -0.059344 -0.086896 +v -0.091589 -0.044742 -0.090589 +v -0.092010 -0.054376 -0.093867 +v -0.081116 -0.050974 -0.086567 +v -0.072426 -0.045891 -0.081524 +v -0.083531 -0.036931 -0.087634 +v -0.067736 -0.036601 -0.078015 +v -0.075572 -0.031197 -0.083426 +v -0.065413 -0.022936 -0.076014 +v -0.093507 -0.012917 -0.091059 +v -0.109342 -0.015790 -0.094825 +v -0.064488 -0.011490 -0.075089 +v -0.078702 -0.012339 -0.085273 +v -0.101816 -0.029265 -0.092876 +v -0.090005 -0.025859 -0.090065 +v -0.076961 -0.023754 -0.084033 +v -0.106569 -0.035759 -0.096463 +v -0.115328 -0.018885 -0.100672 +v -0.117031 -0.022652 -0.108534 +v -0.105552 -0.044131 -0.105575 +v -0.085972 -0.061958 -0.101808 +v -0.060860 -0.068904 -0.099940 +v -0.051265 -0.068675 -0.099502 +v -0.061901 -0.072017 -0.112494 +v -0.051525 -0.073351 -0.113498 +v -0.086224 -0.063371 -0.115244 +v -0.105663 -0.046123 -0.117205 +v -0.118758 -0.023058 -0.119546 +v -0.121061 -0.023738 -0.137744 +v -0.107643 -0.046605 -0.133799 +v -0.087362 -0.063537 -0.132521 +v -0.063073 -0.072533 -0.132772 +v -0.050562 -0.073472 -0.133170 +v -0.063504 -0.072539 -0.164836 +v -0.051023 -0.073751 -0.164841 +v -0.087476 -0.064328 -0.162812 +v -0.108671 -0.047912 -0.160118 +v -0.122347 -0.025404 -0.160064 +v -0.123377 -0.024880 -0.183655 +v -0.109617 -0.047681 -0.184420 +v -0.088284 -0.064060 -0.187759 +v -0.095422 -0.059681 -0.209259 +v -0.110649 -0.046286 -0.199318 +v -0.067714 -0.071210 -0.189989 +v -0.051254 -0.073742 -0.190996 +v -0.064912 -0.072349 -0.208364 +v -0.050825 -0.073723 -0.208502 +v -0.075506 -0.069534 -0.208934 +v -0.083843 -0.065953 -0.224522 +v -0.068850 -0.070750 -0.233928 +v -0.050862 -0.073317 -0.228241 +v -0.063342 -0.068792 -0.257286 +v -0.051135 -0.070935 -0.253097 +v -0.060669 -0.060723 -0.288781 +v -0.055637 -0.055946 -0.302933 +v -0.050628 -0.055913 -0.303569 +v -0.051079 -0.063130 -0.284915 +v -0.070700 -0.065166 -0.266290 +v -0.051051 -0.067972 -0.267879 +v -0.070259 -0.043765 -0.268612 +v -0.061096 -0.043567 -0.287938 +v -0.081772 -0.064830 -0.247192 +v -0.080877 -0.043649 -0.251290 +v -0.093618 -0.059405 -0.232955 +v -0.089176 -0.039155 -0.239523 +v -0.107492 -0.048047 -0.217962 +v -0.099493 -0.027929 -0.228028 +v -0.123276 -0.023296 -0.202756 +v -0.103974 -0.012662 -0.222541 +v -0.054376 -0.050680 -0.316434 +v -0.050364 -0.050510 -0.315899 +v -0.056045 -0.043651 -0.302012 +v -0.054571 -0.044436 -0.316470 +v -0.050079 0.012251 -0.065365 +v -0.049581 0.000258 -0.063514 +v -0.050471 0.000258 -0.064386 +v -0.051684 0.012945 -0.065766 +v -0.054072 0.024759 -0.069201 +v -0.050237 0.024473 -0.068469 +v -0.060403 0.037459 -0.076429 +v -0.050081 0.039415 -0.075248 +v -0.066978 0.048164 -0.082326 +v -0.050507 0.049758 -0.082729 +v -0.072938 0.057016 -0.089150 +v -0.069798 0.059767 -0.092614 +v -0.058872 0.061166 -0.093941 +v -0.051365 0.056899 -0.089774 +v -0.089872 0.044663 -0.094297 +v -0.089321 0.052474 -0.095861 +v -0.079222 0.050652 -0.090140 +v -0.070165 0.046424 -0.084980 +v -0.081827 0.037399 -0.091395 +v -0.065089 0.037125 -0.081186 +v -0.073441 0.031611 -0.086962 +v -0.062659 0.023420 -0.079092 +v -0.092272 0.013438 -0.095000 +v -0.092812 0.000258 -0.095110 +v -0.108053 0.000258 -0.098426 +v -0.107338 0.015979 -0.098421 +v -0.061672 0.012004 -0.078109 +v -0.060916 0.000258 -0.077333 +v -0.076756 0.012911 -0.088915 +v -0.076824 0.000258 -0.088987 +v -0.100241 0.029502 -0.096684 +v -0.088639 0.026307 -0.093962 +v -0.074927 0.024234 -0.087627 +v -0.103640 0.034908 -0.099033 +v -0.111906 0.018614 -0.102846 +v -0.114185 0.000258 -0.103712 +v -0.116738 0.000258 -0.111113 +v -0.113228 0.021902 -0.109530 +v -0.102375 0.042243 -0.106663 +v -0.083924 0.059036 -0.102830 +v -0.060366 0.065612 -0.101459 +v -0.051396 0.065480 -0.101310 +v -0.061028 0.068535 -0.113048 +v -0.051130 0.069790 -0.114027 +v -0.084107 0.060354 -0.115549 +v -0.102476 0.044052 -0.117660 +v -0.114892 0.022249 -0.120142 +v -0.118623 0.000258 -0.121838 +v -0.121178 0.000258 -0.140143 +v -0.117188 0.022880 -0.138163 +v -0.104481 0.044485 -0.134139 +v -0.085268 0.060496 -0.132667 +v -0.062188 0.069016 -0.132858 +v -0.050222 0.069873 -0.133232 +v -0.062621 0.069020 -0.164847 +v -0.050634 0.070156 -0.164850 +v -0.085512 0.061212 -0.162897 +v -0.105598 0.045674 -0.160307 +v -0.118494 0.024452 -0.160300 +v -0.122659 0.000258 -0.158704 +v -0.123626 0.000258 -0.184282 +v -0.119503 0.023963 -0.183676 +v -0.106552 0.045429 -0.184444 +v -0.086310 0.060948 -0.187792 +v -0.093031 0.056830 -0.209210 +v -0.107445 0.044199 -0.199178 +v -0.066702 0.067722 -0.189992 +v -0.050655 0.070172 -0.190949 +v -0.064162 0.068804 -0.208414 +v -0.050371 0.070134 -0.208506 +v -0.074148 0.066150 -0.209018 +v -0.082065 0.062745 -0.224347 +v -0.067897 0.067261 -0.233595 +v -0.050385 0.069738 -0.228000 +v -0.062560 0.065318 -0.256564 +v -0.050653 0.067391 -0.252514 +v -0.058014 0.058644 -0.286972 +v -0.053007 0.053765 -0.301240 +v -0.050452 0.052619 -0.301985 +v -0.050614 0.059735 -0.283674 +v -0.068033 0.063028 -0.264586 +v -0.050477 0.064522 -0.266877 +v -0.066610 0.044170 -0.266682 +v -0.057285 0.044066 -0.286347 +v -0.078977 0.062738 -0.245629 +v -0.077393 0.043913 -0.249087 +v -0.090506 0.057744 -0.231334 +v -0.085942 0.039472 -0.236963 +v -0.104099 0.046812 -0.216388 +v -0.096315 0.028371 -0.225391 +v -0.119537 0.022874 -0.201275 +v -0.100979 0.013141 -0.219697 +v -0.123305 0.000258 -0.198332 +v -0.102393 0.000258 -0.218324 +v -0.051352 0.048677 -0.315180 +v -0.050612 0.047189 -0.314391 +v -0.052025 0.044101 -0.301064 +v -0.050464 0.044822 -0.316059 +v -0.050079 -0.011735 -0.065365 +v -0.051684 -0.012429 -0.065766 +v -0.054072 -0.024243 -0.069201 +v -0.050237 -0.023957 -0.068469 +v -0.060403 -0.036943 -0.076429 +v -0.050081 -0.038899 -0.075248 +v -0.066978 -0.047648 -0.082326 +v -0.050507 -0.049242 -0.082729 +v -0.072938 -0.056500 -0.089150 +v -0.051365 -0.056383 -0.089774 +v -0.058872 -0.060650 -0.093940 +v -0.069798 -0.059251 -0.092614 +v -0.089872 -0.044147 -0.094297 +v -0.079222 -0.050136 -0.090140 +v -0.089321 -0.051958 -0.095861 +v -0.070165 -0.045908 -0.084980 +v -0.081827 -0.036883 -0.091395 +v -0.065089 -0.036609 -0.081186 +v -0.073441 -0.031096 -0.086962 +v -0.062659 -0.022904 -0.079092 +v -0.092272 -0.012922 -0.095000 +v -0.107338 -0.015463 -0.098421 +v -0.061672 -0.011488 -0.078109 +v -0.076756 -0.012395 -0.088915 +v -0.100241 -0.028986 -0.096684 +v -0.088639 -0.025791 -0.093962 +v -0.074927 -0.023718 -0.087627 +v -0.103640 -0.034392 -0.099033 +v -0.111906 -0.018097 -0.102846 +v -0.113228 -0.021386 -0.109530 +v -0.102375 -0.041727 -0.106663 +v -0.083924 -0.058520 -0.102830 +v -0.060366 -0.065096 -0.101459 +v -0.051396 -0.064964 -0.101310 +v -0.061028 -0.068019 -0.113048 +v -0.051130 -0.069275 -0.114027 +v -0.084107 -0.059838 -0.115549 +v -0.102476 -0.043536 -0.117660 +v -0.114892 -0.021733 -0.120142 +v -0.117188 -0.022364 -0.138163 +v -0.104481 -0.043969 -0.134139 +v -0.085268 -0.059981 -0.132667 +v -0.062188 -0.068500 -0.132858 +v -0.050222 -0.069357 -0.133232 +v -0.062621 -0.068504 -0.164847 +v -0.050634 -0.069640 -0.164849 +v -0.085512 -0.060696 -0.162897 +v -0.105598 -0.045158 -0.160306 +v -0.118494 -0.023936 -0.160300 +v -0.119503 -0.023447 -0.183676 +v -0.106552 -0.044913 -0.184444 +v -0.086310 -0.060432 -0.187792 +v -0.093031 -0.056314 -0.209210 +v -0.107445 -0.043683 -0.199178 +v -0.066702 -0.067206 -0.189992 +v -0.050655 -0.069656 -0.190949 +v -0.064162 -0.068288 -0.208414 +v -0.050371 -0.069618 -0.208506 +v -0.074148 -0.065634 -0.209018 +v -0.082065 -0.062229 -0.224347 +v -0.067897 -0.066745 -0.233595 +v -0.050385 -0.069222 -0.228000 +v -0.062560 -0.064802 -0.256564 +v -0.050653 -0.066875 -0.252514 +v -0.058014 -0.058128 -0.286972 +v -0.050614 -0.059219 -0.283674 +v -0.050452 -0.052103 -0.301985 +v -0.053007 -0.053249 -0.301240 +v -0.068033 -0.062512 -0.264586 +v -0.050477 -0.064006 -0.266877 +v -0.057285 -0.043550 -0.286347 +v -0.066610 -0.043654 -0.266682 +v -0.078977 -0.062222 -0.245629 +v -0.077393 -0.043397 -0.249087 +v -0.090506 -0.057228 -0.231334 +v -0.085942 -0.038956 -0.236963 +v -0.104099 -0.046296 -0.216388 +v -0.096315 -0.027855 -0.225391 +v -0.119537 -0.022358 -0.201275 +v -0.100979 -0.012625 -0.219697 +v -0.051352 -0.048161 -0.315180 +v -0.050612 -0.046673 -0.314391 +v -0.052025 -0.043585 -0.301064 +v -0.050464 -0.044306 -0.316059 +v -0.026482 -0.045983 -0.344329 +v -0.024778 -0.047494 -0.332917 +v -0.036297 -0.046875 -0.334804 +v -0.033785 -0.046008 -0.343062 +v -0.018607 -0.043295 -0.343112 +v -0.013129 -0.047138 -0.332893 +v -0.019521 -0.050786 -0.320706 +v -0.036180 -0.050224 -0.320841 +v -0.002343 -0.047454 -0.324966 +v -0.007498 -0.073461 -0.026448 +v -0.012557 -0.073731 -0.030529 +v -0.005394 -0.073743 -0.035325 +v -0.001038 -0.073765 -0.028646 +v -0.006144 -0.073747 -0.040857 +v 0.004654 -0.073779 -0.036666 +v -0.017100 -0.073735 -0.037081 +v -0.006520 -0.073742 -0.047133 +v 0.006194 -0.073766 -0.047888 +v -0.022975 -0.073780 -0.047387 +v -0.028293 -0.073768 -0.060834 +v -0.009151 -0.073733 -0.063017 +v -0.012724 -0.073748 -0.081529 +v -0.032368 -0.073818 -0.078053 +v 0.007401 -0.073748 -0.063457 +v -0.032971 -0.073831 -0.100557 +v -0.015746 -0.073735 -0.102862 +v 0.011751 -0.073585 -0.084866 +v 0.003018 -0.073754 -0.104400 +v 0.009828 -0.073376 -0.119367 +v 0.025417 -0.071268 -0.108499 +v -0.012727 -0.073734 -0.126503 +v -0.031815 -0.073824 -0.125250 +v -0.017438 -0.056672 -0.305981 +v -0.035946 -0.056726 -0.304456 +v -0.000678 -0.053711 -0.308629 +v -0.015357 -0.061951 -0.292895 +v -0.032911 -0.062616 -0.289159 +v -0.010985 -0.068903 -0.268344 +v -0.027699 -0.069191 -0.266850 +v -0.006121 -0.073070 -0.234175 +v -0.027897 -0.073227 -0.233083 +v -0.003074 -0.073505 -0.195833 +v -0.027337 -0.073808 -0.194085 +v -0.003005 -0.073631 -0.178827 +v -0.025988 -0.073797 -0.159282 +v 0.000190 -0.073712 -0.149768 +v 0.020896 -0.071343 -0.138861 +v 0.041083 -0.064367 -0.126756 +v 0.001622 -0.058896 -0.294810 +v 0.007126 -0.064991 -0.270682 +v 0.011079 -0.069601 -0.236075 +v 0.016534 -0.070115 -0.197317 +v 0.017331 -0.070944 -0.175606 +v 0.035818 -0.064729 -0.157951 +v 0.055245 -0.053450 -0.139368 +v 0.013200 -0.043858 -0.319266 +v 0.012151 -0.049457 -0.307685 +v 0.015601 -0.052598 -0.295856 +v 0.020908 -0.057921 -0.271812 +v 0.026395 -0.062365 -0.237513 +v 0.032224 -0.063063 -0.200921 +v 0.040015 -0.059821 -0.184365 +v 0.053521 -0.051356 -0.166617 +v 0.067639 -0.038127 -0.144914 +v 0.054382 -0.042551 -0.203113 +v 0.057541 -0.042646 -0.186220 +v 0.047065 -0.042677 -0.237736 +v 0.041192 -0.038142 -0.270257 +v 0.036378 -0.034254 -0.292275 +v 0.043917 0.000240 -0.301755 +v 0.046915 0.000240 -0.290175 +v 0.044489 -0.016648 -0.291638 +v 0.041476 -0.014588 -0.303257 +v 0.048696 -0.022649 -0.270488 +v 0.052415 0.000240 -0.270233 +v 0.056979 -0.022631 -0.238310 +v 0.061057 0.000240 -0.236365 +v 0.064279 -0.022948 -0.204108 +v 0.067920 0.000240 -0.204760 +v 0.071335 -0.020656 -0.171431 +v 0.076173 -0.018318 -0.147289 +v 0.074078 0.000240 -0.174084 +v 0.078473 0.000240 -0.147253 +v 0.030134 -0.030181 -0.315501 +v 0.032636 -0.033858 -0.303101 +v 0.037765 -0.013437 -0.316072 +v 0.039734 0.000240 -0.315749 +v 0.032655 -0.013531 -0.332137 +v 0.034559 0.000240 -0.332508 +v 0.026412 -0.026459 -0.331644 +v 0.016086 -0.037379 -0.331409 +v 0.002700 -0.042924 -0.335802 +v -0.007140 -0.044523 -0.341178 +v -0.014455 -0.044187 -0.351029 +v -0.027460 -0.045043 -0.352599 +v -0.043331 -0.045494 -0.349105 +v -0.032542 -0.041582 -0.359313 +v -0.021024 -0.040876 -0.361982 +v -0.048082 -0.041580 -0.354495 +v -0.047888 -0.039998 -0.358945 +v -0.038361 -0.041613 -0.363451 +v -0.034877 -0.040778 -0.373714 +v -0.038673 -0.041605 -0.385635 +v -0.037155 -0.040209 -0.389136 +v -0.053707 -0.041609 -0.389529 +v -0.054058 -0.040948 -0.392931 +v -0.063232 -0.041610 -0.382770 +v -0.066886 -0.040856 -0.383422 +v -0.065643 -0.041613 -0.371715 +v -0.069312 -0.040200 -0.370600 +v -0.058067 -0.041356 -0.349718 +v -0.061056 -0.041616 -0.363164 +v -0.049847 -0.045030 -0.334517 +v -0.054131 -0.035613 -0.340375 +v -0.049963 -0.037206 -0.327553 +v -0.051365 -0.029986 -0.335159 +v -0.055335 -0.029353 -0.342538 +v 0.034632 -0.033700 -0.239048 +v 0.041399 -0.026223 -0.237163 +v 0.044360 -0.019552 -0.235693 +v 0.035051 -0.023638 -0.238951 +v 0.045120 -0.013496 -0.235428 +v 0.034897 -0.015367 -0.238981 +v 0.043624 -0.007360 -0.236635 +v 0.034677 -0.007528 -0.239655 +v 0.000444 -0.006936 -0.257011 +v -0.000674 -0.006939 -0.262409 +v -0.009703 -0.007847 -0.257933 +v -0.004223 -0.007951 -0.249446 +v 0.008742 -0.007596 -0.245304 +v 0.010403 -0.006940 -0.256950 +v 0.020630 -0.007157 -0.243324 +v 0.023101 -0.006943 -0.255919 +v 0.032594 -0.006943 -0.253629 +v 0.004266 -0.006943 -0.271427 +v -0.007651 -0.007603 -0.272212 +v 0.024541 -0.006956 -0.268099 +v 0.032268 -0.006955 -0.263581 +v 0.038760 -0.006751 -0.252324 +v 0.038217 -0.006244 -0.262272 +v 0.048142 -0.005182 -0.233465 +v 0.043985 -0.004282 -0.249683 +v 0.050392 -0.001787 -0.231303 +v 0.045603 -0.001431 -0.248730 +v 0.050491 0.000240 -0.231208 +v 0.045972 0.000240 -0.248327 +v 0.029271 -0.006812 -0.279130 +v 0.041326 -0.003762 -0.261404 +v 0.042751 0.000240 -0.261042 +v 0.042420 -0.001440 -0.261150 +v 0.009891 -0.006953 -0.286800 +v 0.033104 -0.004972 -0.280658 +v 0.034889 0.000240 -0.281583 +v 0.034599 -0.002955 -0.281344 +v -0.002861 -0.008014 -0.289819 +v 0.017543 -0.004991 -0.292977 +v 0.018997 0.000240 -0.294719 +v 0.018717 -0.002344 -0.294471 +v 0.001628 0.000240 -0.300459 +v 0.001262 -0.003435 -0.299610 +v 0.000594 -0.005991 -0.297036 +v -0.000450 -0.012469 -0.300901 +v -0.002590 -0.014568 -0.297952 +v -0.043490 -0.034755 -0.321689 +v -0.042738 -0.024370 -0.321924 +v -0.048169 -0.023779 -0.330650 +v -0.036629 -0.022950 -0.330850 +v -0.039896 -0.022958 -0.336990 +v -0.029157 -0.024546 -0.315904 +v -0.028746 -0.022939 -0.325710 +v -0.020071 -0.024440 -0.315856 +v -0.018715 -0.022942 -0.324272 +v -0.010387 -0.023382 -0.311785 +v -0.006357 -0.022904 -0.319539 +v -0.004782 -0.020354 -0.305182 +v 0.001369 -0.021112 -0.314421 +v 0.003350 -0.008097 -0.311800 +v 0.005117 -0.020513 -0.324683 +v 0.003693 0.000240 -0.312979 +v -0.016745 -0.025126 -0.355892 +v -0.010195 -0.024164 -0.347146 +v -0.026003 -0.022945 -0.346549 +v -0.019882 -0.022952 -0.341102 +v -0.005554 -0.024270 -0.343262 +v -0.016023 -0.022960 -0.337601 +v 0.001077 -0.021955 -0.338941 +v -0.011432 -0.022624 -0.334321 +v 0.007000 -0.015899 -0.336256 +v -0.002072 -0.020939 -0.329712 +v 0.011340 -0.006730 -0.334839 +v 0.004024 -0.013538 -0.329592 +v 0.011787 0.000240 -0.334661 +v 0.006107 0.000240 -0.321265 +v 0.018573 -0.015873 -0.242592 +v 0.019490 -0.026834 -0.242373 +v 0.019803 -0.042025 -0.242311 +v 0.006094 -0.015801 -0.245537 +v -0.004297 -0.016024 -0.249813 +v -0.009923 -0.015575 -0.258314 +v -0.008152 -0.015459 -0.272368 +v -0.000774 -0.016959 -0.256411 +v 0.006405 -0.016963 -0.253574 +v 0.015910 -0.017144 -0.248710 +v -0.005749 -0.015462 -0.280903 +v 0.000368 -0.016978 -0.270383 +v 0.002047 -0.017115 -0.279571 +v -0.002090 -0.021615 -0.294671 +v 0.002388 -0.022251 -0.294000 +v -0.005141 -0.036812 -0.306113 +v 0.003386 -0.036503 -0.306826 +v -0.009903 -0.036153 -0.310996 +v -0.021056 -0.035565 -0.315927 +v -0.030105 -0.035420 -0.315775 +v 0.017500 -0.027389 -0.247323 +v 0.020416 -0.017002 -0.266871 +v 0.011821 -0.017409 -0.280944 +v 0.016989 -0.042129 -0.250159 +v 0.013460 -0.032576 -0.277487 +v 0.013648 -0.044296 -0.275110 +v 0.012827 -0.022166 -0.295171 +v 0.012947 -0.031646 -0.280896 +v 0.011257 -0.037219 -0.307049 +v 0.012696 -0.044332 -0.282175 +v -0.048571 -0.049356 -0.321794 +v -0.048924 -0.055509 -0.304440 +v -0.047244 -0.043379 -0.314313 +v -0.048608 -0.062409 -0.287580 +v -0.048659 -0.068219 -0.267107 +v -0.048761 -0.073123 -0.233050 +v -0.048312 -0.073720 -0.194406 +v -0.047811 -0.073801 -0.158103 +v -0.048552 -0.073695 -0.126465 +v -0.048407 -0.073711 -0.100305 +v -0.047499 -0.073400 -0.073757 +v -0.050049 -0.064496 -0.089819 +v -0.050038 -0.057629 -0.093509 +v -0.049897 -0.058421 -0.108801 +v -0.049311 -0.062938 -0.079322 +v -0.050034 -0.052461 -0.085066 +v -0.049976 -0.029658 -0.067550 +v -0.049595 -0.045566 -0.074176 +v -0.045155 -0.037089 -0.061616 +v -0.049982 -0.006538 -0.063003 +v -0.023718 -0.006706 -0.064428 +v -0.024097 0.000240 -0.064409 +v -0.049960 0.000240 -0.062979 +v -0.049828 -0.016840 -0.064320 +v -0.022935 -0.016944 -0.066259 +v -0.020474 -0.028794 -0.069225 +v -0.013228 -0.036522 -0.063079 +v 0.009193 -0.035413 -0.069586 +v 0.008851 -0.025436 -0.072742 +v 0.008917 -0.014195 -0.069799 +v 0.008406 -0.004716 -0.068566 +v 0.008138 0.000240 -0.068260 +v 0.082972 0.000240 -0.117475 +v 0.080370 -0.018373 -0.116812 +v 0.072017 -0.038169 -0.115979 +v 0.060422 -0.052539 -0.111950 +v 0.046994 -0.062936 -0.103241 +v 0.034707 -0.069218 -0.092242 +v 0.024514 -0.072488 -0.077073 +v 0.019402 -0.073403 -0.060890 +v 0.016311 -0.073585 -0.046332 +v 0.013789 -0.073506 -0.032151 +v 0.016902 -0.069852 -0.040795 +v 0.015622 -0.068071 -0.033490 +v 0.006506 -0.073389 -0.020886 +v -0.005275 -0.073239 -0.017005 +v -0.015787 -0.073409 -0.020928 +v -0.022850 -0.073631 -0.029336 +v -0.040562 -0.060267 -0.051358 +v -0.030039 -0.073651 -0.039049 +v -0.038600 -0.073708 -0.051648 +v -0.035090 -0.069759 -0.042554 +v -0.037081 -0.071485 -0.045559 +v 0.017218 -0.066303 -0.042835 +v 0.016337 -0.065483 -0.034782 +v 0.010847 -0.065982 -0.022453 +v -0.002254 -0.066252 -0.015532 +v -0.016708 -0.064963 -0.018987 +v -0.022435 -0.065429 -0.024706 +v -0.027020 -0.065922 -0.030910 +v -0.037072 -0.064012 -0.045548 +v -0.032229 -0.066062 -0.037782 +v -0.038235 -0.038146 -0.047819 +v -0.031475 -0.049721 -0.036224 +v -0.024448 -0.057732 -0.020768 +v -0.014467 -0.058260 -0.013560 +v 0.002728 -0.056623 -0.014942 +v 0.003581 -0.049861 -0.014707 +v -0.011283 -0.052481 -0.010453 +v -0.023109 -0.053931 -0.015299 +v -0.018768 -0.049576 0.001933 +v -0.025460 -0.045339 -0.022495 +v -0.020290 -0.043562 -0.000815 +v -0.016685 -0.049009 0.009712 +v -0.017023 -0.043877 0.010329 +v 0.001109 -0.048791 0.019433 +v -0.008428 -0.048191 0.017761 +v -0.008907 -0.043344 0.017732 +v 0.012620 -0.048870 0.014818 +v 0.013580 -0.042838 0.014564 +v 0.001612 -0.042771 0.019801 +v 0.019159 -0.049345 -0.001200 +v 0.016911 -0.049570 0.007878 +v 0.017372 -0.052486 -0.014247 +v 0.016488 -0.057998 -0.023305 +v 0.018947 -0.062694 -0.050702 +v 0.016969 -0.057785 -0.040873 +v 0.016312 -0.050303 -0.030172 +v 0.021427 -0.064904 -0.062003 +v -0.011592 -0.036452 -0.051761 +v 0.011643 -0.036563 -0.053404 +v 0.012433 -0.048647 -0.058073 +v 0.010008 -0.048678 -0.076199 +v 0.026560 -0.064937 -0.077276 +v 0.014352 -0.056124 -0.060519 +v 0.013909 -0.058875 -0.080333 +v 0.035257 -0.063070 -0.090741 +v 0.014671 -0.061496 -0.100203 +v 0.044748 -0.057766 -0.100437 +v 0.020061 -0.063318 -0.114016 +v 0.057666 -0.047667 -0.108832 +v 0.067225 -0.034813 -0.112889 +v 0.075454 -0.016940 -0.114897 +v 0.077249 0.000240 -0.115310 +v 0.051605 -0.048044 -0.122165 +v 0.042554 -0.055058 -0.117378 +v 0.031463 -0.059968 -0.126207 +v 0.062896 -0.034633 -0.127302 +v 0.070632 -0.017264 -0.130163 +v 0.072797 0.000240 -0.132994 +v 0.042569 -0.053796 -0.132095 +v 0.057088 -0.038528 -0.149044 +v 0.033899 -0.057438 -0.150673 +v 0.034633 -0.057780 -0.139827 +v 0.066844 -0.018790 -0.152124 +v 0.068809 0.000240 -0.157413 +v 0.044571 -0.030164 -0.235268 +v 0.049648 -0.021031 -0.231929 +v 0.052727 -0.012598 -0.228476 +v 0.054525 -0.006615 -0.225480 +v 0.055918 0.000240 -0.222577 +v 0.054433 -0.015646 -0.221489 +v 0.056237 -0.009547 -0.218595 +v 0.052068 -0.021934 -0.223415 +v 0.060447 -0.018175 -0.188680 +v 0.051707 -0.037163 -0.185117 +v 0.062517 0.000240 -0.191120 +v 0.058990 0.000240 -0.208651 +v 0.056640 -0.017055 -0.209527 +v 0.048825 -0.031272 -0.218611 +v 0.033360 -0.044602 -0.238111 +v 0.035164 -0.053426 -0.183740 +v 0.035233 -0.049345 -0.213514 +v 0.016915 -0.057905 -0.239959 +v -0.049987 0.000240 -0.074095 +v -0.050002 -0.004785 -0.075510 +v 0.008750 -0.005298 -0.082837 +v 0.008311 0.000240 -0.082899 +v -0.004001 -0.006578 -0.084437 +v -0.049270 -0.007267 -0.082138 +v -0.050032 -0.019995 -0.078169 +v 0.008411 -0.021511 -0.086118 +v -0.049928 -0.024644 -0.079050 +v 0.007618 -0.036799 -0.093094 +v -0.049850 -0.035807 -0.085169 +v -0.049991 -0.043138 -0.090420 +v 0.007022 -0.058579 -0.119752 +v -0.049875 -0.065331 -0.127254 +v 0.018481 -0.063690 -0.135138 +v -0.049562 -0.066632 -0.157743 +v 0.018132 -0.063279 -0.152513 +v -0.049610 -0.066708 -0.194135 +v 0.019649 -0.061299 -0.187044 +v -0.049663 -0.066334 -0.232044 +v 0.018748 -0.059753 -0.214026 +v 0.013345 -0.057597 -0.251320 +v -0.049451 -0.061512 -0.264309 +v 0.008428 -0.054317 -0.274922 +v -0.049834 -0.056362 -0.284994 +v -0.049674 -0.049619 -0.301524 +v -0.034328 -0.044472 -0.311729 +v -0.025952 -0.045515 -0.310719 +v -0.014959 -0.047451 -0.307356 +v -0.008392 -0.049463 -0.301149 +v -0.004395 -0.050184 -0.298388 +v 0.001363 -0.050008 -0.295027 +v 0.004997 -0.052489 -0.284512 +v -0.006459 -0.051547 -0.295982 +v -0.031675 -0.049656 -0.301023 +v -0.010384 -0.051098 -0.298594 +v -0.035197 -0.022943 -0.362323 +v -0.046059 -0.022945 -0.355836 +v -0.021383 -0.025135 -0.363879 +v -0.035746 -0.022937 -0.375410 +v -0.039232 -0.023577 -0.366437 +v -0.037749 -0.025366 -0.389772 +v -0.041708 -0.022937 -0.385697 +v -0.058841 -0.024695 -0.391829 +v -0.056712 -0.022936 -0.387430 +v -0.067070 -0.024612 -0.384014 +v -0.062647 -0.022936 -0.381225 +v -0.069692 -0.024562 -0.371977 +v -0.063772 -0.022940 -0.371415 +v -0.048883 -0.024435 -0.360798 +v -0.058924 -0.023782 -0.349888 +v -0.056390 -0.022943 -0.361987 +v -0.049812 -0.016269 -0.083017 +v -0.048832 -0.007455 -0.100897 +v -0.042507 -0.007424 -0.109758 +v -0.041899 -0.016401 -0.110110 +v -0.047770 -0.016566 -0.103410 +v -0.022263 -0.007266 -0.104138 +v -0.032304 -0.007228 -0.111353 +v -0.030785 -0.015854 -0.111746 +v -0.007517 -0.018248 -0.086631 +v -0.023064 -0.016249 -0.105888 +v -0.016255 -0.037782 0.011158 +v -0.020063 -0.037725 -0.000854 +v 0.002900 -0.038473 0.019685 +v -0.007368 -0.037836 0.018215 +v 0.017434 -0.038086 -0.020092 +v 0.019784 -0.038029 -0.002576 +v -0.025830 -0.037387 -0.024984 +v -0.004320 -0.036448 -0.019682 +v 0.002772 -0.036438 -0.010565 +v 0.010044 -0.036471 -0.004601 +v -0.006552 -0.036483 -0.008660 +v -0.010807 -0.036476 -0.000106 +v -0.006775 -0.036473 0.008465 +v 0.013947 -0.037687 0.013991 +v 0.002431 -0.036468 0.010722 +v 0.009885 -0.036471 0.004853 +v 0.002772 -0.030533 -0.010565 +v 0.010044 -0.030566 -0.004601 +v -0.006552 -0.030578 -0.008660 +v -0.010807 -0.030571 -0.000106 +v -0.006775 -0.030568 0.008465 +v 0.009885 -0.030566 0.004853 +v 0.002431 -0.030563 0.010722 +v 0.001288 -0.030550 -0.004592 +v 0.004455 -0.030565 -0.001995 +v -0.002772 -0.030570 -0.003762 +v -0.004625 -0.030567 -0.000038 +v -0.002869 -0.030566 0.003695 +v 0.004385 -0.030565 0.002122 +v 0.001139 -0.030563 0.004678 +v 0.001288 -0.018873 -0.004592 +v 0.004455 -0.018888 -0.001995 +v -0.002772 -0.018893 -0.003762 +v -0.004625 -0.018890 -0.000038 +v -0.002869 -0.018889 0.003695 +v 0.004385 -0.018888 0.002122 +v 0.001139 -0.018887 0.004678 +v -0.036297 0.047356 -0.334804 +v -0.024778 0.047975 -0.332917 +v -0.026482 0.046463 -0.344329 +v -0.033785 0.046489 -0.343062 +v -0.013129 0.047619 -0.332893 +v -0.018607 0.043776 -0.343112 +v -0.036179 0.050704 -0.320841 +v -0.019521 0.051266 -0.320706 +v -0.002343 0.047934 -0.324966 +v -0.005394 0.074224 -0.035325 +v -0.012557 0.074211 -0.030529 +v -0.007498 0.073942 -0.026447 +v -0.001038 0.074246 -0.028646 +v 0.004655 0.074259 -0.036666 +v -0.006144 0.074227 -0.040857 +v -0.017100 0.074216 -0.037081 +v 0.006194 0.074246 -0.047888 +v -0.006520 0.074222 -0.047133 +v -0.022975 0.074261 -0.047387 +v -0.009151 0.074214 -0.063017 +v -0.028292 0.074249 -0.060834 +v -0.012724 0.074229 -0.081529 +v -0.032368 0.074298 -0.078053 +v 0.007401 0.074228 -0.063457 +v -0.015746 0.074215 -0.102862 +v -0.032971 0.074311 -0.100557 +v 0.011751 0.074065 -0.084866 +v 0.003018 0.074234 -0.104400 +v 0.025417 0.071749 -0.108499 +v 0.009828 0.073856 -0.119367 +v -0.012727 0.074214 -0.126503 +v -0.031815 0.074304 -0.125250 +v -0.035946 0.057206 -0.304456 +v -0.017438 0.057152 -0.305981 +v -0.000678 0.054191 -0.308629 +v -0.032911 0.063097 -0.289159 +v -0.015357 0.062431 -0.292895 +v -0.010985 0.069383 -0.268344 +v -0.027699 0.069671 -0.266850 +v -0.006121 0.073551 -0.234175 +v -0.027897 0.073708 -0.233083 +v -0.003074 0.073985 -0.195833 +v -0.027337 0.074289 -0.194085 +v -0.003005 0.074111 -0.178827 +v -0.025988 0.074277 -0.159282 +v 0.000190 0.074192 -0.149768 +v 0.020896 0.071823 -0.138862 +v 0.041083 0.064847 -0.126756 +v 0.001622 0.059376 -0.294810 +v 0.007126 0.065472 -0.270682 +v 0.011079 0.070082 -0.236075 +v 0.016534 0.070595 -0.197317 +v 0.017331 0.071425 -0.175606 +v 0.035818 0.065209 -0.157951 +v 0.055245 0.053930 -0.139368 +v 0.012151 0.049937 -0.307685 +v 0.013200 0.044338 -0.319266 +v 0.015601 0.053078 -0.295856 +v 0.020908 0.058401 -0.271812 +v 0.026395 0.062846 -0.237513 +v 0.032224 0.063544 -0.200921 +v 0.040015 0.060302 -0.184365 +v 0.053521 0.051836 -0.166617 +v 0.067639 0.038607 -0.144914 +v 0.057541 0.043127 -0.186221 +v 0.054382 0.043032 -0.203113 +v 0.047065 0.043157 -0.237736 +v 0.041192 0.038622 -0.270257 +v 0.036378 0.034735 -0.292275 +v 0.044489 0.017128 -0.291638 +v 0.041476 0.015068 -0.303257 +v 0.048696 0.023130 -0.270488 +v 0.056979 0.023112 -0.238310 +v 0.064279 0.023428 -0.204108 +v 0.071335 0.021136 -0.171431 +v 0.076173 0.018798 -0.147289 +v 0.032636 0.034338 -0.303101 +v 0.030134 0.030661 -0.315501 +v 0.037765 0.013917 -0.316072 +v 0.032655 0.014011 -0.332137 +v 0.026412 0.026939 -0.331644 +v 0.016086 0.037859 -0.331409 +v 0.002700 0.043404 -0.335802 +v -0.007140 0.045003 -0.341178 +v -0.014455 0.044668 -0.351029 +v -0.027460 0.045523 -0.352599 +v -0.043331 0.045975 -0.349104 +v -0.032542 0.042063 -0.359313 +v -0.021024 0.041356 -0.361982 +v -0.048082 0.042060 -0.354495 +v -0.047888 0.040478 -0.358945 +v -0.038361 0.042094 -0.363451 +v -0.034877 0.041259 -0.373714 +v -0.037155 0.040689 -0.389136 +v -0.038673 0.042085 -0.385635 +v -0.054058 0.041429 -0.392931 +v -0.053707 0.042090 -0.389529 +v -0.066886 0.041337 -0.383422 +v -0.063232 0.042090 -0.382770 +v -0.069312 0.040680 -0.370600 +v -0.065643 0.042093 -0.371714 +v -0.061056 0.042096 -0.363164 +v -0.058067 0.041837 -0.349718 +v -0.049847 0.045510 -0.334517 +v -0.051365 0.030466 -0.335159 +v -0.049963 0.037686 -0.327553 +v -0.054131 0.036093 -0.340375 +v -0.055335 0.029834 -0.342538 +v 0.044360 0.020032 -0.235693 +v 0.041399 0.026704 -0.237163 +v 0.034632 0.034180 -0.239048 +v 0.035051 0.024118 -0.238951 +v 0.045120 0.013977 -0.235428 +v 0.034897 0.015847 -0.238981 +v 0.034677 0.008009 -0.239655 +v 0.043624 0.007840 -0.236635 +v -0.009703 0.008328 -0.257933 +v -0.000674 0.007420 -0.262409 +v 0.000444 0.007417 -0.257011 +v -0.004223 0.008431 -0.249446 +v 0.010403 0.007421 -0.256950 +v 0.008742 0.008077 -0.245304 +v 0.023101 0.007423 -0.255919 +v 0.020630 0.007637 -0.243324 +v 0.032594 0.007423 -0.253629 +v 0.004266 0.007423 -0.271427 +v -0.007651 0.008083 -0.272212 +v 0.024541 0.007436 -0.268099 +v 0.032268 0.007435 -0.263581 +v 0.038760 0.007231 -0.252324 +v 0.038217 0.006725 -0.262272 +v 0.043985 0.004763 -0.249683 +v 0.048142 0.005663 -0.233465 +v 0.045603 0.001911 -0.248730 +v 0.050392 0.002267 -0.231303 +v 0.029271 0.007292 -0.279130 +v 0.041326 0.004242 -0.261404 +v 0.042420 0.001920 -0.261150 +v 0.009891 0.007433 -0.286800 +v 0.033104 0.005452 -0.280658 +v 0.034599 0.003435 -0.281344 +v -0.002861 0.008494 -0.289819 +v 0.017543 0.005471 -0.292977 +v 0.018717 0.002824 -0.294471 +v 0.001262 0.003916 -0.299610 +v 0.000594 0.006471 -0.297036 +v -0.000450 0.012950 -0.300901 +v -0.002590 0.015049 -0.297952 +v -0.048169 0.024260 -0.330649 +v -0.042738 0.024851 -0.321924 +v -0.043490 0.035236 -0.321689 +v -0.039896 0.023438 -0.336990 +v -0.036629 0.023431 -0.330850 +v -0.028746 0.023420 -0.325710 +v -0.029157 0.025027 -0.315904 +v -0.018715 0.023422 -0.324272 +v -0.020071 0.024921 -0.315856 +v -0.006357 0.023384 -0.319539 +v -0.010386 0.023862 -0.311785 +v 0.001369 0.021592 -0.314421 +v -0.004782 0.020835 -0.305182 +v 0.003350 0.008578 -0.311800 +v 0.005117 0.020993 -0.324683 +v -0.010195 0.024644 -0.347146 +v -0.016744 0.025607 -0.355892 +v -0.019882 0.023433 -0.341102 +v -0.026003 0.023426 -0.346549 +v -0.005554 0.024751 -0.343262 +v -0.016023 0.023440 -0.337601 +v 0.001077 0.022436 -0.338941 +v -0.011432 0.023105 -0.334320 +v 0.007000 0.016379 -0.336256 +v -0.002072 0.021420 -0.329712 +v 0.011340 0.007210 -0.334839 +v 0.004024 0.014019 -0.329592 +v 0.018573 0.016354 -0.242592 +v 0.019490 0.027314 -0.242373 +v 0.019803 0.042505 -0.242311 +v 0.006094 0.016281 -0.245537 +v -0.004297 0.016504 -0.249813 +v -0.009923 0.016055 -0.258313 +v -0.008152 0.015939 -0.272368 +v -0.000774 0.017440 -0.256411 +v 0.006405 0.017444 -0.253574 +v 0.015910 0.017624 -0.248710 +v -0.005749 0.015942 -0.280903 +v 0.000368 0.017459 -0.270382 +v 0.002047 0.017595 -0.279571 +v -0.002090 0.022096 -0.294670 +v 0.002388 0.022732 -0.294000 +v 0.003386 0.036983 -0.306826 +v -0.005141 0.037293 -0.306113 +v -0.009903 0.036633 -0.310996 +v -0.021056 0.036046 -0.315927 +v -0.030105 0.035900 -0.315775 +v 0.017500 0.027869 -0.247323 +v 0.020416 0.017482 -0.266871 +v 0.011821 0.017889 -0.280944 +v 0.016989 0.042609 -0.250159 +v 0.013460 0.033057 -0.277487 +v 0.013648 0.044777 -0.275110 +v 0.012827 0.022647 -0.295171 +v 0.012947 0.032126 -0.280896 +v 0.011257 0.037699 -0.307049 +v 0.012696 0.044813 -0.282175 +v -0.048571 0.049837 -0.321794 +v -0.048924 0.055989 -0.304440 +v -0.047244 0.043859 -0.314313 +v -0.048608 0.062889 -0.287579 +v -0.048659 0.068700 -0.267107 +v -0.048761 0.073603 -0.233050 +v -0.048312 0.074201 -0.194406 +v -0.047811 0.074281 -0.158103 +v -0.048552 0.074176 -0.126465 +v -0.048407 0.074191 -0.100305 +v -0.047499 0.073880 -0.073757 +v -0.049897 0.058901 -0.108801 +v -0.050038 0.058110 -0.093509 +v -0.050049 0.064977 -0.089819 +v -0.049311 0.063418 -0.079322 +v -0.050034 0.052941 -0.085066 +v -0.049595 0.046046 -0.074176 +v -0.049976 0.030138 -0.067550 +v -0.045155 0.037570 -0.061616 +v -0.023718 0.007187 -0.064428 +v -0.049982 0.007019 -0.063003 +v -0.022935 0.017425 -0.066259 +v -0.049828 0.017320 -0.064320 +v -0.020474 0.029275 -0.069225 +v -0.013228 0.037003 -0.063079 +v 0.008851 0.025917 -0.072742 +v 0.009193 0.035894 -0.069586 +v 0.008917 0.014675 -0.069799 +v 0.008406 0.005197 -0.068566 +v 0.080370 0.018853 -0.116812 +v 0.072017 0.038650 -0.115979 +v 0.060422 0.053019 -0.111950 +v 0.046994 0.063416 -0.103241 +v 0.034707 0.069699 -0.092242 +v 0.024514 0.072968 -0.077073 +v 0.019402 0.073884 -0.060890 +v 0.016312 0.074065 -0.046332 +v 0.013789 0.073987 -0.032151 +v 0.015622 0.068552 -0.033490 +v 0.016902 0.070332 -0.040795 +v 0.006506 0.073870 -0.020886 +v -0.005275 0.073720 -0.017005 +v -0.015787 0.073889 -0.020928 +v -0.022850 0.074112 -0.029336 +v -0.040562 0.060748 -0.051358 +v -0.030039 0.074131 -0.039049 +v -0.038600 0.074189 -0.051648 +v -0.037081 0.071966 -0.045559 +v -0.035090 0.070239 -0.042554 +v 0.016337 0.065963 -0.034782 +v 0.017218 0.066783 -0.042835 +v 0.010847 0.066463 -0.022453 +v -0.002254 0.066732 -0.015532 +v -0.016708 0.065444 -0.018987 +v -0.022435 0.065910 -0.024706 +v -0.027019 0.066402 -0.030910 +v -0.037072 0.064493 -0.045548 +v -0.032229 0.066542 -0.037781 +v -0.038235 0.038626 -0.047819 +v -0.031475 0.050202 -0.036224 +v -0.024448 0.058212 -0.020768 +v -0.014467 0.058741 -0.013560 +v 0.002728 0.057104 -0.014942 +v -0.011283 0.052962 -0.010453 +v 0.003581 0.050341 -0.014707 +v -0.023109 0.054412 -0.015299 +v -0.018768 0.050057 0.001933 +v -0.025460 0.045819 -0.022495 +v -0.020290 0.044042 -0.000815 +v -0.017023 0.044357 0.010329 +v -0.016685 0.049490 0.009712 +v 0.001109 0.049272 0.019433 +v -0.008427 0.048672 0.017761 +v -0.008907 0.043825 0.017732 +v 0.001612 0.043251 0.019801 +v 0.013580 0.043318 0.014564 +v 0.012620 0.049351 0.014818 +v 0.019159 0.049826 -0.001200 +v 0.016911 0.050051 0.007878 +v 0.017372 0.052966 -0.014247 +v 0.016488 0.058479 -0.023305 +v 0.016969 0.058265 -0.040873 +v 0.018947 0.063175 -0.050702 +v 0.016312 0.050784 -0.030172 +v 0.021427 0.065385 -0.062003 +v -0.011592 0.036933 -0.051761 +v 0.011643 0.037043 -0.053404 +v 0.010008 0.049159 -0.076199 +v 0.012433 0.049128 -0.058073 +v 0.026560 0.065417 -0.077276 +v 0.014352 0.056605 -0.060519 +v 0.013909 0.059355 -0.080333 +v 0.035257 0.063551 -0.090741 +v 0.014671 0.061976 -0.100203 +v 0.044748 0.058247 -0.100437 +v 0.020061 0.063798 -0.114016 +v 0.057666 0.048148 -0.108833 +v 0.067225 0.035293 -0.112889 +v 0.075454 0.017420 -0.114897 +v 0.051605 0.048524 -0.122165 +v 0.042554 0.055538 -0.117378 +v 0.031463 0.060449 -0.126207 +v 0.062896 0.035113 -0.127302 +v 0.070631 0.017745 -0.130163 +v 0.042569 0.054277 -0.132095 +v 0.033899 0.057918 -0.150673 +v 0.057088 0.039008 -0.149044 +v 0.034633 0.058261 -0.139827 +v 0.066844 0.019270 -0.152124 +v 0.049648 0.021511 -0.231929 +v 0.044571 0.030644 -0.235268 +v 0.052727 0.013079 -0.228476 +v 0.054525 0.007096 -0.225480 +v 0.056237 0.010027 -0.218595 +v 0.054433 0.016126 -0.221489 +v 0.052068 0.022414 -0.223415 +v 0.060447 0.018655 -0.188680 +v 0.051707 0.037643 -0.185117 +v 0.056640 0.017535 -0.209527 +v 0.048825 0.031752 -0.218611 +v 0.033360 0.045082 -0.238111 +v 0.035164 0.053906 -0.183740 +v 0.035233 0.049825 -0.213514 +v 0.016915 0.058386 -0.239959 +v -0.050002 0.005266 -0.075510 +v 0.008750 0.005778 -0.082837 +v -0.004001 0.007059 -0.084437 +v -0.049270 0.007748 -0.082138 +v -0.050032 0.020476 -0.078169 +v 0.008411 0.021992 -0.086118 +v -0.049928 0.025124 -0.079050 +v 0.007618 0.037280 -0.093094 +v -0.049850 0.036288 -0.085169 +v -0.049991 0.043619 -0.090420 +v 0.007022 0.059059 -0.119752 +v -0.049875 0.065812 -0.127255 +v 0.018481 0.064170 -0.135138 +v -0.049562 0.067112 -0.157743 +v 0.018132 0.063760 -0.152513 +v -0.049610 0.067189 -0.194135 +v 0.019649 0.061780 -0.187044 +v -0.049663 0.066815 -0.232044 +v 0.018748 0.060234 -0.214026 +v 0.013345 0.058078 -0.251320 +v -0.049451 0.061993 -0.264309 +v 0.008428 0.054798 -0.274922 +v -0.049834 0.056842 -0.284994 +v -0.049674 0.050099 -0.301524 +v -0.034328 0.044953 -0.311729 +v -0.025952 0.045995 -0.310719 +v -0.014959 0.047932 -0.307356 +v -0.008392 0.049944 -0.301149 +v -0.004395 0.050665 -0.298388 +v 0.001363 0.050488 -0.295027 +v 0.004997 0.052970 -0.284512 +v -0.006459 0.052027 -0.295982 +v -0.010384 0.051578 -0.298594 +v -0.031675 0.050136 -0.301023 +v -0.035197 0.023423 -0.362323 +v -0.046059 0.023426 -0.355836 +v -0.021383 0.025615 -0.363879 +v -0.035746 0.023417 -0.375410 +v -0.039232 0.024058 -0.366437 +v -0.037749 0.025847 -0.389772 +v -0.041708 0.023418 -0.385697 +v -0.058841 0.025176 -0.391829 +v -0.056711 0.023416 -0.387430 +v -0.067070 0.025093 -0.384014 +v -0.062647 0.023416 -0.381225 +v -0.069692 0.025043 -0.371977 +v -0.063772 0.023420 -0.371415 +v -0.048883 0.024915 -0.360798 +v -0.058924 0.024263 -0.349888 +v -0.056390 0.023423 -0.361987 +v -0.049812 0.016750 -0.083017 +v -0.041899 0.016882 -0.110110 +v -0.042507 0.007904 -0.109758 +v -0.048832 0.007935 -0.100897 +v -0.047770 0.017046 -0.103410 +v -0.032304 0.007709 -0.111353 +v -0.022263 0.007747 -0.104138 +v -0.030785 0.016335 -0.111746 +v -0.007517 0.018729 -0.086631 +v -0.023064 0.016730 -0.105888 +v -0.016255 0.038262 0.011158 +v -0.020063 0.038205 -0.000854 +v -0.007368 0.038317 0.018215 +v 0.002900 0.038954 0.019684 +v 0.017434 0.038567 -0.020092 +v 0.019784 0.038509 -0.002576 +v -0.025830 0.037867 -0.024984 +v 0.002772 0.036918 -0.010565 +v -0.004320 0.036928 -0.019682 +v 0.010044 0.036952 -0.004601 +v -0.006552 0.036964 -0.008660 +v -0.010807 0.036956 -0.000106 +v -0.006775 0.036954 0.008465 +v 0.002431 0.036949 0.010722 +v 0.013947 0.038168 0.013991 +v 0.009885 0.036952 0.004852 +v 0.010044 0.031046 -0.004601 +v 0.002772 0.031013 -0.010565 +v -0.006552 0.031059 -0.008660 +v -0.010807 0.031051 -0.000106 +v -0.006775 0.031049 0.008465 +v 0.002431 0.031044 0.010722 +v 0.009885 0.031047 0.004852 +v 0.004455 0.031045 -0.001995 +v 0.001288 0.031030 -0.004592 +v -0.002772 0.031050 -0.003762 +v -0.004625 0.031047 -0.000038 +v -0.002869 0.031046 0.003695 +v 0.001139 0.031044 0.004678 +v 0.004385 0.031045 0.002122 +v 0.004455 0.019368 -0.001995 +v 0.001288 0.019354 -0.004592 +v -0.002772 0.019374 -0.003762 +v -0.004625 0.019371 -0.000038 +v -0.002869 0.019369 0.003695 +v 0.001139 0.019367 0.004678 +v 0.004385 0.019369 0.002122 +# 1246 vertices, 0 vertices normals + +f 2 3 1 +f 1 3 4 +f 6 2 1 +f 2 6 5 +f 8 5 6 +f 5 8 7 +f 10 7 8 +f 7 10 9 +f 11 12 13 +f 11 13 14 +f 12 9 10 +f 9 12 11 +f 17 16 11 +f 16 17 15 +f 11 18 9 +f 18 11 16 +f 19 16 15 +f 16 19 18 +f 20 9 18 +f 9 20 7 +f 21 18 19 +f 18 21 20 +f 20 22 7 +f 7 22 5 +f 23 24 25 +f 23 25 26 +f 2 28 3 +f 28 2 27 +f 27 30 28 +f 30 27 29 +f 2 5 27 +f 5 22 27 +f 23 30 29 +f 30 23 26 +f 31 23 32 +f 23 31 24 +f 32 29 33 +f 29 32 23 +f 15 32 19 +f 32 15 31 +f 21 32 33 +f 32 21 19 +f 21 33 22 +f 21 22 20 +f 33 29 22 +f 22 29 27 +f 15 34 31 +f 34 15 17 +f 31 35 24 +f 35 31 34 +f 24 36 25 +f 36 24 35 +f 38 37 35 +f 36 35 37 +f 35 34 38 +f 34 39 38 +f 34 17 39 +f 17 40 39 +f 17 11 40 +f 40 11 14 +f 41 14 13 +f 14 41 40 +f 42 13 12 +f 13 42 41 +f 41 44 43 +f 44 41 42 +f 40 43 45 +f 43 40 41 +f 39 45 46 +f 45 39 40 +f 38 46 47 +f 46 38 39 +f 47 37 38 +f 37 47 48 +f 48 50 49 +f 50 48 47 +f 47 51 50 +f 51 47 46 +f 46 52 51 +f 52 46 45 +f 45 53 52 +f 53 45 43 +f 43 44 53 +f 44 54 53 +f 55 53 54 +f 54 56 55 +f 52 53 57 +f 53 55 57 +f 51 52 58 +f 52 57 58 +f 50 58 59 +f 58 50 51 +f 49 50 60 +f 50 59 60 +f 60 59 61 +f 59 62 61 +f 59 58 62 +f 58 63 62 +f 58 57 63 +f 57 64 63 +f 64 66 63 +f 66 64 65 +f 57 67 64 +f 67 57 55 +f 68 55 56 +f 55 68 67 +f 67 68 69 +f 68 70 69 +f 71 64 67 +f 67 69 71 +f 65 71 72 +f 71 65 64 +f 73 71 69 +f 71 73 72 +f 74 69 70 +f 69 74 73 +f 73 76 75 +f 76 73 74 +f 78 80 77 +f 80 78 79 +f 77 82 78 +f 82 77 81 +f 82 75 76 +f 75 82 81 +f 84 77 83 +f 77 84 81 +f 85 75 81 +f 75 85 73 +f 86 81 84 +f 81 86 85 +f 85 72 73 +f 72 85 87 +f 87 86 88 +f 86 87 85 +f 87 65 72 +f 65 87 89 +f 90 89 88 +f 88 89 87 +f 89 66 65 +f 66 89 91 +f 62 66 91 +f 66 62 63 +f 89 90 91 +f 90 92 91 +f 61 62 93 +f 62 91 93 +f 93 92 94 +f 93 91 92 +f 95 80 79 +f 79 96 95 +f 83 77 80 +f 83 80 97 +f 97 95 98 +f 95 97 80 +f 99 4 3 +f 3 100 99 +f 100 102 99 +f 102 100 101 +f 101 104 102 +f 104 101 103 +f 103 106 104 +f 106 103 105 +f 110 107 109 +f 109 107 108 +f 105 110 106 +f 110 105 107 +f 112 107 113 +f 113 111 112 +f 113 107 114 +f 107 105 114 +f 113 115 111 +f 115 113 114 +f 116 105 103 +f 105 116 114 +f 114 117 115 +f 117 114 116 +f 103 101 118 +f 103 118 116 +f 26 25 119 +f 25 120 119 +f 100 28 121 +f 28 100 3 +f 30 121 28 +f 121 30 122 +f 100 121 101 +f 101 121 118 +f 30 119 122 +f 119 30 26 +f 123 119 120 +f 119 123 124 +f 124 122 119 +f 122 124 125 +f 111 124 123 +f 124 111 115 +f 124 117 125 +f 117 124 115 +f 118 117 116 +f 118 125 117 +f 122 118 121 +f 118 122 125 +f 111 126 112 +f 126 111 123 +f 123 127 126 +f 127 123 120 +f 36 120 25 +f 120 36 127 +f 37 127 36 +f 127 37 128 +f 128 126 127 +f 126 128 129 +f 129 112 126 +f 112 129 130 +f 130 107 112 +f 107 130 108 +f 108 131 109 +f 131 108 130 +f 109 132 110 +f 132 109 131 +f 131 134 132 +f 134 131 133 +f 130 133 131 +f 133 130 135 +f 129 135 130 +f 135 129 136 +f 128 136 129 +f 136 128 137 +f 37 137 128 +f 137 37 48 +f 48 138 137 +f 138 48 49 +f 137 139 136 +f 139 137 138 +f 136 140 135 +f 140 136 139 +f 135 141 133 +f 141 135 140 +f 133 141 134 +f 134 141 142 +f 141 143 142 +f 142 143 144 +f 140 145 141 +f 141 145 143 +f 146 140 139 +f 140 146 145 +f 138 146 139 +f 146 138 147 +f 60 138 49 +f 138 60 147 +f 60 61 147 +f 147 61 148 +f 148 146 147 +f 146 148 149 +f 146 149 145 +f 145 149 150 +f 150 152 151 +f 152 150 149 +f 145 153 143 +f 153 145 150 +f 143 154 144 +f 154 143 153 +f 153 155 154 +f 154 155 156 +f 150 157 153 +f 153 157 155 +f 157 151 158 +f 151 157 150 +f 157 159 155 +f 159 157 158 +f 155 160 156 +f 160 155 159 +f 159 162 160 +f 162 159 161 +f 166 164 165 +f 164 166 163 +f 168 163 166 +f 163 168 167 +f 161 168 162 +f 168 161 167 +f 169 163 167 +f 163 169 170 +f 171 167 161 +f 161 159 171 +f 172 167 171 +f 167 172 169 +f 171 158 173 +f 158 171 159 +f 173 174 172 +f 172 171 173 +f 173 151 175 +f 151 173 158 +f 176 174 175 +f 174 173 175 +f 175 152 177 +f 152 175 151 +f 148 152 149 +f 152 148 177 +f 175 177 176 +f 176 177 178 +f 93 148 61 +f 148 93 177 +f 177 93 178 +f 178 93 94 +f 164 179 165 +f 165 179 180 +f 170 164 163 +f 164 170 181 +f 181 179 164 +f 179 181 182 +f 183 184 185 +f 185 186 183 +f 186 188 183 +f 188 186 187 +f 187 190 188 +f 190 187 189 +f 189 192 190 +f 192 189 191 +f 196 193 195 +f 195 193 194 +f 191 196 192 +f 196 191 193 +f 198 193 199 +f 199 197 198 +f 199 193 200 +f 193 191 200 +f 199 201 197 +f 201 199 200 +f 191 189 202 +f 191 202 200 +f 200 203 201 +f 203 200 202 +f 189 187 204 +f 189 204 202 +f 206 207 205 +f 207 208 205 +f 186 210 209 +f 210 186 185 +f 212 209 210 +f 209 212 211 +f 186 209 187 +f 187 209 204 +f 212 205 211 +f 205 212 206 +f 213 205 208 +f 205 213 214 +f 214 211 205 +f 211 214 215 +f 197 214 213 +f 214 197 201 +f 214 203 215 +f 203 214 201 +f 204 203 202 +f 204 215 203 +f 211 204 209 +f 204 211 215 +f 197 216 198 +f 216 197 213 +f 213 217 216 +f 217 213 208 +f 218 208 207 +f 208 218 217 +f 219 217 218 +f 217 219 220 +f 220 216 217 +f 216 220 221 +f 221 198 216 +f 198 221 222 +f 222 193 198 +f 193 222 194 +f 194 223 195 +f 223 194 222 +f 195 224 196 +f 224 195 223 +f 225 224 223 +f 224 225 226 +f 222 225 223 +f 225 222 227 +f 221 227 222 +f 227 221 228 +f 220 228 221 +f 228 220 229 +f 219 229 220 +f 229 219 230 +f 230 232 229 +f 232 230 231 +f 229 233 228 +f 233 229 232 +f 228 234 227 +f 234 228 233 +f 227 235 225 +f 235 227 234 +f 225 235 226 +f 226 235 236 +f 235 237 236 +f 236 237 238 +f 234 239 235 +f 235 239 237 +f 240 234 233 +f 234 240 239 +f 232 240 233 +f 240 232 241 +f 242 232 231 +f 232 242 241 +f 242 243 241 +f 241 243 244 +f 244 240 241 +f 240 244 245 +f 240 245 239 +f 239 245 246 +f 246 248 247 +f 248 246 245 +f 239 246 237 +f 237 246 249 +f 237 250 238 +f 250 237 249 +f 249 251 250 +f 250 251 252 +f 246 253 249 +f 249 253 251 +f 253 247 254 +f 247 253 246 +f 253 255 251 +f 255 253 254 +f 251 256 252 +f 256 251 255 +f 255 258 256 +f 258 255 257 +f 262 260 261 +f 260 262 259 +f 264 259 262 +f 259 264 263 +f 257 264 258 +f 264 257 263 +f 265 259 263 +f 259 265 266 +f 267 263 257 +f 257 255 267 +f 268 263 267 +f 263 268 265 +f 267 254 269 +f 254 267 255 +f 269 270 268 +f 268 267 269 +f 269 247 271 +f 247 269 254 +f 272 270 271 +f 270 269 271 +f 271 248 273 +f 248 271 247 +f 244 248 245 +f 248 244 273 +f 271 273 272 +f 272 273 274 +f 275 244 243 +f 244 275 273 +f 273 275 274 +f 274 275 276 +f 260 278 261 +f 278 260 277 +f 266 260 259 +f 260 266 279 +f 279 277 260 +f 277 279 280 +f 282 185 281 +f 185 184 281 +f 284 282 281 +f 282 284 283 +f 286 283 284 +f 283 286 285 +f 288 285 286 +f 285 288 287 +f 289 290 291 +f 289 291 292 +f 290 287 288 +f 287 290 289 +f 295 294 289 +f 294 295 293 +f 289 296 287 +f 296 289 294 +f 297 294 293 +f 294 297 296 +f 298 287 296 +f 287 298 285 +f 299 296 297 +f 296 299 298 +f 298 300 285 +f 283 285 300 +f 301 302 207 +f 301 207 206 +f 282 210 185 +f 210 282 303 +f 303 212 210 +f 212 303 304 +f 282 283 303 +f 283 300 303 +f 301 212 304 +f 212 301 206 +f 305 301 306 +f 301 305 302 +f 306 304 307 +f 304 306 301 +f 293 306 297 +f 306 293 305 +f 299 306 307 +f 306 299 297 +f 299 307 300 +f 299 300 298 +f 307 304 300 +f 300 304 303 +f 293 308 305 +f 308 293 295 +f 305 309 302 +f 309 305 308 +f 302 218 207 +f 218 302 309 +f 310 219 309 +f 218 309 219 +f 309 308 310 +f 308 311 310 +f 308 295 311 +f 295 312 311 +f 295 289 312 +f 312 289 292 +f 313 292 291 +f 292 313 312 +f 314 291 290 +f 291 314 313 +f 313 314 315 +f 314 316 315 +f 312 315 317 +f 315 312 313 +f 311 317 318 +f 317 311 312 +f 310 318 319 +f 318 310 311 +f 319 219 310 +f 219 319 230 +f 230 320 231 +f 320 230 319 +f 319 321 320 +f 321 319 318 +f 318 322 321 +f 322 318 317 +f 317 323 322 +f 323 317 315 +f 323 315 316 +f 316 324 323 +f 325 323 324 +f 324 326 325 +f 322 323 327 +f 323 325 327 +f 321 322 328 +f 322 327 328 +f 320 328 329 +f 328 320 321 +f 231 320 242 +f 320 329 242 +f 242 329 243 +f 329 330 243 +f 329 328 330 +f 328 331 330 +f 328 327 331 +f 327 332 331 +f 332 334 331 +f 334 332 333 +f 327 325 332 +f 325 335 332 +f 336 325 326 +f 325 336 335 +f 335 336 337 +f 336 338 337 +f 339 332 335 +f 335 337 339 +f 333 339 340 +f 339 333 332 +f 341 339 337 +f 339 341 340 +f 342 337 338 +f 337 342 341 +f 341 344 343 +f 344 341 342 +f 346 348 345 +f 348 346 347 +f 345 350 346 +f 350 345 349 +f 350 343 344 +f 343 350 349 +f 352 345 351 +f 345 352 349 +f 349 353 343 +f 343 353 341 +f 354 349 352 +f 349 354 353 +f 353 340 341 +f 340 353 355 +f 355 354 356 +f 354 355 353 +f 355 333 340 +f 333 355 357 +f 358 357 356 +f 356 357 355 +f 357 334 333 +f 334 357 359 +f 330 334 359 +f 334 330 331 +f 357 358 359 +f 358 360 359 +f 243 330 275 +f 330 359 275 +f 275 360 276 +f 275 359 360 +f 348 362 361 +f 362 348 347 +f 351 345 348 +f 351 348 363 +f 363 361 364 +f 361 363 348 +f 1 4 184 +f 1 184 183 +f 1 188 6 +f 188 1 183 +f 6 190 8 +f 190 6 188 +f 10 190 192 +f 190 10 8 +f 12 192 196 +f 192 12 10 +f 224 12 196 +f 12 224 42 +f 226 42 224 +f 42 226 44 +f 54 44 226 +f 226 236 54 +f 54 238 56 +f 238 54 236 +f 56 250 68 +f 250 56 238 +f 68 252 70 +f 252 68 250 +f 70 256 74 +f 256 70 252 +f 74 258 76 +f 258 74 256 +f 79 78 262 +f 79 262 261 +f 82 262 78 +f 262 82 264 +f 82 76 258 +f 258 264 82 +f 83 265 84 +f 265 83 266 +f 84 268 86 +f 268 84 265 +f 88 86 268 +f 88 268 270 +f 88 272 90 +f 272 88 270 +f 90 274 92 +f 274 90 272 +f 92 276 94 +f 276 92 274 +f 96 278 277 +f 277 95 96 +f 96 79 261 +f 96 261 278 +f 97 266 83 +f 266 97 279 +f 280 97 98 +f 97 280 279 +f 98 277 280 +f 98 95 277 +f 99 184 4 +f 184 99 281 +f 99 102 284 +f 99 284 281 +f 102 104 286 +f 286 284 102 +f 106 286 104 +f 286 106 288 +f 288 110 290 +f 110 288 106 +f 314 290 110 +f 314 110 132 +f 132 316 314 +f 316 132 134 +f 316 142 324 +f 142 316 134 +f 142 326 324 +f 326 142 144 +f 144 336 326 +f 336 144 154 +f 154 338 336 +f 338 154 156 +f 156 342 338 +f 342 156 160 +f 344 160 162 +f 160 344 342 +f 165 346 166 +f 346 165 347 +f 168 166 346 +f 168 346 350 +f 168 344 162 +f 344 168 350 +f 170 169 352 +f 170 352 351 +f 169 172 354 +f 169 354 352 +f 174 354 172 +f 354 174 356 +f 174 176 358 +f 174 358 356 +f 176 360 358 +f 360 176 178 +f 178 276 360 +f 276 178 94 +f 362 180 361 +f 180 179 361 +f 180 347 165 +f 347 180 362 +f 181 170 351 +f 351 363 181 +f 182 361 179 +f 361 182 364 +f 181 364 182 +f 364 181 363 +f 366 368 365 +f 368 366 367 +f 370 366 369 +f 366 365 369 +f 371 372 366 +f 372 367 366 +f 370 373 371 +f 371 366 370 +f 377 374 376 +f 376 374 375 +f 379 377 376 +f 379 376 378 +f 376 380 378 +f 380 376 375 +f 378 382 379 +f 382 378 381 +f 380 381 378 +f 381 380 383 +f 383 385 381 +f 385 383 384 +f 385 384 386 +f 384 387 386 +f 381 388 382 +f 388 381 385 +f 386 389 390 +f 389 386 387 +f 386 388 385 +f 388 386 391 +f 386 392 391 +f 392 386 390 +f 392 393 394 +f 394 391 392 +f 395 392 390 +f 392 395 393 +f 390 396 395 +f 396 390 389 +f 397 398 371 +f 398 372 371 +f 397 371 399 +f 399 371 373 +f 400 401 397 +f 401 398 397 +f 403 400 402 +f 400 403 401 +f 405 403 404 +f 404 403 402 +f 407 405 406 +f 406 405 404 +f 409 407 408 +f 408 407 406 +f 409 395 396 +f 395 409 410 +f 410 393 395 +f 393 410 411 +f 393 411 394 +f 411 412 394 +f 413 400 399 +f 400 397 399 +f 413 414 402 +f 402 400 413 +f 414 415 404 +f 404 402 414 +f 415 416 406 +f 406 404 415 +f 417 408 416 +f 408 406 416 +f 408 410 409 +f 410 408 417 +f 417 411 410 +f 411 417 418 +f 418 412 411 +f 412 418 419 +f 399 420 421 +f 420 399 373 +f 422 413 421 +f 413 399 421 +f 422 423 414 +f 414 413 422 +f 423 424 415 +f 415 414 423 +f 425 415 424 +f 415 425 416 +f 426 416 425 +f 416 426 417 +f 426 427 418 +f 418 417 426 +f 427 419 418 +f 419 427 428 +f 430 426 429 +f 426 425 429 +f 425 431 429 +f 431 425 424 +f 424 432 431 +f 432 424 423 +f 423 433 432 +f 433 423 422 +f 435 436 434 +f 436 437 434 +f 432 433 438 +f 438 433 436 +f 439 436 435 +f 436 439 438 +f 431 432 440 +f 440 432 438 +f 441 440 439 +f 440 438 439 +f 429 431 442 +f 442 431 440 +f 443 442 441 +f 442 440 441 +f 430 442 444 +f 442 430 429 +f 428 444 445 +f 444 428 427 +f 430 444 427 +f 427 426 430 +f 446 442 443 +f 442 446 444 +f 444 447 445 +f 447 444 446 +f 420 448 421 +f 449 421 448 +f 437 448 450 +f 448 437 449 +f 422 449 433 +f 449 422 421 +f 436 449 437 +f 449 436 433 +f 434 437 451 +f 437 450 451 +f 450 453 451 +f 453 450 452 +f 450 454 452 +f 454 450 448 +f 420 454 448 +f 454 420 455 +f 456 420 373 +f 420 456 455 +f 370 457 456 +f 456 373 370 +f 458 457 369 +f 457 370 369 +f 459 369 365 +f 369 459 458 +f 368 459 365 +f 460 459 368 +f 459 462 458 +f 462 459 461 +f 460 461 459 +f 461 460 463 +f 465 463 464 +f 463 465 461 +f 466 461 465 +f 461 466 462 +f 466 468 462 +f 468 466 467 +f 470 468 469 +f 469 468 467 +f 471 470 469 +f 472 470 471 +f 474 472 473 +f 472 471 473 +f 475 464 463 +f 464 475 476 +f 477 460 367 +f 460 368 367 +f 460 475 463 +f 475 460 477 +f 476 474 473 +f 475 474 476 +f 479 480 478 +f 480 481 478 +f 475 477 478 +f 478 477 479 +f 485 483 484 +f 483 485 482 +f 487 484 486 +f 484 487 485 +f 487 488 489 +f 488 487 486 +f 490 491 492 +f 492 493 490 +f 493 494 490 +f 490 494 495 +f 496 495 494 +f 495 496 497 +f 496 498 497 +f 498 496 489 +f 491 495 499 +f 495 491 490 +f 491 500 492 +f 500 491 499 +f 495 497 501 +f 501 499 495 +f 497 502 501 +f 502 497 498 +f 503 489 488 +f 489 503 498 +f 498 503 504 +f 498 504 502 +f 506 488 505 +f 488 506 503 +f 507 508 505 +f 505 508 506 +f 507 510 508 +f 510 507 509 +f 502 511 501 +f 504 511 502 +f 506 512 503 +f 503 512 504 +f 510 513 508 +f 508 513 514 +f 508 514 506 +f 506 514 512 +f 501 515 499 +f 515 501 511 +f 511 504 516 +f 512 516 504 +f 513 517 514 +f 514 517 518 +f 514 516 512 +f 516 514 518 +f 499 519 500 +f 519 499 515 +f 515 511 520 +f 516 520 511 +f 521 518 517 +f 518 521 522 +f 520 516 522 +f 518 522 516 +f 523 522 521 +f 522 523 524 +f 522 524 520 +f 520 524 525 +f 515 525 519 +f 525 515 520 +f 527 525 526 +f 525 527 519 +f 528 530 480 +f 528 529 530 +f 530 531 532 +f 531 530 529 +f 529 534 531 +f 534 529 533 +f 535 534 533 +f 534 535 536 +f 535 538 536 +f 538 535 537 +f 537 540 538 +f 540 537 539 +f 526 540 539 +f 539 527 526 +f 524 541 526 +f 526 525 524 +f 540 541 542 +f 541 540 526 +f 541 523 543 +f 523 541 524 +f 545 457 458 +f 545 458 544 +f 544 547 545 +f 547 544 546 +f 546 531 547 +f 531 546 532 +f 457 548 456 +f 548 457 545 +f 545 549 548 +f 549 545 547 +f 547 534 549 +f 534 547 531 +f 550 455 456 +f 550 456 548 +f 548 551 550 +f 551 548 549 +f 549 536 551 +f 536 549 534 +f 552 454 455 +f 552 455 550 +f 550 553 552 +f 553 550 551 +f 551 538 553 +f 538 551 536 +f 538 542 553 +f 542 538 540 +f 454 552 554 +f 554 452 454 +f 555 552 553 +f 552 555 554 +f 554 453 452 +f 453 554 556 +f 557 554 555 +f 554 557 556 +f 542 557 555 +f 542 555 553 +f 541 543 557 +f 557 542 541 +f 496 487 489 +f 487 496 558 +f 558 485 487 +f 485 558 559 +f 559 482 485 +f 559 560 482 +f 494 558 496 +f 558 494 561 +f 493 561 494 +f 561 493 562 +f 562 492 563 +f 492 562 493 +f 492 500 563 +f 563 500 564 +f 564 565 563 +f 565 562 563 +f 562 566 561 +f 566 562 565 +f 558 561 567 +f 561 566 567 +f 500 568 564 +f 568 500 519 +f 565 569 566 +f 569 565 564 +f 568 569 564 +f 569 568 570 +f 571 519 527 +f 519 571 568 +f 568 572 570 +f 572 568 571 +f 571 574 572 +f 574 571 573 +f 539 571 527 +f 571 539 573 +f 573 539 537 +f 573 537 575 +f 535 575 537 +f 575 535 576 +f 533 576 535 +f 576 533 577 +f 529 577 533 +f 577 529 528 +f 559 567 578 +f 567 559 558 +f 566 579 567 +f 579 566 569 +f 569 580 579 +f 580 569 570 +f 578 560 559 +f 560 578 581 +f 579 578 567 +f 582 578 579 +f 578 582 581 +f 581 582 583 +f 580 572 584 +f 572 580 570 +f 585 580 584 +f 582 580 585 +f 580 582 579 +f 584 574 586 +f 574 584 572 +f 586 585 584 +f 585 586 587 +f 582 587 583 +f 587 582 585 +f 588 367 372 +f 367 588 477 +f 589 372 398 +f 372 589 588 +f 588 479 477 +f 479 588 590 +f 479 590 528 +f 528 480 479 +f 591 398 401 +f 398 591 589 +f 592 401 403 +f 401 592 591 +f 593 403 405 +f 403 593 592 +f 594 405 407 +f 405 594 593 +f 595 407 409 +f 407 595 594 +f 596 595 396 +f 595 409 396 +f 597 396 389 +f 396 597 596 +f 387 597 389 +f 597 387 598 +f 600 597 599 +f 597 600 601 +f 598 599 597 +f 598 602 599 +f 599 603 600 +f 603 599 602 +f 604 605 606 +f 609 610 607 +f 609 607 608 +f 608 607 611 +f 608 611 612 +f 612 611 604 +f 612 604 613 +f 613 604 606 +f 613 606 614 +f 614 616 613 +f 616 614 615 +f 612 616 617 +f 616 612 613 +f 608 617 618 +f 617 608 612 +f 619 609 608 +f 619 608 618 +f 620 445 447 +f 445 620 621 +f 621 622 428 +f 621 428 445 +f 622 419 428 +f 622 623 419 +f 623 412 419 +f 412 623 624 +f 624 394 412 +f 394 624 625 +f 394 625 391 +f 391 625 626 +f 388 391 626 +f 388 626 627 +f 382 388 627 +f 382 627 628 +f 379 382 628 +f 379 628 629 +f 629 630 631 +f 630 629 628 +f 629 377 379 +f 377 629 632 +f 633 377 632 +f 377 633 374 +f 634 374 633 +f 374 634 375 +f 375 635 380 +f 635 375 634 +f 603 602 605 +f 636 605 602 +f 380 637 383 +f 637 380 635 +f 383 638 384 +f 638 383 637 +f 638 637 640 +f 637 639 640 +f 598 384 638 +f 384 598 387 +f 638 636 598 +f 636 602 598 +f 642 630 641 +f 630 642 631 +f 643 629 631 +f 629 643 632 +f 644 632 643 +f 632 644 633 +f 645 633 644 +f 633 645 634 +f 634 646 635 +f 646 634 645 +f 635 647 637 +f 635 646 647 +f 648 636 638 +f 648 638 640 +f 637 649 639 +f 649 637 647 +f 648 640 639 +f 648 639 649 +f 636 606 605 +f 636 650 606 +f 651 636 648 +f 636 651 650 +f 652 647 646 +f 652 649 647 +f 649 651 648 +f 651 649 652 +f 653 652 645 +f 652 646 645 +f 654 653 644 +f 653 645 644 +f 653 654 656 +f 655 656 654 +f 652 653 657 +f 656 657 653 +f 657 656 658 +f 651 652 659 +f 659 652 657 +f 660 657 658 +f 657 660 659 +f 661 662 658 +f 662 660 658 +f 658 656 663 +f 663 661 658 +f 661 663 664 +f 661 665 662 +f 665 661 664 +f 663 666 668 +f 667 668 666 +f 664 668 665 +f 668 664 663 +f 663 656 655 +f 663 655 669 +f 663 670 666 +f 670 663 669 +f 669 655 671 +f 671 655 654 +f 671 654 672 +f 642 672 643 +f 642 643 631 +f 672 654 643 +f 654 644 643 +f 674 641 673 +f 641 674 642 +f 674 675 642 +f 675 672 642 +f 673 627 676 +f 627 673 628 +f 641 630 628 +f 641 628 673 +f 650 677 614 +f 614 606 650 +f 615 614 678 +f 677 678 614 +f 679 615 678 +f 615 679 680 +f 627 626 676 +f 676 626 681 +f 679 674 682 +f 674 679 675 +f 682 674 673 +f 682 673 676 +f 676 683 682 +f 683 676 681 +f 626 625 681 +f 681 625 684 +f 682 680 679 +f 680 682 683 +f 683 684 685 +f 684 683 681 +f 624 684 625 +f 684 624 686 +f 684 687 685 +f 687 684 686 +f 624 623 686 +f 686 623 688 +f 623 622 688 +f 688 622 689 +f 621 689 622 +f 689 621 690 +f 620 690 621 +f 690 620 691 +f 688 693 686 +f 693 688 692 +f 687 693 694 +f 693 687 686 +f 689 692 688 +f 692 689 695 +f 690 695 689 +f 695 690 696 +f 691 696 690 +f 696 691 697 +f 694 693 698 +f 692 698 693 +f 701 699 700 +f 699 701 698 +f 695 698 692 +f 698 695 699 +f 696 699 695 +f 699 696 702 +f 697 702 696 +f 702 697 703 +f 704 705 483 +f 705 484 483 +f 486 705 706 +f 705 486 484 +f 486 505 488 +f 505 486 706 +f 505 707 507 +f 707 505 706 +f 708 507 707 +f 507 708 509 +f 709 707 706 +f 707 709 710 +f 706 711 709 +f 711 706 705 +f 702 713 699 +f 713 702 712 +f 703 712 702 +f 712 703 714 +f 714 716 712 +f 716 714 715 +f 716 715 710 +f 716 710 709 +f 710 708 707 +f 710 715 708 +f 717 711 704 +f 711 705 704 +f 718 704 482 +f 704 483 482 +f 711 717 716 +f 716 709 711 +f 716 713 712 +f 717 713 716 +f 700 713 719 +f 713 700 699 +f 720 717 718 +f 717 704 718 +f 560 718 482 +f 560 721 718 +f 713 720 719 +f 720 713 717 +f 607 722 723 +f 722 607 610 +f 618 725 619 +f 725 618 724 +f 722 725 723 +f 724 723 725 +f 723 724 726 +f 723 726 727 +f 723 611 607 +f 611 723 728 +f 617 724 618 +f 724 617 729 +f 604 728 730 +f 728 604 611 +f 731 615 680 +f 615 731 616 +f 617 616 729 +f 729 616 731 +f 605 604 732 +f 732 604 730 +f 732 730 731 +f 731 683 685 +f 683 731 680 +f 728 729 730 +f 731 730 729 +f 733 603 605 +f 733 605 732 +f 731 685 734 +f 734 685 687 +f 733 601 600 +f 733 600 603 +f 601 733 734 +f 731 733 732 +f 734 733 731 +f 601 596 597 +f 596 601 735 +f 734 735 601 +f 735 734 736 +f 734 687 736 +f 736 687 694 +f 701 694 698 +f 694 701 736 +f 735 737 596 +f 596 737 595 +f 736 737 735 +f 737 736 738 +f 701 738 736 +f 738 701 700 +f 737 739 595 +f 595 739 594 +f 737 740 739 +f 740 737 738 +f 738 719 740 +f 719 738 700 +f 739 741 594 +f 594 741 593 +f 739 742 741 +f 742 739 740 +f 719 720 740 +f 740 720 742 +f 720 718 742 +f 742 718 721 +f 560 743 721 +f 743 560 581 +f 744 721 743 +f 741 744 593 +f 593 744 592 +f 741 721 744 +f 721 741 742 +f 581 583 743 +f 743 583 745 +f 592 746 591 +f 746 592 744 +f 589 590 588 +f 590 589 747 +f 528 748 577 +f 748 528 590 +f 577 749 576 +f 749 577 748 +f 576 750 575 +f 750 576 749 +f 575 751 573 +f 751 575 750 +f 574 573 752 +f 752 573 751 +f 753 586 574 +f 753 574 752 +f 587 745 583 +f 745 587 754 +f 587 753 754 +f 753 587 586 +f 755 753 752 +f 753 755 754 +f 756 757 750 +f 750 757 751 +f 751 757 755 +f 751 755 752 +f 591 747 589 +f 747 591 746 +f 756 747 746 +f 744 745 746 +f 745 744 743 +f 746 745 754 +f 746 754 756 +f 756 750 749 +f 749 748 756 +f 747 748 590 +f 748 747 756 +f 756 754 755 +f 756 755 757 +f 546 759 532 +f 759 546 758 +f 544 462 760 +f 462 544 458 +f 546 760 758 +f 760 546 544 +f 758 761 762 +f 760 761 758 +f 760 468 763 +f 468 760 462 +f 761 763 764 +f 760 763 761 +f 470 763 468 +f 763 470 765 +f 764 765 766 +f 765 764 763 +f 472 765 470 +f 765 472 767 +f 767 766 765 +f 766 767 768 +f 474 769 472 +f 769 767 472 +f 769 768 767 +f 768 769 770 +f 762 759 758 +f 759 762 771 +f 530 481 480 +f 530 772 481 +f 475 772 474 +f 772 769 474 +f 769 773 770 +f 773 769 772 +f 475 481 772 +f 481 475 478 +f 532 759 772 +f 532 772 530 +f 771 772 759 +f 772 771 773 +f 728 723 774 +f 774 723 727 +f 778 776 777 +f 776 778 775 +f 775 779 780 +f 775 780 776 +f 727 779 775 +f 779 727 726 +f 777 780 781 +f 780 777 776 +f 729 726 724 +f 726 729 782 +f 729 728 782 +f 782 728 774 +f 774 775 778 +f 775 774 727 +f 782 774 783 +f 783 774 778 +f 777 783 778 +f 783 777 781 +f 781 779 783 +f 779 781 780 +f 782 779 726 +f 779 782 783 +f 662 785 660 +f 785 662 784 +f 665 668 787 +f 786 787 668 +f 787 784 665 +f 784 662 665 +f 789 671 788 +f 671 789 669 +f 675 671 672 +f 671 675 788 +f 678 675 679 +f 675 678 788 +f 790 650 651 +f 790 651 659 +f 785 659 660 +f 659 785 790 +f 793 788 792 +f 792 788 791 +f 792 791 794 +f 791 790 794 +f 788 678 791 +f 791 678 677 +f 677 790 791 +f 790 677 650 +f 794 790 785 +f 794 785 795 +f 796 795 784 +f 795 785 784 +f 787 786 798 +f 797 798 786 +f 786 667 797 +f 667 786 668 +f 670 797 667 +f 666 670 667 +f 670 789 797 +f 789 670 669 +f 799 798 797 +f 797 789 799 +f 787 796 784 +f 796 787 798 +f 789 793 799 +f 793 789 788 +f 792 801 793 +f 801 792 800 +f 794 802 792 +f 792 802 800 +f 795 802 794 +f 802 795 803 +f 796 803 795 +f 803 796 804 +f 805 806 798 +f 805 798 799 +f 804 798 806 +f 798 804 796 +f 805 793 801 +f 793 805 799 +f 800 808 801 +f 808 800 807 +f 800 802 809 +f 800 809 807 +f 803 809 802 +f 809 803 810 +f 804 810 803 +f 810 804 811 +f 813 805 812 +f 805 813 806 +f 804 806 813 +f 804 813 811 +f 812 805 808 +f 805 801 808 +f 807 815 808 +f 815 807 814 +f 809 816 807 +f 807 816 814 +f 810 816 809 +f 816 810 817 +f 811 817 810 +f 817 811 818 +f 820 813 819 +f 819 813 812 +f 818 813 820 +f 813 818 811 +f 808 819 812 +f 819 808 815 +f 819 818 820 +f 818 819 814 +f 814 817 818 +f 817 814 816 +f 814 819 815 +f 822 824 821 +f 824 822 823 +f 822 825 826 +f 822 826 823 +f 827 828 822 +f 827 822 821 +f 829 825 828 +f 825 822 828 +f 830 832 833 +f 832 830 831 +f 830 833 834 +f 830 834 835 +f 830 836 831 +f 836 830 835 +f 834 837 835 +f 835 837 838 +f 838 836 835 +f 836 838 839 +f 838 840 839 +f 839 840 841 +f 841 840 842 +f 842 843 841 +f 844 838 837 +f 838 844 840 +f 842 846 843 +f 846 842 845 +f 844 842 840 +f 842 844 847 +f 842 848 845 +f 848 842 847 +f 850 848 849 +f 848 847 849 +f 848 851 845 +f 851 848 850 +f 845 852 846 +f 852 845 851 +f 853 854 828 +f 853 828 827 +f 855 828 854 +f 828 855 829 +f 856 857 854 +f 854 853 856 +f 857 859 858 +f 859 857 856 +f 860 859 861 +f 859 860 858 +f 862 861 863 +f 861 862 860 +f 863 865 864 +f 863 864 862 +f 851 865 852 +f 865 851 866 +f 866 850 867 +f 850 866 851 +f 867 850 849 +f 867 849 868 +f 857 869 855 +f 857 855 854 +f 870 869 858 +f 869 857 858 +f 871 870 860 +f 870 858 860 +f 872 871 862 +f 862 871 860 +f 864 873 872 +f 864 872 862 +f 865 866 864 +f 864 866 873 +f 866 867 873 +f 873 867 874 +f 874 868 875 +f 868 874 867 +f 855 877 829 +f 877 855 876 +f 869 878 876 +f 876 855 869 +f 879 878 870 +f 878 869 870 +f 880 879 871 +f 879 870 871 +f 881 871 872 +f 871 881 880 +f 882 872 873 +f 872 882 881 +f 883 882 874 +f 882 873 874 +f 883 875 884 +f 875 883 874 +f 882 885 886 +f 886 881 882 +f 887 881 886 +f 881 887 880 +f 888 880 887 +f 880 888 879 +f 889 879 888 +f 879 889 878 +f 890 435 434 +f 890 434 891 +f 892 889 888 +f 889 892 890 +f 439 890 892 +f 890 439 435 +f 893 888 887 +f 888 893 892 +f 893 441 439 +f 893 439 892 +f 894 887 886 +f 887 894 893 +f 894 443 441 +f 894 441 893 +f 885 894 886 +f 894 885 895 +f 895 884 896 +f 884 895 883 +f 895 885 883 +f 885 882 883 +f 446 894 895 +f 894 446 443 +f 447 895 896 +f 895 447 446 +f 876 897 898 +f 876 898 877 +f 891 898 897 +f 898 891 899 +f 897 878 889 +f 878 897 876 +f 890 897 889 +f 897 890 891 +f 891 434 451 +f 891 451 899 +f 451 453 899 +f 899 453 900 +f 899 901 898 +f 901 899 900 +f 898 901 877 +f 877 901 902 +f 877 903 829 +f 903 877 902 +f 904 825 903 +f 825 829 903 +f 904 905 826 +f 826 825 904 +f 826 906 823 +f 906 826 905 +f 906 824 823 +f 906 907 824 +f 909 906 905 +f 906 909 908 +f 908 907 906 +f 907 908 910 +f 912 910 908 +f 910 912 911 +f 913 908 909 +f 908 913 912 +f 914 913 909 +f 913 914 915 +f 914 916 917 +f 917 915 914 +f 916 918 919 +f 916 919 917 +f 918 920 921 +f 921 919 918 +f 911 923 910 +f 923 911 922 +f 907 924 821 +f 907 821 824 +f 923 907 910 +f 907 923 924 +f 920 923 922 +f 922 921 920 +f 925 926 927 +f 925 927 928 +f 924 923 927 +f 924 927 926 +f 932 930 931 +f 930 932 929 +f 929 934 933 +f 934 929 932 +f 934 936 933 +f 936 934 935 +f 938 939 937 +f 939 940 937 +f 939 942 940 +f 942 939 941 +f 941 944 942 +f 944 941 943 +f 944 945 935 +f 945 944 943 +f 941 938 946 +f 938 941 939 +f 937 947 938 +f 938 947 946 +f 943 941 948 +f 941 946 948 +f 943 949 945 +f 949 943 948 +f 935 950 936 +f 950 935 945 +f 950 945 951 +f 945 949 951 +f 936 952 953 +f 952 936 950 +f 954 955 953 +f 953 952 954 +f 955 510 509 +f 510 955 954 +f 956 949 948 +f 956 951 949 +f 957 952 950 +f 950 951 957 +f 954 513 510 +f 513 954 958 +f 958 954 952 +f 952 957 958 +f 959 948 946 +f 948 959 956 +f 960 957 951 +f 960 951 956 +f 958 517 513 +f 517 958 961 +f 958 960 961 +f 960 958 957 +f 962 946 947 +f 946 962 959 +f 963 956 959 +f 963 960 956 +f 961 964 521 +f 961 521 517 +f 960 963 964 +f 960 964 961 +f 964 965 523 +f 964 523 521 +f 963 966 965 +f 965 964 963 +f 966 959 962 +f 959 966 963 +f 966 968 967 +f 968 966 962 +f 970 971 969 +f 971 925 969 +f 973 969 972 +f 969 973 970 +f 970 974 975 +f 974 970 973 +f 975 974 977 +f 977 974 976 +f 977 978 979 +f 978 977 976 +f 980 979 978 +f 979 980 981 +f 980 967 981 +f 967 968 981 +f 982 965 967 +f 967 965 966 +f 982 980 983 +f 980 982 967 +f 965 982 523 +f 523 982 543 +f 984 905 904 +f 905 984 985 +f 985 986 987 +f 986 985 984 +f 987 973 972 +f 973 987 986 +f 984 904 988 +f 904 903 988 +f 984 989 986 +f 989 984 988 +f 986 974 973 +f 974 986 989 +f 902 990 903 +f 988 903 990 +f 988 991 989 +f 991 988 990 +f 989 976 974 +f 976 989 991 +f 901 992 902 +f 902 992 990 +f 993 990 992 +f 990 993 991 +f 991 978 976 +f 978 991 993 +f 978 983 980 +f 983 978 993 +f 994 901 900 +f 901 994 992 +f 992 995 993 +f 995 992 994 +f 453 994 900 +f 994 453 556 +f 994 557 995 +f 557 994 556 +f 557 983 995 +f 983 993 995 +f 543 982 557 +f 982 983 557 +f 934 996 944 +f 934 944 935 +f 932 996 934 +f 996 932 997 +f 931 998 997 +f 931 997 932 +f 996 999 942 +f 942 944 996 +f 999 1000 940 +f 940 942 999 +f 1000 937 940 +f 937 1000 1001 +f 1001 947 937 +f 947 1001 1002 +f 1003 1002 1001 +f 1001 1000 1003 +f 1000 999 1004 +f 1000 1004 1003 +f 1004 999 1005 +f 999 996 1005 +f 947 1006 962 +f 1006 947 1002 +f 1007 1003 1004 +f 1003 1007 1002 +f 1007 1006 1002 +f 1006 1007 1008 +f 962 1009 968 +f 1009 962 1006 +f 1008 1010 1006 +f 1006 1010 1009 +f 1012 1009 1011 +f 1011 1009 1010 +f 968 1009 981 +f 981 1009 1012 +f 981 1012 979 +f 979 1012 1013 +f 1013 1014 977 +f 1013 977 979 +f 1014 1015 975 +f 1014 975 977 +f 1015 970 975 +f 970 1015 971 +f 997 1005 996 +f 1005 997 1016 +f 1017 1004 1005 +f 1004 1017 1007 +f 1007 1018 1008 +f 1018 1007 1017 +f 998 1016 997 +f 1016 998 1019 +f 1016 1017 1005 +f 1016 1020 1017 +f 1019 1020 1016 +f 1020 1019 1021 +f 1018 1010 1008 +f 1010 1018 1022 +f 1018 1023 1022 +f 1018 1020 1023 +f 1020 1018 1017 +f 1011 1022 1024 +f 1022 1011 1010 +f 1024 1023 1025 +f 1023 1024 1022 +f 1020 1021 1025 +f 1020 1025 1023 +f 1026 821 924 +f 821 1026 827 +f 1027 827 1026 +f 827 1027 853 +f 926 1026 924 +f 1026 926 1028 +f 1028 926 971 +f 926 925 971 +f 1029 853 1027 +f 853 1029 856 +f 1030 856 1029 +f 856 1030 859 +f 1031 859 1030 +f 859 1031 861 +f 1032 861 1031 +f 861 1032 863 +f 1033 863 1032 +f 863 1033 865 +f 1033 1034 852 +f 852 865 1033 +f 1035 852 1034 +f 852 1035 846 +f 843 1035 1036 +f 1035 843 846 +f 1038 1035 1037 +f 1035 1038 1039 +f 1040 1036 1039 +f 1036 1035 1039 +f 1041 1039 1038 +f 1039 1041 1040 +f 1042 1043 1044 +f 610 609 1046 +f 1045 1046 609 +f 1046 1045 1048 +f 1047 1048 1045 +f 1048 1047 1043 +f 1049 1043 1047 +f 1043 1049 1044 +f 1050 1044 1049 +f 1049 1051 1050 +f 1052 1050 1051 +f 1047 1051 1049 +f 1051 1047 1053 +f 1045 1053 1047 +f 1053 1045 1054 +f 609 619 1045 +f 1054 1045 619 +f 620 896 1055 +f 896 620 447 +f 1056 1055 884 +f 1055 896 884 +f 1057 1056 875 +f 1056 884 875 +f 1057 875 868 +f 1057 868 1058 +f 868 849 1058 +f 1058 849 1059 +f 849 847 1059 +f 1059 847 1060 +f 844 1060 847 +f 1060 844 1061 +f 1061 837 1062 +f 837 1061 844 +f 1062 834 1063 +f 834 1062 837 +f 1063 1065 1062 +f 1065 1063 1064 +f 833 1063 834 +f 1063 833 1066 +f 833 1067 1066 +f 1067 833 832 +f 1068 832 831 +f 832 1068 1067 +f 1069 831 836 +f 831 1069 1068 +f 1042 1040 1041 +f 1042 1070 1040 +f 1071 836 839 +f 836 1071 1069 +f 1072 839 841 +f 839 1072 1071 +f 1071 1072 1073 +f 1074 1071 1073 +f 841 843 1036 +f 841 1036 1072 +f 1070 1036 1040 +f 1070 1072 1036 +f 1075 1065 1064 +f 1065 1075 1076 +f 1077 1063 1066 +f 1063 1077 1064 +f 1078 1066 1067 +f 1066 1078 1077 +f 1079 1067 1068 +f 1067 1079 1078 +f 1068 1080 1079 +f 1080 1068 1069 +f 1071 1081 1069 +f 1080 1069 1081 +f 1072 1070 1082 +f 1072 1082 1073 +f 1083 1071 1074 +f 1071 1083 1081 +f 1074 1073 1082 +f 1074 1082 1083 +f 1044 1070 1042 +f 1084 1070 1044 +f 1070 1085 1082 +f 1085 1070 1084 +f 1081 1086 1080 +f 1083 1086 1081 +f 1082 1085 1083 +f 1083 1085 1086 +f 1080 1086 1079 +f 1079 1086 1087 +f 1087 1078 1079 +f 1078 1087 1088 +f 1088 1087 1089 +f 1088 1089 1090 +f 1087 1086 1091 +f 1087 1091 1089 +f 1089 1091 1092 +f 1085 1093 1086 +f 1086 1093 1091 +f 1094 1091 1093 +f 1091 1094 1092 +f 1095 1092 1094 +f 1095 1096 1092 +f 1089 1092 1097 +f 1096 1097 1092 +f 1097 1096 1098 +f 1098 1096 1099 +f 1096 1095 1099 +f 1102 1097 1100 +f 1102 1100 1101 +f 1098 1100 1097 +f 1100 1098 1099 +f 1090 1089 1097 +f 1090 1097 1103 +f 1097 1104 1103 +f 1104 1097 1102 +f 1090 1103 1105 +f 1090 1105 1088 +f 1106 1088 1105 +f 1106 1075 1077 +f 1075 1064 1077 +f 1078 1088 1077 +f 1077 1088 1106 +f 1107 1076 1075 +f 1076 1107 1108 +f 1109 1107 1075 +f 1075 1106 1109 +f 1108 1061 1062 +f 1061 1108 1110 +f 1062 1076 1108 +f 1076 1062 1065 +f 1111 1084 1050 +f 1084 1044 1050 +f 1112 1111 1050 +f 1112 1050 1052 +f 1114 1052 1113 +f 1052 1114 1112 +f 1110 1060 1061 +f 1060 1110 1115 +f 1107 1114 1116 +f 1114 1107 1109 +f 1107 1116 1108 +f 1108 1116 1110 +f 1117 1110 1116 +f 1110 1117 1115 +f 1115 1059 1060 +f 1059 1115 1118 +f 1116 1113 1117 +f 1113 1116 1114 +f 1117 1118 1115 +f 1118 1117 1119 +f 1059 1118 1058 +f 1058 1118 1120 +f 1121 1118 1119 +f 1118 1121 1120 +f 1120 1122 1057 +f 1057 1058 1120 +f 1122 1123 1056 +f 1056 1057 1122 +f 1055 1123 1124 +f 1123 1055 1056 +f 1124 620 1055 +f 620 1124 691 +f 1122 1126 1125 +f 1126 1122 1120 +f 1121 1126 1120 +f 1126 1121 1127 +f 1123 1125 1128 +f 1125 1123 1122 +f 1124 1128 1129 +f 1128 1124 1123 +f 691 1129 697 +f 1129 691 1124 +f 1130 1125 1126 +f 1130 1126 1127 +f 1132 1133 1131 +f 1133 1132 1130 +f 1128 1130 1132 +f 1130 1128 1125 +f 1129 1132 1134 +f 1132 1129 1128 +f 697 1134 703 +f 1134 697 1129 +f 930 929 1135 +f 930 1135 1136 +f 933 1135 929 +f 1135 933 1137 +f 953 1137 933 +f 953 933 936 +f 953 1138 1137 +f 1138 953 955 +f 955 708 1138 +f 708 955 509 +f 1140 1138 1139 +f 1138 1140 1137 +f 1135 1137 1141 +f 1141 1137 1140 +f 1134 1143 1142 +f 1143 1134 1132 +f 703 1142 714 +f 1142 703 1134 +f 714 1144 715 +f 1144 714 1142 +f 1139 1144 1140 +f 715 1144 1139 +f 1138 708 1139 +f 715 1139 708 +f 1141 1145 1136 +f 1141 1136 1135 +f 1136 931 930 +f 1136 1146 931 +f 1145 1141 1144 +f 1144 1141 1140 +f 1143 1144 1142 +f 1143 1145 1144 +f 1131 1143 1132 +f 1143 1131 1147 +f 1145 1148 1146 +f 1145 1146 1136 +f 1146 998 931 +f 1146 1149 998 +f 1148 1143 1147 +f 1143 1148 1145 +f 1046 722 610 +f 722 1046 1150 +f 619 725 1054 +f 1054 725 1151 +f 725 722 1150 +f 725 1150 1151 +f 1153 1152 1150 +f 1151 1150 1152 +f 1048 1150 1046 +f 1150 1048 1154 +f 1054 1151 1053 +f 1053 1151 1155 +f 1043 1154 1048 +f 1154 1043 1156 +f 1157 1052 1051 +f 1052 1157 1113 +f 1053 1155 1051 +f 1051 1155 1157 +f 1158 1043 1042 +f 1043 1158 1156 +f 1156 1158 1157 +f 1117 1113 1157 +f 1117 1157 1119 +f 1155 1154 1156 +f 1155 1156 1157 +f 1042 1159 1158 +f 1159 1042 1041 +f 1157 1160 1119 +f 1119 1160 1121 +f 1037 1159 1038 +f 1159 1041 1038 +f 1159 1037 1160 +f 1159 1160 1157 +f 1157 1158 1159 +f 1037 1034 1161 +f 1034 1037 1035 +f 1160 1037 1161 +f 1160 1161 1162 +f 1162 1121 1160 +f 1121 1162 1127 +f 1127 1133 1130 +f 1133 1127 1162 +f 1163 1161 1034 +f 1034 1033 1163 +f 1162 1161 1163 +f 1162 1163 1164 +f 1133 1164 1131 +f 1164 1133 1162 +f 1165 1163 1033 +f 1033 1032 1165 +f 1163 1166 1164 +f 1166 1163 1165 +f 1164 1147 1131 +f 1147 1164 1166 +f 1167 1165 1032 +f 1032 1031 1167 +f 1165 1168 1166 +f 1168 1165 1167 +f 1166 1148 1147 +f 1148 1166 1168 +f 1168 1146 1148 +f 1146 1168 1149 +f 998 1169 1019 +f 1169 998 1149 +f 1149 1170 1169 +f 1170 1167 1031 +f 1031 1030 1170 +f 1167 1149 1168 +f 1149 1167 1170 +f 1169 1021 1019 +f 1021 1169 1171 +f 1030 1029 1172 +f 1030 1172 1170 +f 1028 1027 1026 +f 1027 1028 1173 +f 1174 1028 971 +f 971 1015 1174 +f 1015 1175 1174 +f 1175 1015 1014 +f 1175 1014 1176 +f 1014 1013 1176 +f 1176 1013 1177 +f 1013 1012 1177 +f 1011 1178 1012 +f 1177 1012 1178 +f 1024 1179 1011 +f 1178 1011 1179 +f 1171 1025 1021 +f 1025 1171 1180 +f 1025 1179 1024 +f 1179 1025 1180 +f 1181 1179 1180 +f 1179 1181 1178 +f 1182 1183 1176 +f 1176 1177 1182 +f 1182 1177 1181 +f 1177 1178 1181 +f 1173 1029 1027 +f 1029 1173 1172 +f 1173 1183 1172 +f 1170 1171 1169 +f 1171 1170 1172 +f 1171 1172 1180 +f 1180 1172 1183 +f 1176 1183 1175 +f 1174 1175 1183 +f 1173 1174 1183 +f 1174 1173 1028 +f 1180 1183 1181 +f 1181 1183 1182 +f 987 1185 1184 +f 1185 987 972 +f 985 909 905 +f 909 985 1186 +f 987 1186 985 +f 1186 987 1184 +f 1187 1186 1184 +f 1187 1184 1188 +f 1186 914 909 +f 914 1186 1189 +f 1189 1186 1187 +f 1189 1187 1190 +f 1189 916 914 +f 916 1189 1191 +f 1191 1190 1192 +f 1190 1191 1189 +f 918 1191 1193 +f 1191 918 916 +f 1192 1193 1191 +f 1193 1192 1194 +f 1195 920 918 +f 1195 918 1193 +f 1195 1194 1196 +f 1194 1195 1193 +f 1188 1185 1197 +f 1185 1188 1184 +f 928 969 925 +f 1198 969 928 +f 1198 923 920 +f 1198 920 1195 +f 1195 1199 1198 +f 1199 1195 1196 +f 923 928 927 +f 928 923 1198 +f 969 1198 972 +f 1185 972 1198 +f 1185 1198 1197 +f 1197 1198 1199 +f 1200 1150 1154 +f 1150 1200 1153 +f 1204 1202 1203 +f 1202 1204 1201 +f 1205 1203 1202 +f 1206 1203 1205 +f 1153 1206 1152 +f 1206 1153 1203 +f 1201 1205 1202 +f 1205 1201 1207 +f 1152 1155 1151 +f 1155 1152 1208 +f 1154 1155 1208 +f 1154 1208 1200 +f 1200 1203 1153 +f 1203 1200 1204 +f 1209 1200 1208 +f 1200 1209 1204 +f 1209 1201 1204 +f 1201 1209 1207 +f 1206 1207 1209 +f 1207 1206 1205 +f 1208 1206 1209 +f 1206 1208 1152 +f 1095 1211 1210 +f 1211 1095 1094 +f 1100 1099 1212 +f 1100 1212 1213 +f 1095 1210 1099 +f 1099 1210 1212 +f 1215 1105 1103 +f 1105 1215 1214 +f 1109 1105 1214 +f 1105 1109 1106 +f 1109 1112 1114 +f 1112 1109 1214 +f 1216 1085 1084 +f 1085 1216 1093 +f 1211 1093 1216 +f 1093 1211 1094 +f 1214 1219 1217 +f 1214 1217 1218 +f 1218 1217 1220 +f 1220 1216 1218 +f 1218 1112 1214 +f 1112 1218 1111 +f 1216 1111 1218 +f 1111 1216 1084 +f 1216 1220 1211 +f 1211 1220 1221 +f 1221 1222 1210 +f 1210 1211 1221 +f 1223 1213 1212 +f 1223 1224 1213 +f 1213 1101 1100 +f 1101 1213 1224 +f 1104 1102 1101 +f 1224 1104 1101 +f 1104 1215 1103 +f 1215 1104 1224 +f 1223 1225 1224 +f 1225 1215 1224 +f 1212 1222 1223 +f 1222 1212 1210 +f 1215 1219 1214 +f 1219 1215 1225 +f 1226 1217 1219 +f 1217 1226 1227 +f 1227 1228 1217 +f 1228 1220 1217 +f 1221 1228 1229 +f 1228 1221 1220 +f 1222 1229 1230 +f 1229 1222 1221 +f 1223 1232 1225 +f 1232 1223 1231 +f 1223 1230 1231 +f 1230 1223 1222 +f 1232 1219 1225 +f 1219 1232 1226 +f 1227 1233 1234 +f 1233 1227 1226 +f 1235 1228 1227 +f 1235 1227 1234 +f 1229 1235 1236 +f 1235 1229 1228 +f 1230 1236 1237 +f 1236 1230 1229 +f 1232 1238 1239 +f 1238 1232 1231 +f 1230 1238 1231 +f 1238 1230 1237 +f 1232 1233 1226 +f 1232 1239 1233 +f 1240 1234 1233 +f 1234 1240 1241 +f 1234 1241 1242 +f 1242 1235 1234 +f 1236 1242 1243 +f 1242 1236 1235 +f 1237 1243 1244 +f 1243 1237 1236 +f 1238 1246 1239 +f 1246 1238 1245 +f 1238 1244 1245 +f 1244 1238 1237 +f 1246 1233 1239 +f 1233 1246 1240 +f 1243 1242 1241 +f 1243 1241 1244 +f 1246 1244 1241 +f 1244 1246 1245 +f 1246 1241 1240 +# 2464 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/l_uleg_chull.obj b/examples/Atlas/urdf/mesh/l_uleg_chull.obj new file mode 100644 index 0000000..9fd7187 --- /dev/null +++ b/examples/Atlas/urdf/mesh/l_uleg_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object l_uleg_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.128024 -0.013473 -0.196928 +v -0.066338 -0.040351 -0.386306 +v -0.100668 -0.058048 -0.221429 +v -0.043178 -0.041320 -0.392887 +v 0.036808 -0.035859 -0.307644 +v 0.014000 -0.050346 0.013891 +v -0.064297 -0.072733 -0.238606 +v 0.010261 -0.070918 -0.255186 +v -0.066886 0.041337 -0.383422 +v -0.121670 0.019266 -0.106035 +v -0.107679 -0.047446 -0.102959 +v 0.012880 0.051141 0.016002 +v -0.027756 -0.077954 -0.040144 +v 0.031237 -0.073648 -0.075753 +v -0.063133 0.074138 -0.236752 +v -0.110790 0.046504 -0.219981 +v -0.091498 0.061663 -0.101093 +v 0.038709 0.006203 -0.329533 +v 0.078030 0.028717 -0.117900 +v 0.085653 -0.013862 -0.122764 +v 0.051005 0.036670 -0.248941 +v 0.000424 0.074580 -0.001100 +v 0.011051 0.068951 -0.267148 +v 0.041881 0.068482 -0.094515 +v -0.040340 0.041827 -0.391602 +v -0.011042 0.049436 0.016944 +v -0.009904 -0.049233 0.018210 +# 27 vertices, 0 vertices normals + +f 7 2 4 +f 12 22 26 +f 7 3 2 +f 11 10 1 +f 3 11 1 +f 3 1 2 +f 19 24 12 +f 9 15 25 +f 25 2 9 +f 9 1 16 +f 9 2 1 +f 7 4 8 +f 11 3 13 +f 3 7 13 +f 10 16 1 +f 26 17 10 +f 17 26 22 +f 19 12 20 +f 8 14 7 +f 5 14 8 +f 18 4 25 +f 8 4 5 +f 4 18 5 +f 20 14 5 +f 14 20 6 +f 7 14 13 +f 11 13 27 +f 21 24 19 +f 27 14 6 +f 27 13 14 +f 9 16 15 +f 15 23 25 +f 15 16 17 +f 20 12 6 +f 11 27 10 +f 26 10 27 +f 22 12 24 +f 23 15 22 +f 21 23 24 +f 6 12 27 +f 10 17 16 +f 22 15 17 +f 25 23 18 +f 21 19 20 +f 24 23 22 +f 18 20 5 +f 20 18 21 +f 21 18 23 +f 2 25 4 +f 12 26 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/ltorso.obj b/examples/Atlas/urdf/mesh/ltorso.obj new file mode 100644 index 0000000..37cac55 --- /dev/null +++ b/examples/Atlas/urdf/mesh/ltorso.obj @@ -0,0 +1,392 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object ltorso.obj +# +# Vertices: 132 +# Faces: 244 +# +#### +v 0.021511 0.019231 0.108094 +v 0.021511 0.019231 0.087995 +v 0.021511 -0.019477 0.087995 +v 0.021511 -0.019477 0.108094 +v 0.000512 0.019231 0.067797 +v 0.021511 0.019231 0.067797 +v -0.021486 0.033053 0.067797 +v 0.018411 0.033052 0.097195 +v -0.033886 0.033052 0.138392 +v -0.055484 0.019231 0.037899 +v -0.049385 0.019231 0.028299 +v -0.050384 0.033052 0.028299 +v -0.056484 0.033052 0.037899 +v -0.020487 0.019231 0.067797 +v 0.001112 0.019231 0.178689 +v 0.000812 0.033052 0.178689 +v 0.011911 0.033052 0.171990 +v 0.012811 0.019231 0.171990 +v -0.012687 0.019231 0.171490 +v -0.013287 0.033052 0.171490 +v -0.039285 0.033052 0.033399 +v -0.038285 0.019231 0.033399 +v 0.018911 0.019231 0.151591 +v 0.017511 0.033052 0.151591 +v -0.032886 0.019231 0.138392 +v -0.020487 0.019231 0.108094 +v -0.020487 -0.019477 0.108094 +v -0.020487 -0.019477 0.067797 +v 0.021511 -0.019477 0.067797 +v 0.000512 -0.019478 0.067797 +v 0.018411 -0.032730 0.097195 +v -0.021486 -0.032732 0.067797 +v -0.033886 -0.032730 0.138392 +v -0.055484 -0.019477 0.037899 +v -0.056484 -0.032730 0.037899 +v -0.050384 -0.032730 0.028299 +v -0.049385 -0.019477 0.028299 +v 0.001112 -0.019477 0.178689 +v 0.012811 -0.019477 0.171990 +v 0.011911 -0.032730 0.171990 +v 0.000812 -0.032730 0.178689 +v -0.012687 -0.019477 0.171490 +v -0.013287 -0.032729 0.171490 +v -0.038285 -0.019477 0.033399 +v -0.039285 -0.032730 0.033399 +v 0.017511 -0.032730 0.151591 +v 0.018911 -0.019477 0.151591 +v -0.032886 -0.019477 0.138392 +v -0.006667 0.048435 0.145884 +v -0.005231 0.048435 0.142577 +v 0.011772 0.048195 0.144881 +v -0.003188 0.048435 0.150355 +v -0.010015 0.048435 0.147374 +v -0.012062 0.048435 0.152380 +v -0.013238 0.048435 0.145933 +v -0.019178 0.048435 0.146705 +v -0.014763 0.048435 0.142588 +v -0.026903 0.048435 0.130654 +v -0.026289 0.048435 0.125176 +v -0.013457 0.048435 0.139281 +v -0.010011 0.048435 0.137921 +v -0.002712 0.048435 0.125393 +v -0.006698 0.048435 0.139314 +v 0.002961 0.048435 0.127177 +v -0.028629 0.031884 0.131805 +v -0.027878 0.031884 0.114962 +v 0.001273 0.032467 0.115415 +v 0.006801 0.032467 0.119149 +v 0.017592 0.032467 0.145625 +v 0.007048 0.043949 0.146063 +v -0.005231 0.042985 0.142577 +v -0.006667 0.042985 0.145884 +v -0.003188 0.042985 0.150355 +v -0.010015 0.042985 0.147374 +v -0.012062 0.042985 0.152380 +v -0.013238 0.042985 0.145933 +v -0.019178 0.042985 0.146705 +v -0.014763 0.042985 0.142588 +v -0.024116 0.043761 0.130967 +v -0.013457 0.042985 0.139281 +v -0.023316 0.044469 0.127443 +v -0.010011 0.042985 0.137921 +v -0.006505 0.043745 0.132484 +v -0.006698 0.042985 0.139314 +v -0.002857 0.044066 0.133701 +v -0.024934 0.029264 0.118727 +v -0.023225 0.031247 0.132122 +v -0.001326 0.029956 0.132780 +v -0.003400 0.029583 0.130314 +v 0.005576 0.030228 0.145173 +v -0.006667 -0.048079 0.145884 +v -0.003188 -0.048079 0.150355 +v 0.011772 -0.047839 0.144882 +v -0.005231 -0.048079 0.142577 +v -0.010015 -0.048079 0.147374 +v -0.012062 -0.048079 0.152380 +v -0.013238 -0.048079 0.145933 +v -0.019178 -0.048079 0.146705 +v -0.014763 -0.048079 0.142588 +v -0.026903 -0.048079 0.130654 +v -0.026289 -0.048079 0.125176 +v -0.013457 -0.048079 0.139281 +v -0.010011 -0.048079 0.137921 +v -0.002712 -0.048079 0.125393 +v -0.006698 -0.048079 0.139314 +v 0.002961 -0.048079 0.127177 +v -0.028629 -0.031528 0.131805 +v -0.027878 -0.031528 0.114962 +v 0.001273 -0.032112 0.115415 +v 0.006801 -0.032112 0.119149 +v 0.017592 -0.032112 0.145625 +v 0.007048 -0.043593 0.146063 +v -0.003188 -0.042629 0.150355 +v -0.006667 -0.042629 0.145884 +v -0.005231 -0.042629 0.142577 +v -0.012062 -0.042629 0.152380 +v -0.010015 -0.042629 0.147374 +v -0.019178 -0.042629 0.146705 +v -0.013238 -0.042629 0.145933 +v -0.024116 -0.043405 0.130967 +v -0.014763 -0.042629 0.142588 +v -0.023316 -0.044113 0.127443 +v -0.013457 -0.042629 0.139281 +v -0.006505 -0.043389 0.132484 +v -0.010011 -0.042629 0.137921 +v -0.002857 -0.043710 0.133701 +v -0.006698 -0.042629 0.139314 +v -0.023225 -0.030891 0.132122 +v -0.024934 -0.028908 0.118727 +v -0.003400 -0.029228 0.130314 +v -0.001326 -0.029601 0.132780 +v 0.005576 -0.029872 0.145173 +# 132 vertices, 0 vertices normals + +f 4 3 2 +f 2 1 4 +f 2 6 5 +f 9 8 7 +f 13 12 11 +f 11 10 13 +f 7 5 14 +f 7 8 2 +f 2 5 7 +f 8 1 2 +f 18 17 16 +f 16 15 18 +f 15 16 20 +f 20 19 15 +f 22 21 7 +f 7 14 22 +f 20 16 17 +f 24 23 1 +f 1 8 24 +f 18 15 19 +f 17 18 23 +f 23 24 17 +f 18 19 23 +f 19 20 9 +f 9 25 19 +f 26 1 23 +f 23 25 26 +f 19 25 23 +f 20 17 24 +f 24 8 9 +f 24 9 20 +f 13 10 25 +f 25 9 13 +f 11 22 14 +f 14 10 11 +f 11 12 21 +f 21 22 11 +f 9 7 13 +f 12 13 7 +f 7 21 12 +f 26 25 10 +f 10 14 26 +f 28 27 26 +f 26 14 28 +f 2 3 29 +f 29 6 2 +f 27 4 1 +f 1 26 27 +f 29 3 30 +f 33 32 31 +f 37 36 35 +f 35 34 37 +f 30 32 28 +f 3 31 32 +f 32 30 3 +f 4 31 3 +f 41 40 39 +f 39 38 41 +f 43 41 38 +f 38 42 43 +f 32 45 44 +f 44 28 32 +f 41 43 40 +f 4 47 46 +f 46 31 4 +f 38 39 42 +f 47 39 40 +f 40 46 47 +f 42 39 47 +f 33 43 42 +f 42 48 33 +f 4 27 47 +f 48 47 27 +f 48 42 47 +f 40 43 46 +f 31 46 33 +f 33 46 43 +f 48 34 35 +f 35 33 48 +f 28 44 37 +f 37 34 28 +f 45 36 37 +f 37 44 45 +f 32 33 35 +f 32 35 36 +f 36 45 32 +f 34 48 27 +f 27 28 34 +f 6 29 14 +f 14 5 6 +f 30 28 14 +f 14 29 30 +f 52 51 50 +f 50 49 52 +f 54 52 49 +f 49 53 54 +f 56 54 53 +f 53 55 56 +f 58 56 55 +f 55 57 58 +f 58 57 60 +f 60 59 58 +f 62 59 60 +f 60 61 62 +f 64 62 61 +f 61 63 64 +f 51 64 63 +f 63 50 51 +f 58 59 66 +f 66 65 58 +f 62 64 68 +f 68 67 62 +f 64 51 69 +f 69 68 64 +f 59 62 67 +f 67 66 59 +f 73 72 71 +f 71 70 73 +f 75 74 72 +f 72 73 75 +f 77 76 74 +f 74 75 77 +f 79 78 76 +f 76 77 79 +f 79 81 80 +f 80 78 79 +f 83 82 80 +f 80 81 83 +f 85 84 82 +f 82 83 85 +f 70 71 84 +f 84 85 70 +f 79 87 86 +f 86 81 79 +f 83 89 88 +f 88 85 83 +f 85 88 90 +f 90 70 85 +f 81 86 89 +f 89 83 81 +f 51 52 73 +f 73 70 51 +f 49 50 71 +f 71 72 49 +f 52 54 75 +f 75 73 52 +f 53 49 72 +f 72 74 53 +f 54 56 77 +f 77 75 54 +f 55 53 74 +f 74 76 55 +f 56 58 79 +f 79 77 56 +f 57 55 76 +f 76 78 57 +f 60 57 78 +f 78 80 60 +f 61 60 80 +f 80 82 61 +f 63 61 82 +f 82 84 63 +f 50 63 84 +f 84 71 50 +f 58 65 87 +f 87 79 58 +f 69 51 70 +f 70 90 69 +f 94 93 92 +f 92 91 94 +f 91 92 96 +f 96 95 91 +f 95 96 98 +f 98 97 95 +f 97 98 100 +f 100 99 97 +f 102 99 100 +f 100 101 102 +f 102 101 104 +f 104 103 102 +f 103 104 106 +f 106 105 103 +f 105 106 93 +f 93 94 105 +f 108 101 100 +f 100 107 108 +f 110 106 104 +f 104 109 110 +f 111 93 106 +f 106 110 111 +f 109 104 101 +f 101 108 109 +f 115 114 113 +f 113 112 115 +f 114 117 116 +f 116 113 114 +f 117 119 118 +f 118 116 117 +f 119 121 120 +f 120 118 119 +f 123 122 120 +f 120 121 123 +f 123 125 124 +f 124 122 123 +f 125 127 126 +f 126 124 125 +f 127 115 112 +f 112 126 127 +f 129 128 120 +f 120 122 129 +f 131 130 124 +f 124 126 131 +f 132 131 126 +f 126 112 132 +f 130 129 122 +f 122 124 130 +f 113 92 93 +f 93 112 113 +f 115 94 91 +f 91 114 115 +f 116 96 92 +f 92 113 116 +f 114 91 95 +f 95 117 114 +f 118 98 96 +f 96 116 118 +f 117 95 97 +f 97 119 117 +f 120 100 98 +f 98 118 120 +f 119 97 99 +f 99 121 119 +f 121 99 102 +f 102 123 121 +f 123 102 103 +f 103 125 123 +f 125 103 105 +f 105 127 125 +f 127 105 94 +f 94 115 127 +f 128 107 100 +f 100 120 128 +f 112 93 111 +f 111 132 112 +# 244 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/mtorso.obj b/examples/Atlas/urdf/mesh/mtorso.obj new file mode 100644 index 0000000..9349ad8 --- /dev/null +++ b/examples/Atlas/urdf/mesh/mtorso.obj @@ -0,0 +1,144 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object mtorso.obj +# +# Vertices: 44 +# Faces: 84 +# +#### +v 0.016322 0.016854 0.046284 +v 0.016322 0.012976 0.034330 +v 0.016322 -0.012943 0.034330 +v 0.016322 -0.013486 0.061191 +v 0.016322 -0.016821 0.046284 +v 0.016322 0.000017 0.067825 +v 0.016322 0.013520 0.061191 +v 0.016322 0.012976 -0.005051 +v 0.016322 -0.012943 -0.005051 +v 0.007387 0.012976 -0.015609 +v 0.007387 -0.012943 -0.015609 +v -0.034914 0.012976 -0.020318 +v -0.034914 -0.012943 -0.020318 +v -0.043792 0.012976 -0.014262 +v -0.043792 -0.012943 -0.014262 +v -0.064841 0.012976 0.038335 +v -0.064841 -0.012943 0.038335 +v -0.067420 0.015713 0.050005 +v -0.067420 -0.015680 0.050005 +v -0.067084 0.008774 0.076512 +v -0.067084 -0.008741 0.076512 +v -0.067074 0.003724 0.080885 +v -0.067074 -0.003690 0.080885 +v -0.024413 -0.012943 0.021958 +v -0.033959 -0.012943 0.029889 +v -0.033959 0.012976 0.029889 +v -0.024413 0.012976 0.021958 +v -0.034001 -0.015680 0.045840 +v -0.034001 0.015713 0.050005 +v -0.033665 -0.008741 0.076512 +v -0.033665 0.008774 0.076512 +v -0.033656 -0.003690 0.080885 +v -0.033656 0.003724 0.080885 +v 0.005997 -0.013486 0.061191 +v 0.005997 -0.016821 0.046284 +v 0.005997 -0.012943 0.034330 +v 0.005997 0.016854 0.046284 +v 0.005997 0.012976 0.034330 +v 0.005997 0.000017 0.067825 +v 0.005997 0.013521 0.061191 +v 0.005997 -0.012943 0.031540 +v 0.005997 0.012976 0.031540 +v -0.002938 -0.012943 0.021807 +v -0.002938 0.012976 0.021807 +# 44 vertices, 0 vertices normals + +f 4 3 2 +f 2 1 4 +f 4 5 3 +f 7 6 4 +f 4 1 7 +f 9 8 2 +f 2 3 9 +f 11 10 8 +f 8 9 11 +f 13 12 10 +f 10 11 13 +f 15 14 12 +f 12 13 15 +f 17 16 14 +f 14 15 17 +f 19 18 16 +f 16 17 19 +f 21 20 18 +f 18 19 21 +f 23 22 20 +f 20 21 23 +f 27 26 25 +f 25 24 27 +f 26 29 28 +f 28 25 26 +f 29 31 30 +f 30 28 29 +f 31 33 32 +f 32 30 31 +f 37 36 35 +f 35 34 37 +f 37 38 36 +f 40 37 34 +f 34 39 40 +f 38 42 41 +f 41 36 38 +f 42 44 43 +f 43 41 42 +f 33 22 23 +f 23 32 33 +f 44 27 24 +f 24 43 44 +f 4 34 35 +f 35 5 4 +f 5 35 36 +f 36 3 5 +f 41 43 9 +f 9 3 41 +f 43 24 13 +f 13 11 43 +f 13 24 25 +f 25 15 13 +f 15 25 28 +f 28 17 15 +f 28 30 21 +f 21 19 28 +f 6 39 34 +f 34 4 6 +f 7 40 39 +f 39 6 7 +f 1 37 40 +f 40 7 1 +f 2 38 37 +f 37 1 2 +f 8 44 42 +f 42 2 8 +f 12 27 44 +f 44 10 12 +f 26 27 14 +f 14 16 26 +f 31 29 18 +f 18 20 31 +f 22 33 31 +f 31 20 22 +f 10 44 8 +f 9 43 11 +f 14 27 12 +f 18 29 26 +f 26 16 18 +f 17 28 19 +f 23 21 30 +f 30 32 23 +f 41 3 36 +f 38 2 42 +# 84 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/pelvis.obj b/examples/Atlas/urdf/mesh/pelvis.obj new file mode 100644 index 0000000..175a37f --- /dev/null +++ b/examples/Atlas/urdf/mesh/pelvis.obj @@ -0,0 +1,3168 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object pelvis.obj +# +# Vertices: 1174 +# Faces: 1978 +# +#### +v -0.004260 0.109649 0.012912 +v 0.011414 0.106175 0.012912 +v 0.011414 0.106175 0.047070 +v -0.004260 0.109649 0.047070 +v -0.017800 0.101024 0.012912 +v -0.017800 0.101024 0.047070 +v -0.021275 0.085350 0.012912 +v -0.021275 0.085350 0.047070 +v -0.012649 0.071810 0.012912 +v -0.012649 0.071810 0.047070 +v 0.003025 0.068335 0.012912 +v 0.003025 0.068335 0.047070 +v 0.016565 0.076961 0.012912 +v 0.016565 0.076961 0.047070 +v 0.007693 0.100860 0.012912 +v 0.013651 0.091508 0.012912 +v 0.020040 0.092634 0.012912 +v -0.003133 0.103260 0.012912 +v -0.012485 0.097302 0.012912 +v -0.014885 0.086476 0.012912 +v -0.008927 0.077124 0.012912 +v 0.001899 0.074724 0.012912 +v 0.011251 0.080682 0.012912 +v 0.020040 0.092634 0.047070 +v 0.013651 0.091508 0.047070 +v 0.007693 0.100860 0.047070 +v -0.003133 0.103260 0.047070 +v -0.012485 0.097302 0.047070 +v -0.014885 0.086476 0.047070 +v -0.008927 0.077124 0.047070 +v 0.001899 0.074724 0.047070 +v 0.011251 0.080682 0.047070 +v -0.019179 0.046417 0.013116 +v -0.023338 0.052946 0.013116 +v -0.023338 0.052946 0.025026 +v -0.019179 0.046417 0.025026 +v -0.011621 0.044742 0.013116 +v -0.011621 0.044742 0.025026 +v -0.005092 0.048901 0.013116 +v -0.005092 0.048901 0.025026 +v -0.003417 0.056459 0.013116 +v -0.003417 0.056459 0.025026 +v -0.007576 0.062988 0.013116 +v -0.011121 0.057925 0.013116 +v -0.009502 0.055386 0.013116 +v -0.015134 0.064663 0.013116 +v -0.014060 0.058577 0.013116 +v -0.021662 0.060504 0.013116 +v -0.016600 0.056959 0.013116 +v -0.017252 0.054019 0.013116 +v -0.015634 0.051479 0.013116 +v -0.012694 0.050828 0.013116 +v -0.010154 0.052446 0.013116 +v -0.003417 0.056459 0.047207 +v -0.009502 0.055386 0.047207 +v -0.011121 0.057925 0.047207 +v -0.007576 0.062988 0.047207 +v -0.014060 0.058577 0.047207 +v -0.015134 0.064663 0.047207 +v -0.016600 0.056959 0.047207 +v -0.021662 0.060504 0.047207 +v -0.017252 0.054019 0.047207 +v -0.023338 0.052946 0.047207 +v -0.015634 0.051479 0.047207 +v -0.019179 0.046417 0.047207 +v -0.012694 0.050828 0.047207 +v -0.011621 0.044742 0.047207 +v -0.010154 0.052446 0.047207 +v -0.005092 0.048901 0.047207 +v -0.019179 0.046417 0.039006 +v -0.023338 0.052946 0.039006 +v -0.011621 0.044742 0.039006 +v -0.005092 0.048901 0.039006 +v -0.003417 0.056459 0.039006 +v -0.009134 0.055451 0.025026 +v -0.010906 0.058232 0.025026 +v -0.007576 0.062988 0.025026 +v -0.014125 0.058945 0.025026 +v -0.015134 0.064663 0.025026 +v -0.016907 0.057174 0.025026 +v -0.021662 0.060504 0.025026 +v -0.017620 0.053954 0.025026 +v -0.015848 0.051173 0.025026 +v -0.012629 0.050459 0.025026 +v -0.009848 0.052231 0.025026 +v -0.007576 0.062988 0.039006 +v -0.010906 0.058232 0.039006 +v -0.009134 0.055451 0.039006 +v -0.015134 0.064663 0.039006 +v -0.014125 0.058945 0.039006 +v -0.021662 0.060504 0.039006 +v -0.016907 0.057174 0.039006 +v -0.017620 0.053954 0.039006 +v -0.015848 0.051173 0.039006 +v -0.012629 0.050459 0.039006 +v -0.009848 0.052231 0.039006 +v 0.004212 0.071177 0.013116 +v -0.002899 0.071368 0.013116 +v -0.002899 0.071368 0.025026 +v 0.004212 0.071177 0.025026 +v -0.016500 0.073382 0.013116 +v -0.016500 0.073382 0.025026 +v -0.028560 0.073336 0.013116 +v -0.028560 0.073336 0.025026 +v -0.031655 0.073252 0.013116 +v -0.031655 0.073252 0.025026 +v -0.002899 0.071368 0.047207 +v 0.004212 0.071177 0.047207 +v -0.016500 0.073382 0.047207 +v -0.028560 0.073336 0.047207 +v -0.031655 0.073252 0.047207 +v 0.004212 0.071177 0.039006 +v -0.002899 0.071368 0.039006 +v -0.016500 0.073382 0.039006 +v -0.028560 0.073336 0.039006 +v -0.031655 0.073252 0.039006 +v 0.039383 0.092521 0.012912 +v 0.039365 0.103904 0.012912 +v 0.039376 0.079344 0.012912 +v 0.039365 0.103904 0.047070 +v 0.039376 0.079344 0.047070 +v 0.039383 0.092521 0.047070 +v -0.040586 -0.038236 -0.125090 +v -0.040586 0.038958 -0.125090 +v -0.049085 0.042758 -0.128690 +v -0.049085 -0.042036 -0.128690 +v -0.049385 -0.044336 -0.125590 +v -0.040786 -0.040536 -0.122091 +v -0.051685 -0.042936 -0.119191 +v -0.044586 -0.039736 -0.116191 +v -0.031787 -0.021138 -0.121491 +v -0.031787 0.021959 -0.121491 +v -0.092783 0.062357 -0.146689 +v -0.092783 -0.061635 -0.146689 +v -0.049385 0.045058 -0.125590 +v -0.040786 0.041258 -0.122091 +v -0.051685 0.043658 -0.119191 +v -0.044586 0.040458 -0.116191 +v -0.128180 0.071856 -0.144489 +v -0.128180 -0.071135 -0.144489 +v -0.153979 0.000361 -0.107092 +v -0.153979 0.059157 -0.100592 +v -0.153979 0.020459 -0.097692 +v -0.153979 -0.019738 -0.097692 +v -0.153979 -0.058435 -0.100592 +v -0.050485 0.041958 -0.126090 +v -0.041986 0.038058 -0.122590 +v -0.041986 -0.037337 -0.122590 +v -0.050485 -0.041237 -0.126090 +v -0.042186 -0.037837 -0.121691 +v -0.050685 -0.041637 -0.125190 +v -0.045386 -0.036937 -0.117091 +v -0.052585 -0.040137 -0.120091 +v -0.032887 -0.021138 -0.118691 +v -0.032887 0.021959 -0.118691 +v -0.093083 0.062357 -0.143689 +v -0.093083 -0.061635 -0.143689 +v -0.050685 0.042358 -0.125190 +v -0.042186 0.038558 -0.121691 +v -0.052585 0.040958 -0.120091 +v -0.045386 0.037658 -0.117091 +v -0.126680 -0.071034 -0.141889 +v -0.126680 0.071756 -0.141889 +v -0.151279 0.000361 -0.105692 +v -0.150979 0.020459 -0.097692 +v -0.151279 0.058957 -0.099292 +v -0.151279 -0.058235 -0.099292 +v -0.150979 -0.019738 -0.097692 +v -0.027687 -0.174128 0.116494 +v 0.048108 -0.174128 0.116494 +v 0.048108 -0.179627 0.119593 +v -0.027687 -0.179627 0.119593 +v -0.027687 -0.174128 0.110094 +v 0.048108 -0.174128 0.110094 +v -0.027687 -0.185127 0.116494 +v 0.048108 -0.185127 0.116494 +v 0.048108 -0.185127 0.110094 +v -0.027687 -0.185127 0.110094 +v 0.066607 -0.167928 0.116494 +v 0.069907 -0.172328 0.119593 +v 0.066607 -0.167928 0.110094 +v 0.048108 -0.179627 0.106894 +v 0.069907 -0.172328 0.106894 +v 0.073206 -0.176728 0.110094 +v 0.073206 -0.176728 0.116494 +v 0.148501 -0.106032 0.116494 +v 0.151801 -0.110432 0.119593 +v 0.148501 -0.106032 0.110094 +v 0.151801 -0.110432 0.106894 +v 0.155101 -0.114831 0.110094 +v 0.155101 -0.114831 0.116494 +v 0.160900 -0.081634 0.116494 +v 0.166400 -0.081734 0.119593 +v 0.160900 -0.081634 0.110094 +v 0.166400 -0.081734 0.106894 +v 0.171900 -0.081734 0.110094 +v 0.171900 -0.081734 0.116494 +v 0.171900 0.082455 0.110094 +v 0.166400 0.082455 0.106894 +v 0.171900 0.082455 0.116494 +v 0.048108 0.174849 0.116494 +v -0.027687 0.174849 0.116494 +v -0.027687 0.180349 0.119593 +v 0.048108 0.180349 0.119593 +v 0.048108 0.174849 0.110094 +v 0.048108 0.180349 0.106894 +v -0.027687 0.180349 0.106894 +v -0.027687 0.174849 0.110094 +v 0.048108 0.185848 0.110094 +v -0.027687 0.185848 0.110094 +v 0.048108 0.185848 0.116494 +v -0.027687 0.185848 0.116494 +v 0.069907 0.173049 0.119593 +v 0.066607 0.168649 0.116494 +v 0.066607 0.168649 0.110094 +v 0.069907 0.173049 0.106894 +v 0.073206 0.177449 0.110094 +v 0.073206 0.177449 0.116494 +v 0.151801 0.111153 0.119593 +v 0.148501 0.106754 0.116494 +v 0.148501 0.106754 0.110094 +v 0.151801 0.111153 0.106894 +v 0.155101 0.115553 0.110094 +v 0.155101 0.115553 0.116494 +v 0.166400 0.082455 0.119593 +v 0.160900 0.082355 0.116494 +v 0.160900 0.082355 0.110094 +v -0.027687 -0.179627 0.106894 +v -0.049486 -0.172328 0.119593 +v -0.046186 -0.167928 0.116494 +v -0.046186 -0.167928 0.110094 +v -0.049486 -0.172328 0.106894 +v -0.052785 -0.176728 0.110094 +v -0.052785 -0.176728 0.116494 +v -0.131380 -0.110432 0.119593 +v -0.128080 -0.106032 0.116494 +v -0.128080 -0.106032 0.110094 +v -0.131380 -0.110432 0.106894 +v -0.134680 -0.114831 0.110094 +v -0.134680 -0.114831 0.116494 +v -0.145979 -0.081734 0.119593 +v -0.140479 -0.081634 0.116494 +v -0.140479 -0.081634 0.110094 +v -0.145979 -0.081734 0.106894 +v -0.151479 -0.081734 0.110094 +v -0.151479 -0.081734 0.116494 +v -0.145979 0.082455 0.106894 +v -0.151479 0.082455 0.110094 +v -0.151479 0.082455 0.116494 +v -0.046186 0.168649 0.116494 +v -0.049486 0.173049 0.119593 +v -0.046186 0.168649 0.110094 +v -0.049486 0.173049 0.106894 +v -0.052785 0.177449 0.110094 +v -0.052785 0.177449 0.116494 +v -0.128080 0.106754 0.116494 +v -0.131380 0.111153 0.119593 +v -0.128080 0.106754 0.110094 +v -0.131380 0.111153 0.106894 +v -0.134680 0.115553 0.110094 +v -0.134680 0.115553 0.116494 +v -0.140479 0.082355 0.116494 +v -0.145979 0.082455 0.119593 +v -0.140479 0.082355 0.110094 +v 0.068307 0.166550 0.111894 +v 0.062507 0.170749 0.109694 +v 0.066807 0.167549 0.114194 +v 0.075506 0.176649 0.110594 +v 0.074106 0.177849 0.113594 +v 0.068906 0.179949 0.109294 +v 0.060907 0.170349 0.072596 +v 0.057207 0.171649 0.068497 +v 0.054208 0.174049 0.073096 +v 0.066207 0.180749 0.071996 +v 0.059207 0.183248 0.072496 +v 0.061707 0.183348 0.068397 +v 0.067207 0.173349 0.076296 +v 0.074106 0.170449 0.107694 +v 0.055807 0.179249 0.075196 +v 0.062107 0.177649 0.106194 +v 0.144702 0.108654 0.111494 +v 0.139102 0.113253 0.109494 +v 0.143302 0.109653 0.113794 +v 0.152401 0.117853 0.110394 +v 0.151201 0.119053 0.113494 +v 0.146901 0.122453 0.109194 +v 0.134502 0.116053 0.071197 +v 0.131602 0.117753 0.068597 +v 0.128803 0.120853 0.071996 +v 0.142302 0.125352 0.070896 +v 0.136602 0.130152 0.071596 +v 0.139502 0.127152 0.068297 +v 0.142202 0.117653 0.074896 +v 0.150601 0.112953 0.107394 +v 0.132702 0.125952 0.074196 +v 0.139902 0.120253 0.106194 +v -0.048285 0.166550 0.111894 +v -0.046786 0.167549 0.114194 +v -0.042486 0.170749 0.109694 +v -0.055485 0.176649 0.110594 +v -0.048885 0.179949 0.109294 +v -0.054085 0.177849 0.113594 +v -0.040886 0.170349 0.072596 +v -0.034186 0.174049 0.073096 +v -0.037086 0.171649 0.068497 +v -0.046186 0.180749 0.071996 +v -0.041686 0.183348 0.068397 +v -0.039086 0.183248 0.072496 +v -0.047186 0.173349 0.076296 +v -0.054085 0.170449 0.107694 +v -0.035786 0.179249 0.075196 +v -0.042086 0.177649 0.106194 +v -0.124680 0.108654 0.111494 +v -0.123281 0.109653 0.113794 +v -0.119081 0.113253 0.109494 +v -0.132380 0.117853 0.110394 +v -0.126780 0.122453 0.109194 +v -0.131080 0.119053 0.113494 +v -0.114481 0.116053 0.071197 +v -0.108781 0.120853 0.071996 +v -0.111581 0.117753 0.068597 +v -0.122181 0.125352 0.070896 +v -0.119481 0.127152 0.068297 +v -0.116481 0.130152 0.071597 +v -0.122181 0.117653 0.074896 +v -0.130480 0.112953 0.107394 +v -0.112581 0.125952 0.074196 +v -0.119881 0.120253 0.106194 +v -0.048285 -0.165828 0.111894 +v -0.042486 -0.170028 0.109694 +v -0.046786 -0.166828 0.114194 +v -0.055485 -0.175928 0.110594 +v -0.054085 -0.177127 0.113594 +v -0.048885 -0.179227 0.109294 +v -0.040886 -0.169628 0.072596 +v -0.037086 -0.170928 0.068497 +v -0.034186 -0.173328 0.073096 +v -0.046186 -0.180027 0.071996 +v -0.039086 -0.182527 0.072496 +v -0.041686 -0.182627 0.068397 +v -0.047185 -0.172628 0.076296 +v -0.054085 -0.169728 0.107694 +v -0.035786 -0.178527 0.075196 +v -0.042086 -0.176928 0.106194 +v -0.124680 -0.107932 0.111494 +v -0.119081 -0.112532 0.109494 +v -0.123281 -0.108932 0.113794 +v -0.132380 -0.117131 0.110394 +v -0.131080 -0.118331 0.113494 +v -0.126780 -0.121731 0.109194 +v -0.114481 -0.115331 0.071197 +v -0.111581 -0.117031 0.068597 +v -0.108781 -0.120131 0.071996 +v -0.122181 -0.124631 0.070896 +v -0.116481 -0.129431 0.071597 +v -0.119481 -0.126431 0.068297 +v -0.122181 -0.116932 0.074896 +v -0.130480 -0.112232 0.107394 +v -0.112581 -0.125231 0.074196 +v -0.119881 -0.119531 0.106194 +v 0.068307 -0.165828 0.111894 +v 0.066807 -0.166828 0.114194 +v 0.062507 -0.170028 0.109694 +v 0.075506 -0.175928 0.110594 +v 0.068907 -0.179227 0.109294 +v 0.074106 -0.177127 0.113594 +v 0.060907 -0.169628 0.072596 +v 0.054208 -0.173328 0.073096 +v 0.057207 -0.170928 0.068497 +v 0.066207 -0.180027 0.071996 +v 0.061707 -0.182627 0.068397 +v 0.059207 -0.182527 0.072496 +v 0.067207 -0.172628 0.076296 +v 0.074106 -0.169728 0.107694 +v 0.055807 -0.178527 0.075196 +v 0.062107 -0.176928 0.106194 +v 0.144702 -0.107932 0.111494 +v 0.143302 -0.108932 0.113794 +v 0.139102 -0.112532 0.109494 +v 0.152401 -0.117131 0.110394 +v 0.146901 -0.121731 0.109194 +v 0.151201 -0.118331 0.113494 +v 0.134502 -0.115331 0.071197 +v 0.128803 -0.120131 0.071996 +v 0.131602 -0.117031 0.068597 +v 0.142302 -0.124631 0.070896 +v 0.139502 -0.126431 0.068297 +v 0.136602 -0.129431 0.071596 +v 0.142202 -0.116932 0.074896 +v 0.150601 -0.112232 0.107394 +v 0.132702 -0.125231 0.074196 +v 0.139902 -0.119531 0.106194 +v -0.113681 0.058657 -0.144889 +v -0.118581 0.053957 -0.140789 +v -0.118581 -0.056635 -0.140789 +v -0.113681 -0.061335 -0.144889 +v -0.117481 0.053957 -0.134490 +v -0.117481 -0.056635 -0.134490 +v -0.111481 0.058657 -0.132290 +v -0.111481 -0.061335 -0.132290 +v -0.106582 0.051257 -0.136489 +v -0.106582 -0.053936 -0.136489 +v -0.107682 0.051257 -0.142789 +v -0.107682 -0.053936 -0.142789 +v -0.139380 0.060357 -0.104592 +v -0.142579 0.056357 -0.110091 +v -0.142579 -0.055636 -0.110091 +v -0.139380 -0.059635 -0.104592 +v -0.148979 0.056357 -0.110091 +v -0.148979 -0.055636 -0.110091 +v -0.152179 0.060357 -0.104592 +v -0.152179 -0.059635 -0.104592 +v -0.148979 0.052957 -0.099092 +v -0.148979 -0.052236 -0.099092 +v -0.142579 0.052957 -0.099092 +v -0.142579 -0.052236 -0.099092 +v -0.090279 0.053526 -0.093192 +v -0.090279 0.053526 -0.088293 +v -0.127970 0.037967 -0.088293 +v -0.127970 0.037967 -0.093192 +v -0.143639 0.000276 -0.088293 +v -0.143639 0.000276 -0.093192 +v -0.127970 -0.037415 -0.088293 +v -0.127970 -0.037415 -0.093192 +v -0.090279 -0.052973 -0.088293 +v -0.090279 -0.052973 -0.093192 +v -0.052698 -0.037415 -0.088293 +v -0.052698 -0.037415 -0.093192 +v -0.037030 0.000276 -0.088293 +v -0.037030 0.000276 -0.093192 +v -0.052698 0.037967 -0.088293 +v -0.052698 0.037967 -0.093192 +v -0.090279 0.048814 -0.085893 +v -0.124683 0.034680 -0.085893 +v -0.138927 0.000276 -0.085893 +v -0.124683 -0.034128 -0.085893 +v -0.090279 -0.048262 -0.085893 +v -0.055985 -0.034128 -0.085893 +v -0.041741 0.000276 -0.085893 +v -0.055985 0.034680 -0.085893 +v -0.090279 0.048814 -0.011998 +v -0.124683 0.034680 -0.011998 +v -0.138927 0.000276 -0.011998 +v -0.124683 -0.034128 -0.011998 +v -0.090279 -0.048262 -0.011998 +v -0.055985 -0.034128 -0.011998 +v -0.041741 0.000276 -0.011998 +v -0.055985 0.034680 -0.011998 +v -0.011988 0.013760 -0.013998 +v -0.011988 0.013760 0.054598 +v -0.023587 0.007060 0.054598 +v -0.023587 0.007060 -0.013998 +v -0.023587 -0.006339 0.054598 +v -0.023587 -0.006339 -0.013998 +v -0.011988 -0.013038 0.054598 +v -0.011988 -0.013038 -0.013998 +v -0.000489 -0.006339 0.054598 +v -0.000489 -0.006339 -0.013998 +v -0.000489 0.007060 0.054598 +v -0.000489 0.007060 -0.013998 +v 0.159400 -0.003539 -0.014498 +v 0.159400 -0.003539 0.113294 +v 0.166200 -0.007539 0.106994 +v 0.166200 -0.007539 -0.014498 +v 0.159400 0.004260 -0.014498 +v 0.159400 0.004360 0.113294 +v 0.166200 0.008260 -0.014498 +v 0.166200 0.008260 0.106994 +v 0.173000 0.004260 -0.014498 +v 0.173000 0.004260 0.113294 +v 0.173000 -0.003539 -0.014498 +v 0.173000 -0.003539 0.113294 +v 0.151001 -0.007539 -0.070294 +v 0.144402 -0.003539 -0.068494 +v 0.144402 0.004360 -0.068494 +v 0.151001 0.008260 -0.070294 +v 0.157601 0.004260 -0.071994 +v 0.157601 -0.003539 -0.071994 +v 0.138102 -0.007539 -0.091493 +v 0.133302 -0.003539 -0.086593 +v 0.133302 0.004360 -0.086593 +v 0.138102 0.008260 -0.091493 +v 0.143002 0.004260 -0.096292 +v 0.143002 -0.003539 -0.096292 +v 0.106004 -0.007539 -0.104692 +v 0.106004 -0.003539 -0.097792 +v 0.106004 0.004360 -0.097792 +v 0.106004 0.008260 -0.104692 +v 0.106004 0.004360 -0.111491 +v 0.106004 -0.003539 -0.111491 +v -0.145479 -0.010539 -0.104692 +v -0.138879 -0.005039 -0.097992 +v -0.138879 0.005760 -0.097992 +v -0.145479 0.011260 -0.104692 +v -0.152179 0.005760 -0.111291 +v -0.152179 -0.005039 -0.111291 +v -0.145479 -0.010539 0.106694 +v -0.138879 -0.005039 0.113394 +v -0.138879 0.005760 0.113394 +v -0.145479 0.011260 0.106694 +v -0.152179 0.005760 0.113394 +v -0.152179 -0.005039 0.113394 +v 0.171400 0.025159 -0.000599 +v 0.172400 0.073856 0.110994 +v 0.166200 0.076156 0.107694 +v 0.165900 0.028259 -0.000599 +v 0.160600 0.073856 0.110994 +v 0.160400 0.025159 -0.000599 +v 0.160600 0.067056 0.109794 +v 0.160400 0.018760 -0.000599 +v 0.166200 0.063257 0.107194 +v 0.165900 0.015660 -0.000599 +v 0.172400 0.067056 0.109794 +v 0.171400 0.018760 -0.000599 +v 0.172900 0.072456 0.113294 +v 0.160400 0.072456 0.113294 +v 0.171400 -0.024437 -0.000599 +v 0.165900 -0.027537 -0.000599 +v 0.166200 -0.075434 0.107694 +v 0.172400 -0.073134 0.110994 +v 0.160400 -0.024437 -0.000599 +v 0.160600 -0.073134 0.110994 +v 0.160400 -0.018038 -0.000599 +v 0.160600 -0.066335 0.109794 +v 0.165900 -0.014838 -0.000599 +v 0.166200 -0.062535 0.107194 +v 0.171400 -0.018038 -0.000599 +v 0.172400 -0.066335 0.109794 +v 0.172900 -0.071734 0.113294 +v 0.160400 -0.071734 0.113294 +v 0.148601 -0.007339 -0.079593 +v 0.139002 -0.007139 -0.089093 +v 0.153401 -0.007139 -0.056095 +v 0.139002 0.000361 -0.074994 +v 0.133502 0.000361 -0.083493 +v 0.133502 -0.004539 -0.086893 +v 0.139002 0.007860 -0.089093 +v 0.148601 0.008060 -0.079593 +v 0.153401 0.007860 -0.056095 +v 0.133502 0.005260 -0.086893 +v 0.012610 0.186748 0.068297 +v 0.048308 0.186748 0.068297 +v 0.048308 0.183548 0.073796 +v 0.012610 0.183548 0.073796 +v 0.048308 0.177149 0.073796 +v 0.012610 0.177149 0.073796 +v 0.048308 0.174049 0.068297 +v 0.012610 0.174049 0.068297 +v 0.048308 0.177149 0.062797 +v 0.012610 0.177149 0.062797 +v 0.048308 0.183548 0.062797 +v 0.012610 0.183548 0.062797 +v 0.073906 0.178149 0.068297 +v 0.072006 0.175649 0.073796 +v 0.068107 0.170549 0.073796 +v 0.066207 0.167949 0.068297 +v 0.068106 0.170549 0.062797 +v 0.072006 0.175649 0.062797 +v 0.137302 0.125852 0.073796 +v 0.139202 0.128452 0.068297 +v 0.133502 0.120853 0.073796 +v 0.131602 0.118253 0.068297 +v 0.133502 0.120853 0.062797 +v 0.137302 0.125852 0.062797 +v 0.153501 0.097254 0.065197 +v 0.156601 0.100754 0.060797 +v 0.147401 0.095954 0.064397 +v 0.144302 0.098054 0.059297 +v 0.147401 0.101454 0.054898 +v 0.153501 0.102854 0.055698 +v 0.168300 0.044658 0.036099 +v 0.171400 0.035058 0.023600 +v 0.162100 0.043358 0.035299 +v 0.159001 0.032359 0.022100 +v 0.162100 0.036958 0.018500 +v 0.168300 0.038258 0.019300 +v 0.012610 -0.186027 0.068297 +v 0.012610 -0.182827 0.073796 +v 0.048308 -0.182827 0.073796 +v 0.048308 -0.186027 0.068297 +v 0.012610 -0.176427 0.073796 +v 0.048308 -0.176427 0.073796 +v 0.012610 -0.173328 0.068297 +v 0.048308 -0.173328 0.068297 +v 0.012610 -0.176427 0.062797 +v 0.048308 -0.176427 0.062797 +v 0.012610 -0.182827 0.062797 +v 0.048308 -0.182827 0.062797 +v 0.072006 -0.174928 0.073796 +v 0.073906 -0.177428 0.068297 +v 0.068107 -0.169828 0.073796 +v 0.066207 -0.167228 0.068297 +v 0.068107 -0.169828 0.062797 +v 0.072006 -0.174928 0.062797 +v 0.137302 -0.125131 0.073796 +v 0.139202 -0.127731 0.068297 +v 0.133502 -0.120131 0.073796 +v 0.131602 -0.117531 0.068297 +v 0.133502 -0.120131 0.062797 +v 0.137302 -0.125131 0.062797 +v 0.153501 -0.096533 0.065197 +v 0.156601 -0.100033 0.060797 +v 0.147401 -0.095233 0.064397 +v 0.144302 -0.097333 0.059297 +v 0.147401 -0.100732 0.054898 +v 0.153501 -0.102132 0.055698 +v 0.168300 -0.043936 0.036099 +v 0.171400 -0.034337 0.023600 +v 0.162100 -0.042636 0.035299 +v 0.159001 -0.031637 0.022100 +v 0.162100 -0.036237 0.018500 +v 0.168300 -0.037537 0.019300 +v 0.007411 0.186748 0.068297 +v 0.007411 0.183548 0.073796 +v -0.028287 0.183548 0.073796 +v -0.028287 0.186748 0.068297 +v 0.007411 0.177149 0.073796 +v -0.028287 0.177149 0.073796 +v 0.007411 0.174049 0.068297 +v -0.028287 0.174049 0.068297 +v 0.007411 0.177149 0.062797 +v -0.028287 0.177149 0.062797 +v 0.007411 0.183548 0.062797 +v -0.028287 0.183548 0.062797 +v -0.051885 0.175649 0.073796 +v -0.053785 0.178149 0.068297 +v -0.048086 0.170549 0.073796 +v -0.046186 0.167949 0.068297 +v -0.048086 0.170549 0.062797 +v -0.051885 0.175649 0.062797 +v -0.117281 0.125852 0.073796 +v -0.119181 0.128452 0.068297 +v -0.113481 0.120853 0.073796 +v -0.111581 0.118253 0.068297 +v -0.113481 0.120853 0.062797 +v -0.117281 0.125852 0.062797 +v -0.133480 0.097254 0.065197 +v -0.136580 0.100754 0.060797 +v -0.127380 0.095954 0.064397 +v -0.124280 0.098054 0.059297 +v -0.127380 0.101454 0.054898 +v -0.133480 0.102854 0.055698 +v -0.148279 0.043958 0.036099 +v -0.151379 0.034358 0.023600 +v -0.142079 0.042658 0.035299 +v -0.138980 0.031659 0.022100 +v -0.142079 0.036258 0.018500 +v -0.148279 0.037558 0.019300 +v 0.007411 -0.186027 0.068297 +v -0.028287 -0.186027 0.068297 +v -0.028287 -0.182827 0.073796 +v 0.007411 -0.182827 0.073796 +v -0.028287 -0.176427 0.073796 +v 0.007411 -0.176427 0.073796 +v -0.028287 -0.173328 0.068297 +v 0.007411 -0.173328 0.068297 +v -0.028287 -0.176427 0.062797 +v 0.007411 -0.176427 0.062797 +v -0.028287 -0.182827 0.062797 +v 0.007411 -0.182827 0.062797 +v -0.053785 -0.177428 0.068297 +v -0.051885 -0.174928 0.073796 +v -0.048086 -0.169828 0.073796 +v -0.046186 -0.167228 0.068297 +v -0.048086 -0.169828 0.062797 +v -0.051885 -0.174928 0.062797 +v -0.117281 -0.125131 0.073796 +v -0.119181 -0.127731 0.068297 +v -0.113481 -0.120131 0.073796 +v -0.111581 -0.117532 0.068297 +v -0.113481 -0.120131 0.062797 +v -0.117281 -0.125131 0.062797 +v -0.133480 -0.096533 0.065197 +v -0.136580 -0.100033 0.060797 +v -0.127380 -0.095233 0.064397 +v -0.124280 -0.097333 0.059297 +v -0.127380 -0.100732 0.054898 +v -0.133480 -0.102132 0.055698 +v -0.148279 -0.043236 0.036099 +v -0.151379 -0.033637 0.023600 +v -0.142079 -0.041936 0.035299 +v -0.138980 -0.030937 0.022100 +v -0.142079 -0.035537 0.018500 +v -0.148279 -0.036837 0.019300 +v -0.151479 0.025059 -0.000598 +v -0.145979 0.028159 -0.000598 +v -0.146179 0.076156 0.107694 +v -0.152379 0.073856 0.110994 +v -0.140479 0.025059 -0.000598 +v -0.140479 0.073856 0.110994 +v -0.140479 0.018659 -0.000598 +v -0.140479 0.067056 0.109794 +v -0.145979 0.015460 -0.000598 +v -0.146179 0.063257 0.107194 +v -0.151479 0.018659 -0.000598 +v -0.152379 0.067056 0.109794 +v -0.152779 0.072456 0.113294 +v -0.140380 0.072456 0.113294 +v -0.145779 0.066856 -0.102792 +v -0.140279 0.063756 -0.103592 +v -0.140279 0.057657 -0.105292 +v -0.145779 0.054557 -0.106091 +v -0.151279 0.057657 -0.105292 +v -0.151279 0.063756 -0.103592 +v -0.124780 0.071156 -0.137589 +v -0.123581 0.067556 -0.132590 +v -0.124680 0.061357 -0.132790 +v -0.127080 0.058757 -0.137990 +v -0.128280 0.062357 -0.143089 +v -0.127180 0.068556 -0.142889 +v -0.092882 0.061857 -0.138889 +v -0.095982 0.059057 -0.134190 +v -0.098382 0.053157 -0.134990 +v -0.097482 0.050257 -0.140589 +v -0.094383 0.053157 -0.145289 +v -0.091983 0.058957 -0.144389 +v -0.019687 0.028459 -0.109191 +v -0.022887 0.025559 -0.104492 +v -0.025187 0.019759 -0.105292 +v -0.024387 0.016760 -0.110891 +v -0.021287 0.019659 -0.115591 +v -0.018887 0.025559 -0.114691 +v 0.039309 0.008260 -0.104592 +v 0.029109 0.006160 -0.099292 +v 0.008710 0.007260 -0.099492 +v 0.000511 0.007760 -0.105092 +v 0.009910 0.007160 -0.110391 +v 0.030309 0.006160 -0.110191 +v -0.151479 -0.024338 -0.000598 +v -0.152379 -0.073134 0.110994 +v -0.146179 -0.075434 0.107694 +v -0.145979 -0.027438 -0.000598 +v -0.140479 -0.073134 0.110994 +v -0.140479 -0.024338 -0.000598 +v -0.140479 -0.066335 0.109794 +v -0.140479 -0.017938 -0.000598 +v -0.146179 -0.062535 0.107194 +v -0.145979 -0.014838 -0.000598 +v -0.152379 -0.066335 0.109794 +v -0.151479 -0.017938 -0.000598 +v -0.152778 -0.071734 0.113294 +v -0.140379 -0.071734 0.113294 +v -0.140279 -0.063035 -0.103592 +v -0.145779 -0.066135 -0.102792 +v -0.140279 -0.056936 -0.105292 +v -0.145779 -0.053836 -0.106091 +v -0.151279 -0.056936 -0.105292 +v -0.151279 -0.063035 -0.103592 +v -0.123581 -0.066835 -0.132590 +v -0.124780 -0.070435 -0.137589 +v -0.124680 -0.060635 -0.132790 +v -0.127080 -0.058035 -0.137990 +v -0.128280 -0.061635 -0.143089 +v -0.127180 -0.067835 -0.142889 +v -0.095982 -0.058335 -0.134190 +v -0.092882 -0.061135 -0.138889 +v -0.098382 -0.052436 -0.134990 +v -0.097482 -0.049536 -0.140589 +v -0.094383 -0.052436 -0.145289 +v -0.091983 -0.058235 -0.144389 +v -0.022887 -0.024838 -0.104492 +v -0.019687 -0.027737 -0.109191 +v -0.025187 -0.019038 -0.105292 +v -0.024387 -0.016038 -0.110891 +v -0.021287 -0.018938 -0.115591 +v -0.018887 -0.024838 -0.114691 +v 0.029109 -0.005439 -0.099292 +v 0.039309 -0.007539 -0.104592 +v 0.008710 -0.006539 -0.099492 +v 0.000511 -0.007039 -0.105092 +v 0.009910 -0.006439 -0.110391 +v 0.030309 -0.005439 -0.110191 +v -0.031187 -0.025738 -0.011998 +v -0.040786 -0.035137 -0.011798 +v -0.040786 -0.035137 -0.007398 +v 0.022410 -0.014138 0.018800 +v 0.030809 -0.017938 0.011101 +v 0.003611 -0.035137 0.011101 +v 0.003611 -0.018738 0.018800 +v 0.081306 -0.035137 -0.012598 +v 0.081306 -0.035137 0.011101 +v 0.112104 -0.035137 0.011101 +v 0.122803 -0.035137 -0.012598 +v 0.130402 -0.026137 0.014700 +v 0.133302 -0.035137 0.010901 +v 0.115103 -0.026237 0.014700 +v 0.174999 -0.035137 -0.012598 +v 0.174999 -0.035137 0.010901 +v -0.006688 -0.025738 0.018800 +v -0.006688 -0.025738 0.011401 +v -0.031187 -0.025738 0.011700 +v -0.029087 -0.019338 0.018800 +v -0.031187 -0.023838 -0.017097 +v -0.038086 -0.031037 -0.017097 +v -0.006688 -0.025738 -0.012298 +v -0.006688 -0.023838 -0.017098 +v 0.003611 -0.035137 -0.012598 +v 0.001911 -0.031037 -0.017098 +v -0.006688 -0.025738 0.061397 +v -0.029087 -0.019338 0.061397 +v -0.029087 -0.019338 0.067197 +v -0.006688 -0.025738 0.067197 +v -0.006688 0.026459 0.067197 +v -0.035486 0.000361 0.067197 +v -0.029087 0.020059 0.067197 +v -0.035486 0.000361 0.061397 +v -0.035486 0.000361 0.018800 +v -0.035486 0.000361 0.011700 +v -0.040686 -0.035137 0.011600 +v -0.040686 0.000361 0.011600 +v -0.154779 -0.035137 0.011101 +v -0.154779 0.000361 0.011101 +v -0.154779 0.000361 -0.011798 +v -0.154779 -0.035137 -0.007698 +v -0.154779 -0.035137 -0.011798 +v -0.040786 0.000361 -0.011798 +v -0.038086 0.000361 -0.017097 +v -0.006688 0.000361 -0.017098 +v 0.019610 0.000361 -0.017098 +v 0.023210 0.000361 -0.012598 +v 0.122803 0.000361 -0.012598 +v 0.174999 0.000361 -0.012598 +v 0.174999 0.000361 0.010901 +v 0.133302 0.000361 0.010901 +v 0.130402 -0.008539 0.014600 +v 0.130002 -0.010238 0.025199 +v 0.130002 -0.024537 0.025199 +v 0.115503 -0.024537 0.025199 +v 0.115503 -0.010238 0.025199 +v 0.115103 -0.008539 0.014600 +v 0.112104 0.000361 0.011101 +v 0.038909 0.000361 0.011101 +v 0.026109 0.000361 0.018800 +v -0.006688 0.026459 0.061397 +v 0.003611 -0.018738 0.061397 +v 0.022410 -0.014138 0.061397 +v 0.026109 0.000361 0.061397 +v 0.009010 -0.052336 0.011101 +v 0.009010 -0.052336 -0.012598 +v 0.044908 -0.052336 -0.012598 +v 0.044808 -0.052336 0.011101 +v 0.009311 -0.064035 0.011101 +v 0.009311 -0.064035 -0.012598 +v 0.026509 -0.088533 -0.012598 +v 0.026409 -0.088533 0.011101 +v 0.002411 -0.073334 0.011101 +v 0.002411 -0.073334 -0.012598 +v 0.005011 -0.103132 -0.012598 +v 0.005011 -0.103032 0.011101 +v -0.009388 -0.078234 0.011101 +v -0.009388 -0.078234 -0.012598 +v -0.008688 -0.100033 -0.012598 +v -0.008688 -0.100033 0.011101 +v -0.013988 -0.089133 0.011101 +v -0.013988 -0.089133 -0.012598 +v -0.090283 -0.045936 -0.011798 +v -0.090383 -0.045936 -0.007498 +v -0.031187 0.026459 -0.011998 +v -0.040786 0.035858 -0.007398 +v -0.040786 0.035858 -0.011798 +v 0.022410 0.014860 0.018800 +v 0.003611 0.019459 0.018800 +v 0.003611 0.035858 0.011101 +v 0.030809 0.018659 0.011101 +v 0.081306 0.035858 -0.012598 +v 0.122803 0.035858 -0.012598 +v 0.112104 0.035858 0.011101 +v 0.081306 0.035858 0.011101 +v 0.130402 0.026859 0.014700 +v 0.115103 0.026959 0.014700 +v 0.133302 0.035858 0.010901 +v 0.174999 0.035858 -0.012598 +v 0.174999 0.035858 0.010901 +v -0.006688 0.026459 0.018800 +v -0.029087 0.020059 0.018800 +v -0.031187 0.026459 0.011700 +v -0.006688 0.026459 0.011401 +v -0.031187 0.024559 -0.017097 +v -0.038086 0.031758 -0.017097 +v -0.006688 0.024559 -0.017098 +v -0.006688 0.026459 -0.012298 +v 0.001911 0.031758 -0.017098 +v 0.003611 0.035858 -0.012598 +v -0.029087 0.020059 0.061397 +v -0.040686 0.035858 0.011600 +v -0.154779 0.035858 0.011101 +v -0.154779 0.035858 -0.011798 +v -0.154779 0.035858 -0.007698 +v 0.130402 0.009260 0.014600 +v 0.130002 0.010960 0.025199 +v 0.115503 0.010960 0.025199 +v 0.115503 0.025259 0.025199 +v 0.130002 0.025259 0.025199 +v 0.115103 0.009260 0.014600 +v 0.003611 0.019459 0.061397 +v 0.022410 0.014860 0.061397 +v 0.009010 0.053057 -0.012598 +v 0.009010 0.053057 0.011101 +v 0.044808 0.053057 0.011101 +v 0.044908 0.053057 -0.012598 +v 0.009311 0.064756 -0.012598 +v 0.009311 0.064756 0.011101 +v 0.026409 0.089255 0.011101 +v 0.026509 0.089255 -0.012598 +v 0.002411 0.074056 -0.012598 +v 0.002411 0.074056 0.011101 +v 0.005011 0.103754 0.011101 +v 0.005011 0.103854 -0.012598 +v -0.009388 0.078955 -0.012598 +v -0.009388 0.078955 0.011101 +v -0.008688 0.100754 0.011101 +v -0.008688 0.100754 -0.012598 +v -0.013988 0.089855 0.011101 +v -0.013988 0.089855 -0.012598 +v -0.090383 0.046657 -0.007498 +v -0.090283 0.046657 -0.011798 +v -0.011988 0.019259 0.054198 +v -0.011988 0.019259 0.107594 +v -0.028387 0.009860 0.107594 +v -0.028387 0.009860 0.054198 +v -0.028387 -0.009139 0.107594 +v -0.028387 -0.009139 0.054198 +v -0.011988 -0.018538 0.107594 +v -0.011988 -0.018538 0.054198 +v 0.004311 -0.009139 0.107594 +v 0.004311 -0.009139 0.054198 +v 0.004311 0.009860 0.107594 +v 0.004311 0.009860 0.054198 +v -0.112481 -0.061235 -0.135489 +v -0.112181 -0.061435 -0.135489 +v -0.111081 -0.059735 -0.135790 +v 0.126872 0.027590 0.114482 +v 0.126872 -0.027517 0.114482 +v 0.111078 -0.027517 0.114482 +v 0.111078 0.027590 0.114482 +v 0.127281 0.027590 0.095350 +v 0.127281 -0.027517 0.095350 +v 0.075924 0.027590 0.114482 +v 0.075924 0.027590 0.095350 +v 0.111078 0.027590 0.095350 +v 0.075924 -0.027517 0.114482 +v 0.075924 -0.027517 0.095350 +v 0.111078 -0.027517 0.095350 +v 0.130200 0.027590 0.062375 +v 0.130200 -0.027517 0.062375 +v 0.075924 0.027590 0.062375 +v 0.113374 0.027590 0.062375 +v 0.113374 -0.027517 0.062375 +v 0.113374 -0.025476 0.038904 +v 0.130200 -0.025476 0.038904 +v 0.130200 0.025549 0.038904 +v 0.113374 0.025549 0.038904 +v 0.075924 -0.027517 0.062375 +v 0.075924 -0.053941 0.095350 +v 0.075924 0.054014 0.095350 +v 0.075924 0.054014 0.062224 +v 0.075924 -0.053941 0.062224 +v 0.060008 -0.053941 0.095350 +v 0.060008 0.054014 0.095350 +v 0.060008 0.054014 0.062224 +v 0.060008 -0.053941 0.062224 +v 0.060008 -0.053941 0.087935 +v 0.060008 0.054014 0.087935 +v 0.060008 0.054014 0.062221 +v 0.060008 -0.053941 0.062221 +v 0.022022 -0.053941 0.087935 +v 0.022022 0.054014 0.087935 +v 0.022022 0.054014 0.062221 +v 0.022022 -0.053941 0.062221 +v 0.058935 -0.062629 0.114660 +v 0.027347 -0.062629 0.114660 +v 0.027347 0.062702 0.114660 +v 0.058935 0.062702 0.114660 +v 0.058935 0.062702 0.107118 +v 0.058935 -0.062629 0.107118 +v 0.027347 0.062702 0.107118 +v 0.027347 -0.062629 0.107118 +v 0.052708 0.061513 0.107118 +v 0.049451 -0.061440 0.107118 +v 0.027757 0.061513 0.107118 +v 0.027757 -0.061440 0.107118 +v 0.052708 0.061513 0.091602 +v 0.049451 -0.061440 0.091602 +v 0.027757 0.061513 0.091601 +v 0.027757 -0.061440 0.091601 +v 0.055913 0.065788 0.091602 +v 0.055914 -0.065715 0.091602 +v 0.024551 0.065788 0.091601 +v 0.024551 -0.065715 0.091601 +v 0.060556 0.058191 0.091602 +v 0.060556 -0.058118 0.091602 +v 0.019909 -0.058118 0.091601 +v 0.019908 0.058191 0.091601 +v 0.024551 0.065788 0.087578 +v 0.055913 0.065788 0.087578 +v 0.055914 -0.065715 0.087578 +v 0.024551 -0.065715 0.087578 +v 0.060556 -0.058118 0.087578 +v 0.060556 0.058191 0.087578 +v 0.019908 0.058191 0.087578 +v 0.019909 -0.058118 0.087578 +v 0.057469 -0.028564 0.127214 +v 0.057470 -0.054336 0.127214 +v 0.049570 -0.061933 0.127214 +v 0.028688 -0.054336 0.127214 +v 0.036430 -0.061933 0.127214 +v 0.036430 -0.020966 0.127214 +v 0.028688 -0.028564 0.127214 +v 0.049570 -0.020966 0.127214 +v 0.049570 -0.020966 0.114025 +v 0.057469 -0.028564 0.114025 +v 0.057470 -0.054336 0.114025 +v 0.049570 -0.061933 0.114025 +v 0.036430 -0.061933 0.114025 +v 0.028688 -0.054336 0.114025 +v 0.028688 -0.028564 0.114025 +v 0.036430 -0.020966 0.114025 +v 0.057469 0.012799 0.127214 +v 0.057470 -0.012972 0.127214 +v 0.049570 -0.020570 0.127214 +v 0.028688 -0.012973 0.127214 +v 0.036430 -0.020570 0.127214 +v 0.036430 0.020397 0.127214 +v 0.028688 0.012799 0.127214 +v 0.049570 0.020397 0.127214 +v 0.049570 0.020397 0.114025 +v 0.057469 0.012799 0.114025 +v 0.057470 -0.012972 0.114025 +v 0.049570 -0.020570 0.114025 +v 0.036430 -0.020570 0.114025 +v 0.028688 -0.012973 0.114025 +v 0.028688 0.012799 0.114025 +v 0.036430 0.020397 0.114025 +v 0.057469 0.054604 0.127214 +v 0.057470 0.028833 0.127214 +v 0.049570 0.021235 0.127214 +v 0.028688 0.028833 0.127214 +v 0.036430 0.021235 0.127214 +v 0.036430 0.062202 0.127214 +v 0.028688 0.054604 0.127214 +v 0.049570 0.062202 0.127214 +v 0.049570 0.062202 0.114025 +v 0.057469 0.054604 0.114025 +v 0.057470 0.028833 0.114025 +v 0.049570 0.021235 0.114025 +v 0.036430 0.021235 0.114025 +v 0.028688 0.028833 0.114025 +v 0.028688 0.054604 0.114025 +v 0.036430 0.062202 0.114025 +v -0.004260 -0.109890 0.047070 +v 0.011414 -0.106415 0.047070 +v 0.011414 -0.106415 0.012912 +v -0.004260 -0.109890 0.012912 +v -0.017800 -0.101264 0.047070 +v -0.017800 -0.101264 0.012912 +v -0.021275 -0.085590 0.047070 +v -0.021275 -0.085590 0.012912 +v -0.012649 -0.072050 0.047070 +v -0.012649 -0.072050 0.012912 +v 0.003025 -0.068575 0.047070 +v 0.003025 -0.068575 0.012912 +v 0.016565 -0.077201 0.047070 +v 0.016565 -0.077201 0.012912 +v 0.020040 -0.092875 0.012912 +v 0.013651 -0.091748 0.012912 +v 0.007693 -0.101100 0.012912 +v -0.003133 -0.103500 0.012912 +v -0.012485 -0.097542 0.012912 +v -0.014885 -0.086717 0.012912 +v -0.008927 -0.077364 0.012912 +v 0.001899 -0.074964 0.012912 +v 0.011251 -0.080922 0.012912 +v 0.007693 -0.101100 0.047070 +v 0.013651 -0.091748 0.047070 +v 0.020040 -0.092875 0.047070 +v -0.003133 -0.103500 0.047070 +v -0.012485 -0.097542 0.047070 +v -0.014885 -0.086717 0.047070 +v -0.008927 -0.077364 0.047070 +v 0.001899 -0.074964 0.047070 +v 0.011251 -0.080922 0.047070 +v -0.019179 -0.046658 0.025026 +v -0.023338 -0.053186 0.025026 +v -0.023338 -0.053186 0.013116 +v -0.019179 -0.046658 0.013116 +v -0.011621 -0.044982 0.025026 +v -0.011621 -0.044982 0.013116 +v -0.005092 -0.049141 0.025026 +v -0.005092 -0.049141 0.013116 +v -0.003417 -0.056699 0.025026 +v -0.003417 -0.056699 0.013115 +v -0.009502 -0.055626 0.013115 +v -0.011121 -0.058166 0.013115 +v -0.007576 -0.063228 0.013115 +v -0.014060 -0.058818 0.013115 +v -0.015134 -0.064903 0.013115 +v -0.016600 -0.057200 0.013115 +v -0.021662 -0.060744 0.013116 +v -0.017252 -0.054259 0.013116 +v -0.015634 -0.051720 0.013116 +v -0.012694 -0.051068 0.013116 +v -0.010154 -0.052686 0.013116 +v -0.007576 -0.063228 0.047207 +v -0.011121 -0.058166 0.047207 +v -0.009502 -0.055626 0.047207 +v -0.003417 -0.056699 0.047207 +v -0.015134 -0.064903 0.047207 +v -0.014060 -0.058818 0.047207 +v -0.021662 -0.060744 0.047207 +v -0.016600 -0.057200 0.047207 +v -0.023338 -0.053186 0.047207 +v -0.017252 -0.054259 0.047207 +v -0.019179 -0.046658 0.047207 +v -0.015634 -0.051720 0.047207 +v -0.011621 -0.044982 0.047207 +v -0.012694 -0.051068 0.047207 +v -0.005092 -0.049142 0.047207 +v -0.010154 -0.052686 0.047207 +v -0.023338 -0.053186 0.039006 +v -0.019179 -0.046658 0.039006 +v -0.011621 -0.044982 0.039006 +v -0.005092 -0.049141 0.039006 +v -0.003417 -0.056699 0.039006 +v -0.007576 -0.063228 0.025026 +v -0.010906 -0.058472 0.025026 +v -0.009134 -0.055691 0.025026 +v -0.015134 -0.064903 0.025026 +v -0.014125 -0.059186 0.025026 +v -0.021662 -0.060744 0.025026 +v -0.016907 -0.057414 0.025026 +v -0.017620 -0.054195 0.025026 +v -0.015848 -0.051414 0.025026 +v -0.012629 -0.050700 0.025026 +v -0.009848 -0.052472 0.025026 +v -0.009134 -0.055691 0.039006 +v -0.010906 -0.058472 0.039006 +v -0.007576 -0.063228 0.039006 +v -0.014125 -0.059186 0.039006 +v -0.015134 -0.064903 0.039006 +v -0.016907 -0.057414 0.039006 +v -0.021662 -0.060744 0.039006 +v -0.017620 -0.054195 0.039006 +v -0.015848 -0.051414 0.039006 +v -0.012629 -0.050700 0.039006 +v -0.009848 -0.052472 0.039006 +v -0.002899 -0.071608 0.013116 +v 0.004213 -0.071417 0.013116 +v 0.004213 -0.071417 0.025026 +v -0.002899 -0.071608 0.025026 +v -0.016500 -0.073622 0.013116 +v -0.016500 -0.073622 0.025026 +v -0.028560 -0.073576 0.013116 +v -0.028560 -0.073576 0.025026 +v -0.031655 -0.073492 0.013116 +v -0.031655 -0.073492 0.025026 +v 0.004212 -0.071417 0.047207 +v -0.002899 -0.071608 0.047207 +v -0.016500 -0.073622 0.047207 +v -0.028560 -0.073576 0.047207 +v -0.031655 -0.073492 0.047207 +v 0.004212 -0.071417 0.039006 +v -0.002899 -0.071608 0.039006 +v -0.016500 -0.073622 0.039006 +v -0.028560 -0.073576 0.039006 +v -0.031655 -0.073492 0.039006 +v 0.039365 -0.104145 0.012912 +v 0.039383 -0.092762 0.012912 +v 0.039376 -0.079585 0.012912 +v 0.039365 -0.104145 0.047070 +v 0.039376 -0.079585 0.047070 +v 0.039383 -0.092762 0.047070 +v -0.111081 0.059495 -0.135790 +v -0.112181 0.061195 -0.135489 +v -0.112481 0.060995 -0.135489 +# 1174 vertices, 0 vertices normals + +f 4 3 2 +f 2 1 4 +f 6 4 1 +f 1 5 6 +f 8 6 5 +f 5 7 8 +f 10 8 7 +f 7 9 10 +f 12 10 9 +f 9 11 12 +f 14 12 11 +f 11 13 14 +f 17 16 15 +f 15 2 17 +f 2 15 18 +f 18 1 2 +f 1 18 19 +f 19 5 1 +f 5 19 20 +f 20 7 5 +f 7 20 21 +f 21 9 7 +f 9 21 22 +f 22 11 9 +f 11 22 23 +f 23 13 11 +f 13 23 16 +f 16 17 13 +f 3 26 25 +f 25 24 3 +f 4 27 26 +f 26 3 4 +f 6 28 27 +f 27 4 6 +f 8 29 28 +f 28 6 8 +f 10 30 29 +f 29 8 10 +f 12 31 30 +f 30 10 12 +f 14 32 31 +f 31 12 14 +f 24 25 32 +f 32 14 24 +f 16 25 26 +f 26 15 16 +f 23 32 25 +f 25 16 23 +f 22 31 32 +f 32 23 22 +f 21 30 31 +f 31 22 21 +f 20 29 30 +f 30 21 20 +f 19 28 29 +f 29 20 19 +f 18 27 28 +f 28 19 18 +f 15 26 27 +f 27 18 15 +f 36 35 34 +f 34 33 36 +f 38 36 33 +f 33 37 38 +f 40 38 37 +f 37 39 40 +f 42 40 39 +f 39 41 42 +f 41 45 44 +f 44 43 41 +f 43 44 47 +f 47 46 43 +f 46 47 49 +f 49 48 46 +f 48 49 50 +f 50 34 48 +f 34 50 51 +f 51 33 34 +f 33 51 52 +f 52 37 33 +f 37 52 53 +f 53 39 37 +f 39 53 45 +f 45 41 39 +f 57 56 55 +f 55 54 57 +f 59 58 56 +f 56 57 59 +f 61 60 58 +f 58 59 61 +f 63 62 60 +f 60 61 63 +f 65 64 62 +f 62 63 65 +f 67 66 64 +f 64 65 67 +f 69 68 66 +f 66 67 69 +f 54 55 68 +f 68 69 54 +f 63 71 70 +f 70 65 63 +f 65 70 72 +f 72 67 65 +f 67 72 73 +f 73 69 67 +f 69 73 74 +f 74 54 69 +f 77 76 75 +f 75 42 77 +f 79 78 76 +f 76 77 79 +f 81 80 78 +f 78 79 81 +f 35 82 80 +f 80 81 35 +f 36 83 82 +f 82 35 36 +f 38 84 83 +f 83 36 38 +f 40 85 84 +f 84 38 40 +f 42 75 85 +f 85 40 42 +f 74 88 87 +f 87 86 74 +f 86 87 90 +f 90 89 86 +f 89 90 92 +f 92 91 89 +f 91 92 93 +f 93 71 91 +f 71 93 94 +f 94 70 71 +f 70 94 95 +f 95 72 70 +f 72 95 96 +f 96 73 72 +f 73 96 88 +f 88 74 73 +f 58 90 87 +f 87 56 58 +f 60 92 90 +f 90 58 60 +f 62 93 92 +f 92 60 62 +f 64 94 93 +f 93 62 64 +f 66 95 94 +f 94 64 66 +f 68 96 95 +f 95 66 68 +f 55 88 96 +f 96 68 55 +f 56 87 88 +f 88 55 56 +f 51 83 84 +f 84 52 51 +f 50 82 83 +f 83 51 50 +f 49 80 82 +f 82 50 49 +f 47 78 80 +f 80 49 47 +f 44 76 78 +f 78 47 44 +f 45 75 76 +f 76 44 45 +f 53 85 75 +f 75 45 53 +f 52 84 85 +f 85 53 52 +f 43 98 97 +f 97 41 43 +f 42 100 99 +f 99 77 42 +f 41 97 100 +f 100 42 41 +f 46 101 98 +f 98 43 46 +f 77 99 102 +f 102 79 77 +f 48 103 101 +f 101 46 48 +f 79 102 104 +f 104 81 79 +f 34 105 103 +f 103 48 34 +f 35 106 105 +f 105 34 35 +f 81 104 106 +f 106 35 81 +f 54 108 107 +f 107 57 54 +f 57 107 109 +f 109 59 57 +f 59 109 110 +f 110 61 59 +f 61 110 111 +f 111 63 61 +f 74 112 108 +f 108 54 74 +f 86 113 112 +f 112 74 86 +f 89 114 113 +f 113 86 89 +f 91 115 114 +f 114 89 91 +f 63 111 116 +f 116 71 63 +f 71 116 115 +f 115 91 71 +f 2 118 117 +f 117 17 2 +f 17 117 119 +f 119 13 17 +f 3 120 118 +f 118 2 3 +f 13 119 121 +f 121 14 13 +f 24 122 120 +f 120 3 24 +f 14 121 122 +f 122 24 14 +f 126 125 124 +f 124 123 126 +f 126 123 128 +f 128 127 126 +f 127 128 130 +f 130 129 127 +f 132 131 123 +f 123 124 132 +f 134 133 125 +f 125 126 134 +f 136 124 125 +f 125 135 136 +f 138 136 135 +f 135 137 138 +f 134 140 139 +f 139 133 134 +f 141 139 140 +f 139 141 143 +f 143 142 139 +f 140 145 144 +f 144 141 140 +f 149 148 147 +f 147 146 149 +f 149 151 150 +f 150 148 149 +f 151 153 152 +f 152 150 151 +f 155 147 148 +f 148 154 155 +f 157 149 146 +f 146 156 157 +f 159 158 146 +f 146 147 159 +f 161 160 158 +f 158 159 161 +f 157 156 163 +f 163 162 157 +f 164 162 163 +f 163 166 165 +f 165 164 163 +f 162 164 168 +f 168 167 162 +f 150 128 123 +f 123 148 150 +f 149 126 127 +f 127 151 149 +f 152 130 128 +f 128 150 152 +f 153 129 130 +f 130 152 153 +f 151 127 129 +f 129 153 151 +f 148 123 131 +f 131 154 148 +f 155 132 124 +f 124 147 155 +f 154 131 132 +f 132 155 154 +f 146 125 133 +f 133 156 146 +f 157 134 126 +f 126 149 157 +f 158 135 125 +f 125 146 158 +f 147 124 136 +f 136 159 147 +f 160 137 135 +f 135 158 160 +f 161 138 137 +f 137 160 161 +f 159 136 138 +f 138 161 159 +f 156 133 139 +f 139 163 156 +f 162 140 134 +f 134 157 162 +f 165 143 141 +f 141 164 165 +f 166 142 143 +f 143 165 166 +f 163 139 142 +f 142 166 163 +f 168 144 145 +f 145 167 168 +f 164 141 144 +f 144 168 164 +f 167 145 140 +f 140 162 167 +f 172 171 170 +f 170 169 172 +f 170 174 173 +f 173 169 170 +f 178 177 176 +f 176 175 178 +f 175 176 171 +f 171 172 175 +f 171 180 179 +f 179 170 171 +f 170 179 181 +f 181 174 170 +f 174 181 183 +f 183 182 174 +f 182 183 184 +f 184 177 182 +f 177 184 185 +f 185 176 177 +f 176 185 180 +f 180 171 176 +f 180 187 186 +f 186 179 180 +f 179 186 188 +f 188 181 179 +f 181 188 189 +f 189 183 181 +f 183 189 190 +f 190 184 183 +f 184 190 191 +f 191 185 184 +f 185 191 187 +f 187 180 185 +f 187 193 192 +f 192 186 187 +f 186 192 194 +f 194 188 186 +f 188 194 195 +f 195 189 188 +f 189 195 196 +f 196 190 189 +f 190 196 197 +f 197 191 190 +f 191 197 193 +f 193 187 191 +f 195 199 198 +f 198 196 195 +f 196 198 200 +f 200 197 196 +f 204 203 202 +f 202 201 204 +f 208 207 206 +f 206 205 208 +f 207 210 209 +f 209 206 207 +f 210 212 211 +f 211 209 210 +f 212 203 204 +f 204 211 212 +f 214 213 204 +f 204 201 214 +f 215 214 201 +f 201 205 215 +f 216 215 205 +f 205 206 216 +f 217 216 206 +f 206 209 217 +f 218 217 209 +f 209 211 218 +f 213 218 211 +f 211 204 213 +f 220 219 213 +f 213 214 220 +f 221 220 214 +f 214 215 221 +f 222 221 215 +f 215 216 222 +f 223 222 216 +f 216 217 223 +f 224 223 217 +f 217 218 224 +f 219 224 218 +f 218 213 219 +f 226 225 219 +f 219 220 226 +f 227 226 220 +f 220 221 227 +f 199 227 221 +f 221 222 199 +f 198 199 222 +f 222 223 198 +f 200 198 223 +f 223 224 200 +f 225 200 224 +f 224 219 225 +f 192 193 225 +f 225 226 192 +f 194 192 226 +f 226 227 194 +f 195 194 227 +f 227 199 195 +f 197 200 225 +f 225 193 197 +f 174 182 228 +f 228 173 174 +f 182 177 178 +f 178 228 182 +f 230 229 172 +f 172 169 230 +f 231 230 169 +f 169 173 231 +f 232 231 173 +f 173 228 232 +f 233 232 228 +f 228 178 233 +f 234 233 178 +f 178 175 234 +f 229 234 175 +f 175 172 229 +f 236 235 229 +f 229 230 236 +f 237 236 230 +f 230 231 237 +f 238 237 231 +f 231 232 238 +f 239 238 232 +f 232 233 239 +f 240 239 233 +f 233 234 240 +f 235 240 234 +f 234 229 235 +f 242 241 235 +f 235 236 242 +f 243 242 236 +f 236 237 243 +f 244 243 237 +f 237 238 244 +f 245 244 238 +f 238 239 245 +f 246 245 239 +f 239 240 246 +f 241 246 240 +f 240 235 241 +f 248 247 244 +f 244 245 248 +f 249 248 245 +f 245 246 249 +f 202 208 205 +f 205 201 202 +f 203 251 250 +f 250 202 203 +f 202 250 252 +f 252 208 202 +f 208 252 253 +f 253 207 208 +f 207 253 254 +f 254 210 207 +f 210 254 255 +f 255 212 210 +f 212 255 251 +f 251 203 212 +f 251 257 256 +f 256 250 251 +f 250 256 258 +f 258 252 250 +f 252 258 259 +f 259 253 252 +f 253 259 260 +f 260 254 253 +f 254 260 261 +f 261 255 254 +f 255 261 257 +f 257 251 255 +f 257 263 262 +f 262 256 257 +f 256 262 264 +f 264 258 256 +f 258 264 247 +f 247 259 258 +f 259 247 248 +f 248 260 259 +f 260 248 249 +f 249 261 260 +f 261 249 263 +f 263 257 261 +f 263 241 242 +f 242 262 263 +f 262 242 243 +f 243 264 262 +f 264 243 244 +f 244 247 264 +f 263 249 246 +f 246 241 263 +f 267 266 265 +f 270 269 268 +f 273 272 271 +f 276 275 274 +f 278 265 271 +f 271 277 278 +f 274 268 278 +f 278 277 274 +f 270 268 274 +f 274 275 270 +f 280 270 275 +f 275 279 280 +f 273 266 280 +f 280 279 273 +f 271 265 266 +f 266 273 271 +f 283 282 281 +f 286 285 284 +f 289 288 287 +f 292 291 290 +f 294 281 287 +f 287 293 294 +f 290 284 294 +f 294 293 290 +f 286 284 290 +f 290 291 286 +f 296 286 291 +f 291 295 296 +f 289 282 296 +f 296 295 289 +f 287 281 282 +f 282 289 287 +f 299 298 297 +f 302 301 300 +f 305 304 303 +f 308 307 306 +f 303 297 310 +f 310 309 303 +f 310 300 306 +f 306 309 310 +f 306 300 301 +f 301 308 306 +f 308 301 312 +f 312 311 308 +f 312 299 304 +f 304 311 312 +f 299 297 303 +f 303 304 299 +f 315 314 313 +f 318 317 316 +f 321 320 319 +f 324 323 322 +f 319 313 326 +f 326 325 319 +f 326 316 322 +f 322 325 326 +f 322 316 317 +f 317 324 322 +f 324 317 328 +f 328 327 324 +f 328 315 320 +f 320 327 328 +f 315 313 319 +f 319 320 315 +f 331 330 329 +f 334 333 332 +f 337 336 335 +f 340 339 338 +f 342 329 335 +f 335 341 342 +f 338 332 342 +f 342 341 338 +f 334 332 338 +f 338 339 334 +f 344 334 339 +f 339 343 344 +f 337 330 344 +f 344 343 337 +f 335 329 330 +f 330 337 335 +f 347 346 345 +f 350 349 348 +f 353 352 351 +f 356 355 354 +f 358 345 351 +f 351 357 358 +f 354 348 358 +f 358 357 354 +f 350 348 354 +f 354 355 350 +f 360 350 355 +f 355 359 360 +f 353 346 360 +f 360 359 353 +f 351 345 346 +f 346 353 351 +f 363 362 361 +f 366 365 364 +f 369 368 367 +f 372 371 370 +f 367 361 374 +f 374 373 367 +f 374 364 370 +f 370 373 374 +f 370 364 365 +f 365 372 370 +f 372 365 376 +f 376 375 372 +f 376 363 368 +f 368 375 376 +f 363 361 367 +f 367 368 363 +f 379 378 377 +f 382 381 380 +f 385 384 383 +f 388 387 386 +f 383 377 390 +f 390 389 383 +f 390 380 386 +f 386 389 390 +f 386 380 381 +f 381 388 386 +f 388 381 392 +f 392 391 388 +f 392 379 384 +f 384 391 392 +f 379 377 383 +f 383 384 379 +f 396 395 394 +f 394 393 396 +f 395 398 397 +f 397 394 395 +f 398 400 399 +f 399 397 398 +f 400 402 401 +f 401 399 400 +f 402 404 403 +f 403 401 402 +f 404 396 393 +f 393 403 404 +f 408 407 406 +f 406 405 408 +f 407 410 409 +f 409 406 407 +f 410 412 411 +f 411 409 410 +f 412 414 413 +f 413 411 412 +f 414 416 415 +f 415 413 414 +f 416 408 405 +f 405 415 416 +f 420 419 418 +f 418 417 420 +f 422 421 419 +f 419 420 422 +f 424 423 421 +f 421 422 424 +f 426 425 423 +f 423 424 426 +f 428 427 425 +f 425 426 428 +f 430 429 427 +f 427 428 430 +f 432 431 429 +f 429 430 432 +f 417 418 431 +f 431 432 417 +f 428 426 417 +f 417 430 428 +f 424 422 417 +f 417 426 424 +f 420 417 422 +f 430 417 432 +f 419 434 433 +f 433 418 419 +f 421 435 434 +f 434 419 421 +f 423 436 435 +f 435 421 423 +f 425 437 436 +f 436 423 425 +f 427 438 437 +f 437 425 427 +f 429 439 438 +f 438 427 429 +f 431 440 439 +f 439 429 431 +f 418 433 440 +f 440 431 418 +f 434 442 441 +f 441 433 434 +f 435 443 442 +f 442 434 435 +f 436 444 443 +f 443 435 436 +f 437 445 444 +f 444 436 437 +f 438 446 445 +f 445 437 438 +f 439 447 446 +f 446 438 439 +f 440 448 447 +f 447 439 440 +f 433 441 448 +f 448 440 433 +f 452 451 450 +f 450 449 452 +f 454 453 451 +f 451 452 454 +f 456 455 453 +f 453 454 456 +f 458 457 455 +f 455 456 458 +f 460 459 457 +f 457 458 460 +f 449 450 459 +f 459 460 449 +f 456 454 449 +f 449 458 456 +f 452 449 454 +f 458 449 460 +f 464 463 462 +f 462 461 464 +f 461 462 466 +f 466 465 461 +f 465 466 468 +f 468 467 465 +f 467 468 470 +f 470 469 467 +f 469 470 472 +f 472 471 469 +f 471 472 463 +f 463 464 471 +f 461 474 473 +f 473 464 461 +f 465 475 474 +f 474 461 465 +f 467 476 475 +f 475 465 467 +f 469 477 476 +f 476 467 469 +f 471 478 477 +f 477 469 471 +f 464 473 478 +f 478 471 464 +f 474 480 479 +f 479 473 474 +f 475 481 480 +f 480 474 475 +f 476 482 481 +f 481 475 476 +f 477 483 482 +f 482 476 477 +f 478 484 483 +f 483 477 478 +f 473 479 484 +f 484 478 473 +f 480 486 485 +f 485 479 480 +f 481 487 486 +f 486 480 481 +f 482 488 487 +f 487 481 482 +f 483 489 488 +f 488 482 483 +f 484 490 489 +f 489 483 484 +f 479 485 490 +f 490 484 479 +f 486 492 491 +f 491 485 486 +f 487 493 492 +f 492 486 487 +f 488 494 493 +f 493 487 488 +f 489 495 494 +f 494 488 489 +f 490 496 495 +f 495 489 490 +f 485 491 496 +f 496 490 485 +f 492 498 497 +f 497 491 492 +f 493 499 498 +f 498 492 493 +f 494 500 499 +f 499 493 494 +f 495 501 500 +f 500 494 495 +f 496 502 501 +f 501 495 496 +f 491 497 502 +f 502 496 491 +f 506 505 504 +f 504 503 506 +f 508 507 505 +f 505 506 508 +f 510 509 507 +f 507 508 510 +f 512 511 509 +f 509 510 512 +f 514 513 511 +f 511 512 514 +f 503 504 513 +f 513 514 503 +f 515 513 504 +f 509 516 507 +f 520 519 518 +f 518 517 520 +f 519 522 521 +f 521 518 519 +f 522 524 523 +f 523 521 522 +f 524 526 525 +f 525 523 524 +f 526 528 527 +f 527 525 526 +f 528 520 517 +f 517 527 528 +f 528 529 520 +f 530 524 522 +f 518 532 531 +f 531 517 518 +f 517 531 533 +f 533 527 517 +f 527 533 534 +f 534 525 527 +f 525 534 535 +f 535 523 525 +f 523 535 536 +f 536 521 523 +f 521 536 532 +f 532 518 521 +f 538 537 506 +f 506 503 538 +f 539 538 503 +f 503 514 539 +f 534 539 514 +f 514 512 534 +f 535 534 512 +f 512 510 535 +f 540 535 510 +f 510 508 540 +f 537 540 508 +f 508 506 537 +f 544 543 542 +f 542 541 544 +f 546 545 543 +f 543 544 546 +f 548 547 545 +f 545 546 548 +f 550 549 547 +f 547 548 550 +f 552 551 549 +f 549 550 552 +f 541 542 551 +f 551 552 541 +f 554 553 542 +f 542 543 554 +f 555 554 543 +f 543 545 555 +f 556 555 545 +f 545 547 556 +f 557 556 547 +f 547 549 557 +f 558 557 549 +f 549 551 558 +f 553 558 551 +f 551 542 553 +f 560 553 554 +f 554 559 560 +f 559 554 555 +f 555 561 559 +f 561 555 556 +f 556 562 561 +f 562 556 557 +f 557 563 562 +f 563 557 558 +f 558 564 563 +f 564 558 553 +f 553 560 564 +f 566 560 559 +f 559 565 566 +f 565 559 561 +f 561 567 565 +f 567 561 562 +f 562 568 567 +f 568 562 563 +f 563 569 568 +f 569 563 564 +f 564 570 569 +f 570 564 560 +f 560 566 570 +f 572 566 565 +f 565 571 572 +f 571 565 567 +f 567 573 571 +f 573 567 568 +f 568 574 573 +f 574 568 569 +f 569 575 574 +f 575 569 570 +f 570 576 575 +f 576 570 566 +f 566 572 576 +f 552 550 546 +f 546 541 552 +f 548 546 550 +f 546 544 541 +f 580 579 578 +f 578 577 580 +f 579 582 581 +f 581 578 579 +f 582 584 583 +f 583 581 582 +f 584 586 585 +f 585 583 584 +f 586 588 587 +f 587 585 586 +f 588 580 577 +f 577 587 588 +f 580 590 589 +f 589 579 580 +f 579 589 591 +f 591 582 579 +f 582 591 592 +f 592 584 582 +f 584 592 593 +f 593 586 584 +f 586 593 594 +f 594 588 586 +f 588 594 590 +f 590 580 588 +f 589 590 596 +f 596 595 589 +f 591 589 595 +f 595 597 591 +f 592 591 597 +f 597 598 592 +f 593 592 598 +f 598 599 593 +f 594 593 599 +f 599 600 594 +f 590 594 600 +f 600 596 590 +f 595 596 602 +f 602 601 595 +f 597 595 601 +f 601 603 597 +f 598 597 603 +f 603 604 598 +f 599 598 604 +f 604 605 599 +f 600 599 605 +f 605 606 600 +f 596 600 606 +f 606 602 596 +f 601 602 608 +f 608 607 601 +f 603 601 607 +f 607 609 603 +f 604 603 609 +f 609 610 604 +f 605 604 610 +f 610 611 605 +f 606 605 611 +f 611 612 606 +f 602 606 612 +f 612 608 602 +f 578 581 585 +f 585 577 578 +f 583 585 581 +f 585 587 577 +f 616 615 614 +f 614 613 616 +f 615 618 617 +f 617 614 615 +f 618 620 619 +f 619 617 618 +f 620 622 621 +f 621 619 620 +f 622 624 623 +f 623 621 622 +f 624 616 613 +f 613 623 624 +f 616 626 625 +f 625 615 616 +f 615 625 627 +f 627 618 615 +f 618 627 628 +f 628 620 618 +f 620 628 629 +f 629 622 620 +f 622 629 630 +f 630 624 622 +f 624 630 626 +f 626 616 624 +f 625 626 632 +f 632 631 625 +f 627 625 631 +f 631 633 627 +f 628 627 633 +f 633 634 628 +f 629 628 634 +f 634 635 629 +f 630 629 635 +f 635 636 630 +f 626 630 636 +f 636 632 626 +f 631 632 638 +f 638 637 631 +f 633 631 637 +f 637 639 633 +f 634 633 639 +f 639 640 634 +f 635 634 640 +f 640 641 635 +f 636 635 641 +f 641 642 636 +f 632 636 642 +f 642 638 632 +f 637 638 644 +f 644 643 637 +f 639 637 643 +f 643 645 639 +f 640 639 645 +f 645 646 640 +f 641 640 646 +f 646 647 641 +f 642 641 647 +f 647 648 642 +f 638 642 648 +f 648 644 638 +f 614 617 621 +f 621 613 614 +f 619 621 617 +f 621 623 613 +f 652 651 650 +f 650 649 652 +f 654 653 651 +f 651 652 654 +f 656 655 653 +f 653 654 656 +f 658 657 655 +f 655 656 658 +f 660 659 657 +f 657 658 660 +f 649 650 659 +f 659 660 649 +f 662 661 650 +f 650 651 662 +f 663 662 651 +f 651 653 663 +f 664 663 653 +f 653 655 664 +f 665 664 655 +f 655 657 665 +f 666 665 657 +f 657 659 666 +f 661 666 659 +f 659 650 661 +f 668 661 662 +f 662 667 668 +f 667 662 663 +f 663 669 667 +f 669 663 664 +f 664 670 669 +f 670 664 665 +f 665 671 670 +f 671 665 666 +f 666 672 671 +f 672 666 661 +f 661 668 672 +f 674 668 667 +f 667 673 674 +f 673 667 669 +f 669 675 673 +f 675 669 670 +f 670 676 675 +f 676 670 671 +f 671 677 676 +f 677 671 672 +f 672 678 677 +f 678 672 668 +f 668 674 678 +f 680 674 673 +f 673 679 680 +f 679 673 675 +f 675 681 679 +f 681 675 676 +f 676 682 681 +f 682 676 677 +f 677 683 682 +f 683 677 678 +f 678 684 683 +f 684 678 674 +f 674 680 684 +f 660 658 654 +f 654 649 660 +f 656 654 658 +f 654 652 649 +f 688 687 686 +f 686 685 688 +f 687 690 689 +f 689 686 687 +f 690 692 691 +f 691 689 690 +f 692 694 693 +f 693 691 692 +f 694 696 695 +f 695 693 694 +f 696 688 685 +f 685 695 696 +f 696 697 688 +f 698 692 690 +f 700 699 686 +f 686 689 700 +f 701 700 689 +f 689 691 701 +f 702 701 691 +f 691 693 702 +f 703 702 693 +f 693 695 703 +f 704 703 695 +f 695 685 704 +f 699 704 685 +f 685 686 699 +f 706 705 699 +f 699 700 706 +f 707 706 700 +f 700 701 707 +f 708 707 701 +f 701 702 708 +f 709 708 702 +f 702 703 709 +f 710 709 703 +f 703 704 710 +f 705 710 704 +f 704 699 705 +f 712 711 705 +f 705 706 712 +f 713 712 706 +f 706 707 713 +f 714 713 707 +f 707 708 714 +f 715 714 708 +f 708 709 715 +f 716 715 709 +f 709 710 716 +f 711 716 710 +f 710 705 711 +f 718 717 711 +f 711 712 718 +f 719 718 712 +f 712 713 719 +f 720 719 713 +f 713 714 720 +f 721 720 714 +f 714 715 721 +f 722 721 715 +f 715 716 722 +f 717 722 716 +f 716 711 717 +f 724 723 717 +f 717 718 724 +f 725 724 718 +f 718 719 725 +f 726 725 719 +f 719 720 726 +f 727 726 720 +f 720 721 727 +f 728 727 721 +f 721 722 728 +f 723 728 722 +f 722 717 723 +f 732 731 730 +f 730 729 732 +f 734 733 731 +f 731 732 734 +f 736 735 733 +f 733 734 736 +f 738 737 735 +f 735 736 738 +f 740 739 737 +f 737 738 740 +f 729 730 739 +f 739 740 729 +f 741 739 730 +f 735 742 733 +f 732 744 743 +f 743 734 732 +f 734 743 745 +f 745 736 734 +f 736 745 746 +f 746 738 736 +f 738 746 747 +f 747 740 738 +f 740 747 748 +f 748 729 740 +f 744 750 749 +f 749 743 744 +f 743 749 751 +f 751 745 743 +f 745 751 752 +f 752 746 745 +f 746 752 753 +f 753 747 746 +f 747 753 754 +f 754 748 747 +f 748 754 750 +f 750 744 748 +f 750 756 755 +f 755 749 750 +f 749 755 757 +f 757 751 749 +f 751 757 758 +f 758 752 751 +f 752 758 759 +f 759 753 752 +f 753 759 760 +f 760 754 753 +f 754 760 756 +f 756 750 754 +f 756 762 761 +f 761 755 756 +f 755 761 763 +f 763 757 755 +f 757 763 764 +f 764 758 757 +f 758 764 765 +f 765 759 758 +f 759 765 766 +f 766 760 759 +f 760 766 762 +f 762 756 760 +f 762 768 767 +f 767 761 762 +f 761 767 769 +f 769 763 761 +f 763 769 770 +f 770 764 763 +f 764 770 771 +f 771 765 764 +f 765 771 772 +f 772 766 765 +f 766 772 768 +f 768 762 766 +f 729 748 744 +f 744 732 729 +f 775 774 773 +f 779 778 777 +f 777 776 779 +f 783 782 781 +f 781 780 783 +f 786 782 785 +f 785 784 786 +f 788 785 783 +f 783 787 788 +f 792 791 790 +f 790 789 792 +f 789 790 778 +f 778 779 789 +f 773 774 794 +f 794 793 773 +f 796 795 773 +f 773 793 796 +f 798 797 795 +f 795 796 798 +f 795 790 791 +f 791 773 795 +f 797 778 790 +f 790 795 797 +f 783 785 782 +f 802 801 800 +f 800 799 802 +f 805 804 801 +f 801 803 805 +f 801 802 803 +f 806 800 801 +f 801 804 806 +f 792 800 806 +f 806 807 792 +f 810 809 791 +f 791 808 810 +f 812 811 809 +f 809 810 812 +f 815 814 813 +f 817 794 774 +f 774 816 817 +f 818 793 794 +f 794 817 818 +f 796 793 818 +f 819 798 796 +f 796 818 819 +f 820 797 798 +f 798 819 820 +f 821 780 797 +f 797 820 821 +f 783 780 821 +f 822 787 783 +f 783 821 822 +f 823 788 787 +f 787 822 823 +f 824 785 788 +f 788 823 824 +f 784 785 824 +f 824 825 784 +f 829 828 827 +f 827 826 829 +f 786 828 829 +f 829 830 786 +f 832 781 782 +f 782 831 832 +f 776 777 832 +f 832 833 776 +f 803 802 799 +f 799 834 803 +f 779 776 836 +f 836 835 779 +f 800 792 789 +f 789 799 800 +f 799 789 779 +f 779 835 799 +f 791 792 807 +f 807 808 791 +f 836 776 833 +f 833 837 836 +f 781 777 778 +f 781 832 777 +f 830 825 824 +f 824 831 830 +f 797 839 838 +f 838 778 797 +f 781 841 840 +f 840 780 781 +f 778 838 841 +f 841 781 778 +f 780 840 839 +f 839 797 780 +f 839 843 842 +f 842 838 839 +f 841 845 844 +f 844 840 841 +f 838 842 845 +f 845 841 838 +f 840 844 843 +f 843 839 840 +f 843 847 846 +f 846 842 843 +f 845 849 848 +f 848 844 845 +f 842 846 849 +f 849 845 842 +f 844 848 847 +f 847 843 844 +f 847 851 850 +f 850 846 847 +f 849 853 852 +f 852 848 849 +f 846 850 854 +f 854 849 846 +f 854 853 849 +f 848 852 855 +f 855 847 848 +f 855 851 847 +f 854 850 851 +f 851 855 854 +f 853 854 855 +f 855 852 853 +f 828 786 784 +f 784 827 828 +f 827 784 825 +f 825 826 827 +f 782 786 830 +f 830 831 782 +f 826 825 830 +f 830 829 826 +f 809 775 773 +f 773 791 809 +f 811 812 813 +f 813 814 811 +f 816 774 815 +f 815 813 816 +f 775 809 811 +f 811 814 775 +f 775 857 856 +f 856 774 775 +f 814 857 775 +f 815 856 857 +f 857 814 815 +f 774 856 815 +f 860 859 858 +f 864 863 862 +f 862 861 864 +f 868 867 866 +f 866 865 868 +f 871 867 870 +f 870 869 871 +f 866 871 873 +f 873 872 866 +f 877 876 875 +f 875 874 877 +f 863 877 874 +f 874 862 863 +f 879 860 858 +f 858 878 879 +f 858 881 880 +f 880 878 858 +f 881 883 882 +f 882 880 881 +f 876 877 881 +f 881 858 876 +f 877 863 883 +f 883 881 877 +f 871 866 867 +f 884 805 803 +f 803 834 884 +f 805 884 806 +f 806 804 805 +f 806 884 875 +f 875 807 806 +f 876 885 810 +f 810 808 876 +f 885 886 812 +f 812 810 885 +f 888 887 813 +f 860 879 817 +f 817 816 860 +f 879 878 818 +f 818 817 879 +f 878 880 818 +f 880 882 819 +f 819 818 880 +f 882 883 820 +f 820 819 882 +f 883 865 821 +f 821 820 883 +f 866 821 865 +f 866 872 822 +f 822 821 866 +f 872 873 823 +f 823 822 872 +f 873 871 824 +f 824 823 873 +f 824 871 869 +f 869 889 824 +f 893 892 891 +f 891 890 893 +f 891 892 870 +f 870 894 891 +f 867 868 832 +f 832 831 867 +f 832 864 861 +f 861 833 832 +f 896 861 862 +f 862 895 896 +f 874 875 884 +f 884 834 874 +f 862 874 834 +f 834 895 862 +f 807 875 876 +f 876 808 807 +f 833 861 896 +f 896 837 833 +f 864 868 863 +f 832 868 864 +f 824 889 894 +f 894 831 824 +f 898 897 883 +f 883 863 898 +f 900 899 868 +f 868 865 900 +f 899 898 863 +f 863 868 899 +f 897 900 865 +f 865 883 897 +f 902 901 897 +f 897 898 902 +f 904 903 899 +f 899 900 904 +f 903 902 898 +f 898 899 903 +f 901 904 900 +f 900 897 901 +f 906 905 901 +f 901 902 906 +f 908 907 903 +f 903 904 908 +f 907 906 902 +f 902 903 907 +f 905 908 904 +f 904 901 905 +f 910 909 905 +f 905 906 910 +f 912 911 907 +f 907 908 912 +f 911 913 910 +f 910 907 911 +f 910 906 907 +f 909 914 912 +f 912 905 909 +f 912 908 905 +f 909 910 913 +f 913 914 909 +f 914 913 911 +f 911 912 914 +f 869 870 892 +f 892 893 869 +f 889 869 893 +f 893 890 889 +f 894 870 867 +f 867 831 894 +f 894 889 890 +f 890 891 894 +f 858 859 885 +f 885 876 858 +f 813 812 886 +f 886 888 813 +f 887 860 816 +f 816 813 887 +f 886 885 859 +f 859 888 886 +f 916 915 859 +f 859 860 916 +f 915 888 859 +f 915 916 887 +f 887 888 915 +f 916 860 887 +f 837 896 836 +f 834 799 835 +f 835 895 834 +f 895 835 836 +f 836 896 895 +f 920 919 918 +f 918 917 920 +f 922 921 919 +f 919 920 922 +f 924 923 921 +f 921 922 924 +f 926 925 923 +f 923 924 926 +f 928 927 925 +f 925 926 928 +f 917 918 927 +f 927 928 917 +f 924 922 917 +f 917 926 924 +f 920 917 922 +f 926 917 928 +f 931 930 929 +f 935 934 933 +f 933 932 935 +f 933 937 936 +f 936 932 933 +f 940 939 938 +f 938 935 940 +f 938 939 942 +f 942 941 938 +f 943 937 933 +f 933 934 943 +f 937 945 944 +f 944 936 937 +f 947 946 939 +f 939 940 947 +f 943 948 945 +f 945 937 943 +f 952 951 950 +f 950 949 952 +f 941 934 935 +f 935 938 941 +f 936 940 935 +f 935 932 936 +f 942 943 934 +f 934 941 942 +f 944 947 940 +f 940 936 944 +f 942 953 948 +f 948 943 942 +f 946 947 948 +f 948 953 946 +f 945 950 951 +f 951 944 945 +f 948 949 950 +f 950 945 948 +f 947 952 949 +f 949 948 947 +f 944 951 952 +f 952 947 944 +f 939 955 954 +f 954 942 939 +f 946 956 955 +f 955 939 946 +f 942 954 957 +f 957 953 942 +f 953 957 956 +f 956 946 953 +f 955 959 958 +f 958 954 955 +f 956 960 959 +f 959 955 956 +f 954 958 961 +f 961 957 954 +f 957 961 960 +f 960 956 957 +f 959 963 962 +f 962 958 959 +f 960 964 963 +f 963 959 960 +f 958 962 965 +f 965 961 958 +f 961 965 964 +f 964 960 961 +f 963 967 966 +f 966 962 963 +f 964 968 967 +f 967 963 964 +f 962 966 969 +f 969 965 962 +f 965 969 968 +f 968 964 965 +f 969 966 967 +f 967 968 969 +f 973 972 971 +f 971 970 973 +f 970 975 974 +f 974 973 970 +f 973 974 976 +f 976 972 973 +f 972 976 977 +f 977 971 972 +f 971 977 975 +f 975 970 971 +f 975 979 978 +f 978 974 975 +f 974 978 980 +f 980 976 974 +f 976 980 981 +f 981 977 976 +f 977 981 979 +f 979 975 977 +f 979 983 982 +f 982 978 979 +f 978 982 984 +f 984 980 978 +f 980 984 985 +f 985 981 980 +f 981 985 983 +f 983 979 981 +f 983 987 986 +f 986 982 983 +f 982 986 988 +f 988 984 982 +f 984 988 989 +f 989 985 984 +f 985 989 987 +f 987 983 985 +f 987 991 990 +f 990 986 987 +f 988 993 992 +f 992 989 988 +f 986 995 994 +f 994 988 986 +f 989 997 996 +f 996 987 989 +f 987 996 998 +f 998 991 987 +f 990 999 995 +f 995 986 990 +f 988 994 1000 +f 1000 993 988 +f 992 1001 997 +f 997 989 992 +f 991 998 999 +f 999 990 991 +f 993 1000 1001 +f 1001 992 993 +f 999 1001 1000 +f 1000 994 999 +f 997 1001 999 +f 999 996 997 +f 999 998 996 +f 999 994 995 +f 1005 1004 1003 +f 1003 1002 1005 +f 1005 1006 1004 +f 1008 1005 1002 +f 1002 1007 1008 +f 1007 1002 1009 +f 1002 1011 1010 +f 1010 1009 1002 +f 1003 1012 1011 +f 1011 1002 1003 +f 1004 1013 1012 +f 1012 1003 1004 +f 1006 1014 1013 +f 1013 1004 1006 +f 1005 1015 1014 +f 1014 1006 1005 +f 1008 1016 1015 +f 1015 1005 1008 +f 1007 1017 1016 +f 1016 1008 1007 +f 1009 1010 1017 +f 1017 1007 1009 +f 1021 1020 1019 +f 1019 1018 1021 +f 1021 1022 1020 +f 1024 1021 1018 +f 1018 1023 1024 +f 1023 1018 1025 +f 1018 1027 1026 +f 1026 1025 1018 +f 1019 1028 1027 +f 1027 1018 1019 +f 1020 1029 1028 +f 1028 1019 1020 +f 1022 1030 1029 +f 1029 1020 1022 +f 1021 1031 1030 +f 1030 1022 1021 +f 1024 1032 1031 +f 1031 1021 1024 +f 1023 1033 1032 +f 1032 1024 1023 +f 1025 1026 1033 +f 1033 1023 1025 +f 1037 1036 1035 +f 1035 1034 1037 +f 1037 1038 1036 +f 1040 1037 1034 +f 1034 1039 1040 +f 1039 1034 1041 +f 1034 1043 1042 +f 1042 1041 1034 +f 1035 1044 1043 +f 1043 1034 1035 +f 1036 1045 1044 +f 1044 1035 1036 +f 1038 1046 1045 +f 1045 1036 1038 +f 1037 1047 1046 +f 1046 1038 1037 +f 1040 1048 1047 +f 1047 1037 1040 +f 1039 1049 1048 +f 1048 1040 1039 +f 1041 1042 1049 +f 1049 1039 1041 +f 1050 1053 1052 +f 1052 1051 1050 +f 1054 1055 1053 +f 1053 1050 1054 +f 1056 1057 1055 +f 1055 1054 1056 +f 1058 1059 1057 +f 1057 1056 1058 +f 1060 1061 1059 +f 1059 1058 1060 +f 1062 1063 1061 +f 1061 1060 1062 +f 1064 1052 1066 +f 1066 1065 1064 +f 1052 1053 1067 +f 1067 1066 1052 +f 1053 1055 1068 +f 1068 1067 1053 +f 1055 1057 1069 +f 1069 1068 1055 +f 1057 1059 1070 +f 1070 1069 1057 +f 1059 1061 1071 +f 1071 1070 1059 +f 1061 1063 1072 +f 1072 1071 1061 +f 1063 1064 1065 +f 1065 1072 1063 +f 1051 1075 1074 +f 1074 1073 1051 +f 1050 1051 1073 +f 1073 1076 1050 +f 1054 1050 1076 +f 1076 1077 1054 +f 1056 1054 1077 +f 1077 1078 1056 +f 1058 1056 1078 +f 1078 1079 1058 +f 1060 1058 1079 +f 1079 1080 1060 +f 1062 1060 1080 +f 1080 1081 1062 +f 1075 1062 1081 +f 1081 1074 1075 +f 1065 1066 1073 +f 1073 1074 1065 +f 1072 1065 1074 +f 1074 1081 1072 +f 1071 1072 1081 +f 1081 1080 1071 +f 1070 1071 1080 +f 1080 1079 1070 +f 1069 1070 1079 +f 1079 1078 1069 +f 1068 1069 1078 +f 1078 1077 1068 +f 1067 1068 1077 +f 1077 1076 1067 +f 1066 1067 1076 +f 1076 1073 1066 +f 1082 1085 1084 +f 1084 1083 1082 +f 1086 1087 1085 +f 1085 1082 1086 +f 1088 1089 1087 +f 1087 1086 1088 +f 1090 1091 1089 +f 1089 1088 1090 +f 1091 1094 1093 +f 1093 1092 1091 +f 1094 1096 1095 +f 1095 1093 1094 +f 1096 1098 1097 +f 1097 1095 1096 +f 1098 1084 1099 +f 1099 1097 1098 +f 1084 1085 1100 +f 1100 1099 1084 +f 1085 1087 1101 +f 1101 1100 1085 +f 1087 1089 1102 +f 1102 1101 1087 +f 1089 1091 1092 +f 1092 1102 1089 +f 1103 1106 1105 +f 1105 1104 1103 +f 1107 1103 1104 +f 1104 1108 1107 +f 1109 1107 1108 +f 1108 1110 1109 +f 1111 1109 1110 +f 1110 1112 1111 +f 1113 1111 1112 +f 1112 1114 1113 +f 1115 1113 1114 +f 1114 1116 1115 +f 1117 1115 1116 +f 1116 1118 1117 +f 1106 1117 1118 +f 1118 1105 1106 +f 1111 1113 1120 +f 1120 1119 1111 +f 1113 1115 1121 +f 1121 1120 1113 +f 1115 1117 1122 +f 1122 1121 1115 +f 1117 1106 1123 +f 1123 1122 1117 +f 1124 1090 1126 +f 1126 1125 1124 +f 1127 1124 1125 +f 1125 1128 1127 +f 1129 1127 1128 +f 1128 1130 1129 +f 1083 1129 1130 +f 1130 1131 1083 +f 1082 1083 1131 +f 1131 1132 1082 +f 1086 1082 1132 +f 1132 1133 1086 +f 1088 1086 1133 +f 1133 1134 1088 +f 1090 1088 1134 +f 1134 1126 1090 +f 1123 1137 1136 +f 1136 1135 1123 +f 1137 1139 1138 +f 1138 1136 1137 +f 1139 1141 1140 +f 1140 1138 1139 +f 1141 1119 1142 +f 1142 1140 1141 +f 1119 1120 1143 +f 1143 1142 1119 +f 1120 1121 1144 +f 1144 1143 1120 +f 1121 1122 1145 +f 1145 1144 1121 +f 1122 1123 1135 +f 1135 1145 1122 +f 1108 1104 1136 +f 1136 1138 1108 +f 1110 1108 1138 +f 1138 1140 1110 +f 1112 1110 1140 +f 1140 1142 1112 +f 1114 1112 1142 +f 1142 1143 1114 +f 1116 1114 1143 +f 1143 1144 1116 +f 1118 1116 1144 +f 1144 1145 1118 +f 1105 1118 1145 +f 1145 1135 1105 +f 1104 1105 1135 +f 1135 1136 1104 +f 1100 1101 1133 +f 1133 1132 1100 +f 1099 1100 1132 +f 1132 1131 1099 +f 1097 1099 1131 +f 1131 1130 1097 +f 1095 1097 1130 +f 1130 1128 1095 +f 1093 1095 1128 +f 1128 1125 1093 +f 1092 1093 1125 +f 1125 1126 1092 +f 1102 1092 1126 +f 1126 1134 1102 +f 1101 1102 1134 +f 1134 1133 1101 +f 1094 1091 1147 +f 1147 1146 1094 +f 1090 1124 1149 +f 1149 1148 1090 +f 1091 1090 1148 +f 1148 1147 1091 +f 1096 1094 1146 +f 1146 1150 1096 +f 1124 1127 1151 +f 1151 1149 1124 +f 1098 1096 1150 +f 1150 1152 1098 +f 1127 1129 1153 +f 1153 1151 1127 +f 1084 1098 1152 +f 1152 1154 1084 +f 1083 1084 1154 +f 1154 1155 1083 +f 1129 1083 1155 +f 1155 1153 1129 +f 1106 1103 1157 +f 1157 1156 1106 +f 1103 1107 1158 +f 1158 1157 1103 +f 1107 1109 1159 +f 1159 1158 1107 +f 1109 1111 1160 +f 1160 1159 1109 +f 1123 1106 1156 +f 1156 1161 1123 +f 1137 1123 1161 +f 1161 1162 1137 +f 1139 1137 1162 +f 1162 1163 1139 +f 1141 1139 1163 +f 1163 1164 1141 +f 1111 1119 1165 +f 1165 1160 1111 +f 1119 1141 1164 +f 1164 1165 1119 +f 1052 1064 1167 +f 1167 1166 1052 +f 1064 1063 1168 +f 1168 1167 1064 +f 1051 1052 1166 +f 1166 1169 1051 +f 1063 1062 1170 +f 1170 1168 1063 +f 1075 1051 1169 +f 1169 1171 1075 +f 1062 1075 1171 +f 1171 1170 1062 +f 1172 1174 1173 +# 1978 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/pelvis_chull.obj b/examples/Atlas/urdf/mesh/pelvis_chull.obj new file mode 100644 index 0000000..26b23f4 --- /dev/null +++ b/examples/Atlas/urdf/mesh/pelvis_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object pelvis_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.147139 0.122397 0.068708 +v 0.172313 0.096042 0.119280 +v -0.134683 0.116482 0.119250 +v 0.147138 -0.121676 0.068708 +v -0.151696 -0.089549 0.119413 +v 0.063722 0.185485 0.119142 +v -0.119669 0.128081 0.068295 +v -0.043540 -0.184810 0.119218 +v -0.043541 0.185531 0.119219 +v 0.170902 -0.097129 0.119330 +v -0.153509 -0.060495 -0.103875 +v -0.119669 -0.127359 0.068295 +v -0.092783 -0.061635 -0.146689 +v -0.128180 -0.071135 -0.144489 +v -0.128180 0.071856 -0.144489 +v -0.092783 0.062357 -0.146689 +v 0.175348 0.035890 -0.011993 +v 0.063088 0.188426 0.072787 +v -0.042682 0.186211 0.067682 +v -0.152584 0.080952 0.119296 +v 0.043023 0.001902 0.127669 +v 0.175330 -0.031061 -0.017519 +v -0.155606 0.058104 -0.105442 +v -0.042682 -0.185490 0.067682 +v 0.063088 -0.187705 0.072787 +v 0.063667 -0.184787 0.119160 +v 0.137219 0.000361 -0.104170 +# 27 vertices, 0 vertices normals + +f 18 15 16 +f 15 7 23 +f 19 7 15 +f 10 2 22 +f 17 2 1 +f 6 18 1 +f 4 10 22 +f 3 20 23 +f 27 18 16 +f 27 1 18 +f 22 17 27 +f 27 17 1 +f 6 2 21 +f 2 6 1 +f 3 21 20 +f 21 3 9 +f 10 26 21 +f 25 13 14 +f 9 7 19 +f 9 3 7 +f 7 3 23 +f 11 14 23 +f 21 8 5 +f 13 25 27 +f 25 4 27 +f 27 4 22 +f 5 23 20 +f 5 11 23 +f 4 25 26 +f 12 24 14 +f 12 8 24 +f 12 5 8 +f 4 26 10 +f 5 12 11 +f 11 12 14 +f 13 15 14 +f 13 16 15 +f 18 19 15 +f 5 20 21 +f 21 2 10 +f 24 25 14 +f 2 17 22 +f 9 18 6 +f 18 9 19 +f 24 8 25 +f 8 26 25 +f 16 13 27 +f 23 14 15 +f 8 21 26 +f 9 6 21 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_clav.obj b/examples/Atlas/urdf/mesh/r_clav.obj new file mode 100644 index 0000000..7fcca21 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_clav.obj @@ -0,0 +1,898 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_clav.obj +# +# Vertices: 326 +# Faces: 556 +# +#### +v -0.054377 -0.113772 -0.292824 +v -0.054377 -0.084444 -0.281406 +v -0.054377 -0.068839 -0.252495 +v -0.054377 -0.074259 -0.219619 +v -0.054377 -0.098167 -0.198160 +v -0.054377 -0.129377 -0.198160 +v -0.054377 -0.153285 -0.219619 +v -0.054377 -0.158705 -0.252495 +v -0.054377 -0.143100 -0.281406 +v 0.018171 -0.113772 -0.292824 +v 0.018170 -0.084444 -0.281406 +v 0.018170 -0.068839 -0.252495 +v 0.018171 -0.074259 -0.219619 +v 0.018170 -0.098167 -0.198160 +v 0.018170 -0.129377 -0.198160 +v 0.018170 -0.153285 -0.219619 +v 0.018170 -0.158705 -0.252495 +v 0.018170 -0.143100 -0.281406 +v -0.014744 -0.057897 -0.157924 +v -0.014744 -0.023038 -0.157923 +v -0.014744 -0.057897 -0.150185 +v -0.014744 -0.023038 -0.150185 +v 0.005071 -0.057909 -0.157924 +v 0.005071 -0.023051 -0.157924 +v 0.005071 -0.057909 -0.150185 +v 0.005071 -0.023051 -0.150185 +v -0.014580 -0.063090 -0.152345 +v -0.014580 -0.059840 -0.159368 +v 0.005236 -0.059852 -0.159368 +v 0.005236 -0.063103 -0.152345 +v -0.014521 -0.068935 -0.160963 +v -0.014521 -0.065685 -0.167986 +v 0.005294 -0.065697 -0.167986 +v 0.005294 -0.068947 -0.160963 +v -0.014803 -0.093418 -0.203815 +v -0.014593 -0.089705 -0.208791 +v 0.005223 -0.089717 -0.208791 +v 0.005013 -0.093430 -0.203815 +v -0.014744 -0.027744 -0.150185 +v -0.014744 -0.030028 -0.157924 +v 0.005071 -0.030040 -0.157924 +v 0.005071 -0.027757 -0.150185 +v -0.022683 -0.027744 -0.178606 +v -0.022683 -0.023038 -0.178605 +v 0.013010 -0.023051 -0.178606 +v 0.013010 -0.027757 -0.178605 +v -0.014744 -0.027744 -0.168161 +v -0.014744 -0.023038 -0.168161 +v 0.005071 -0.023051 -0.168161 +v 0.005071 -0.027757 -0.168161 +v -0.017226 -0.027744 -0.174148 +v -0.017226 -0.023038 -0.174148 +v 0.007553 -0.023051 -0.174148 +v 0.007553 -0.027757 -0.174148 +v -0.014744 -0.027744 -0.156109 +v -0.014744 -0.025461 -0.157924 +v -0.014744 -0.027744 -0.159738 +v 0.005071 -0.027757 -0.159738 +v 0.005071 -0.025473 -0.157923 +v 0.005071 -0.027757 -0.156109 +v -0.026038 -0.030123 -0.204201 +v -0.026038 0.013775 -0.202898 +v -0.026037 -0.043750 -0.177411 +v -0.026037 0.013766 -0.177411 +v 0.019173 -0.030123 -0.204201 +v 0.011636 0.022831 -0.202629 +v 0.019183 -0.043750 -0.177411 +v 0.011784 0.022826 -0.177411 +v -0.026039 -0.036273 -0.210044 +v -0.026037 -0.070351 -0.177411 +v 0.019170 -0.036273 -0.210044 +v 0.019183 -0.070351 -0.177411 +v -0.023574 -0.045694 -0.227734 +v -0.025996 -0.084496 -0.205136 +v 0.021589 -0.045694 -0.227734 +v 0.019506 -0.086788 -0.205006 +v -0.019892 0.022831 -0.202629 +v -0.019744 0.022826 -0.177411 +v 0.019173 0.013775 -0.202898 +v 0.019183 0.013766 -0.177411 +v 0.017111 -0.086175 -0.205561 +v 0.062730 -0.086175 -0.205561 +v 0.017111 -0.046481 -0.229508 +v 0.062730 -0.046481 -0.229508 +v 0.017111 -0.077407 -0.191028 +v 0.062730 -0.077407 -0.191028 +v 0.017111 -0.037713 -0.214974 +v 0.062730 -0.037713 -0.214974 +v 0.017241 -0.068659 -0.195896 +v 0.039658 -0.068659 -0.195896 +v 0.017241 -0.045456 -0.209893 +v 0.039658 -0.045456 -0.209893 +v 0.017241 -0.058697 -0.179384 +v 0.039658 -0.058697 -0.179384 +v 0.017241 -0.035495 -0.193381 +v 0.039658 -0.035495 -0.193381 +v -0.054735 -0.086175 -0.205561 +v -0.046624 -0.086175 -0.205561 +v -0.054735 -0.046481 -0.229508 +v -0.046624 -0.046481 -0.229508 +v -0.054735 -0.077407 -0.191028 +v -0.046624 -0.077407 -0.191028 +v -0.054735 -0.037713 -0.214974 +v -0.046624 -0.037713 -0.214974 +v -0.048071 -0.082403 -0.199634 +v -0.025588 -0.082403 -0.199634 +v -0.048071 -0.042709 -0.223581 +v -0.025588 -0.042709 -0.223581 +v -0.048071 -0.079740 -0.195219 +v -0.025588 -0.079740 -0.195219 +v -0.048071 -0.040045 -0.219166 +v -0.025588 -0.040045 -0.219166 +v -0.053689 -0.115865 -0.255953 +v -0.053689 -0.077299 -0.280079 +v -0.053689 -0.081214 -0.200564 +v -0.053689 -0.042649 -0.224690 +v 0.052029 -0.115865 -0.255953 +v 0.052029 -0.077299 -0.280079 +v 0.052029 -0.081214 -0.200564 +v 0.052029 -0.042649 -0.224690 +v 0.050434 -0.060967 -0.251388 +v -0.041855 -0.060967 -0.251388 +v 0.050434 -0.043724 -0.221909 +v -0.041855 -0.043724 -0.221909 +v 0.050434 -0.035391 -0.266348 +v -0.041855 -0.035391 -0.266347 +v 0.050434 -0.018149 -0.236869 +v -0.041855 -0.018149 -0.236869 +v 0.009460 -0.043724 -0.221909 +v 0.009460 -0.060967 -0.251388 +v 0.009460 -0.035391 -0.266348 +v 0.009460 -0.018149 -0.236869 +v 0.009460 -0.050770 -0.292640 +v 0.050434 -0.050770 -0.292640 +v 0.050434 -0.076345 -0.277680 +v 0.009460 -0.076345 -0.277680 +v 0.049236 -0.042736 -0.223012 +v 0.049236 -0.040757 -0.219628 +v 0.009372 -0.040757 -0.219628 +v 0.009372 -0.042736 -0.223012 +v 0.049236 -0.020485 -0.236027 +v 0.009372 -0.020485 -0.236027 +v 0.009372 -0.018506 -0.232643 +v 0.049236 -0.018506 -0.232643 +v -0.040552 -0.042736 -0.223012 +v -0.040552 -0.040757 -0.219628 +v -0.040552 -0.018506 -0.232643 +v -0.040552 -0.020485 -0.236027 +v 0.043524 0.011083 -0.141351 +v 0.065284 0.011083 -0.141351 +v 0.043524 -0.009304 -0.141351 +v 0.065284 -0.009304 -0.141351 +v 0.043524 0.021696 -0.148793 +v 0.043449 0.011082 -0.148793 +v 0.043449 -0.009304 -0.148793 +v 0.043524 -0.019917 -0.148793 +v 0.065284 -0.019917 -0.148793 +v 0.065444 -0.009304 -0.148793 +v 0.065444 0.011083 -0.148793 +v 0.065284 0.021696 -0.148793 +v 0.043524 0.021696 -0.162581 +v 0.043449 0.011083 -0.162581 +v 0.043449 -0.009304 -0.162581 +v 0.043524 -0.019917 -0.162581 +v 0.065284 -0.019917 -0.162581 +v 0.065444 -0.009304 -0.162581 +v 0.065444 0.011083 -0.162581 +v 0.065284 0.021696 -0.162581 +v 0.065284 -0.009304 -0.170023 +v 0.043524 -0.009304 -0.170023 +v 0.065284 0.011083 -0.170023 +v 0.043524 0.011083 -0.170023 +v 0.042887 0.021489 -0.141506 +v 0.042887 -0.021099 -0.141505 +v 0.050226 -0.021099 -0.141505 +v 0.050226 0.021489 -0.141505 +v 0.042887 0.021489 -0.171502 +v 0.042887 -0.021099 -0.171502 +v 0.050226 -0.021099 -0.171502 +v 0.050226 0.021489 -0.171502 +v 0.030067 0.018745 -0.145470 +v 0.030067 -0.020945 -0.145470 +v 0.050063 -0.020945 -0.145470 +v 0.050063 0.018745 -0.145470 +v 0.030067 0.018745 -0.167103 +v 0.030067 -0.020944 -0.167103 +v 0.050063 -0.020944 -0.167103 +v 0.050063 0.018745 -0.167103 +v 0.025968 0.016904 -0.138979 +v 0.030370 0.016904 -0.138979 +v 0.025968 -0.015125 -0.138979 +v 0.030370 -0.015125 -0.138979 +v 0.025968 0.024111 -0.147285 +v 0.025953 0.016904 -0.147285 +v 0.025953 -0.015125 -0.147285 +v 0.025968 -0.022333 -0.147285 +v 0.030370 -0.022333 -0.147285 +v 0.030402 -0.015125 -0.147285 +v 0.030402 0.016904 -0.147285 +v 0.030370 0.024111 -0.147285 +v 0.025968 0.024111 -0.165584 +v 0.025953 0.016904 -0.165584 +v 0.025953 -0.015125 -0.165584 +v 0.025968 -0.022333 -0.165584 +v 0.030370 -0.022333 -0.165584 +v 0.030402 -0.015125 -0.165584 +v 0.030402 0.016904 -0.165584 +v 0.030370 0.024111 -0.165584 +v 0.030370 -0.015125 -0.172375 +v 0.025968 -0.015125 -0.172375 +v 0.030370 0.016904 -0.172375 +v 0.025968 0.016904 -0.172375 +v 0.001042 -0.110123 -0.286865 +v 0.001042 -0.085601 -0.277318 +v 0.001042 -0.072553 -0.253145 +v 0.001042 -0.077085 -0.225656 +v 0.001042 -0.097075 -0.207714 +v 0.001042 -0.123170 -0.207714 +v 0.001042 -0.143161 -0.225656 +v 0.001042 -0.147692 -0.253145 +v 0.001042 -0.134644 -0.277318 +v 0.053160 -0.110123 -0.286865 +v 0.053160 -0.085601 -0.277318 +v 0.053160 -0.072553 -0.253145 +v 0.053160 -0.077085 -0.225656 +v 0.053160 -0.097075 -0.207714 +v 0.053160 -0.123170 -0.207714 +v 0.053160 -0.143161 -0.225656 +v 0.053160 -0.147692 -0.253145 +v 0.053160 -0.134644 -0.277318 +v -0.004365 -0.026968 -0.154205 +v -0.004365 -0.033885 -0.154205 +v -0.004365 -0.060141 -0.154169 +v -0.004365 -0.069808 -0.174597 +v -0.004365 -0.027003 -0.158576 +v -0.004365 -0.032828 -0.158576 +v -0.004365 -0.035000 -0.161729 +v -0.004365 -0.035043 -0.174087 +v -0.004365 -0.072641 -0.179222 +v -0.004365 -0.026949 -0.179222 +v -0.004365 -0.026991 -0.177641 +v -0.004365 -0.033176 -0.177641 +v -0.008324 -0.026968 -0.154205 +v -0.008324 -0.033885 -0.154205 +v -0.008324 -0.060141 -0.154169 +v -0.008324 -0.069808 -0.174597 +v -0.008324 -0.027003 -0.158576 +v -0.008324 -0.032828 -0.158576 +v -0.008324 -0.035000 -0.161729 +v -0.008324 -0.035043 -0.174087 +v -0.008324 -0.072641 -0.179221 +v -0.008324 -0.026949 -0.179221 +v -0.008324 -0.026991 -0.177641 +v -0.008324 -0.033176 -0.177641 +v 0.025001 0.017708 -0.113760 +v 0.025001 -0.018809 -0.113760 +v 0.025001 -0.018809 -0.178212 +v 0.025001 0.017708 -0.178212 +v 0.020179 0.022352 -0.113760 +v 0.020179 0.017708 -0.113538 +v 0.020179 -0.018809 -0.113538 +v 0.020179 -0.023453 -0.113760 +v 0.020179 -0.023453 -0.178212 +v 0.020179 -0.018809 -0.178684 +v 0.020179 0.017708 -0.178684 +v 0.020179 0.022352 -0.178212 +v -0.018575 0.022352 -0.113760 +v -0.018575 0.017708 -0.113538 +v -0.018575 -0.018809 -0.113538 +v -0.018575 -0.023453 -0.113760 +v -0.018575 -0.023453 -0.178212 +v -0.018575 -0.018809 -0.178684 +v -0.018575 0.017708 -0.178684 +v -0.018575 0.022352 -0.178212 +v -0.023397 0.017708 -0.113760 +v -0.023397 -0.018809 -0.113760 +v -0.023397 -0.018809 -0.178212 +v -0.023397 0.017708 -0.178212 +v -0.048071 -0.071156 -0.200310 +v -0.048071 -0.048552 -0.213947 +v -0.026667 -0.048552 -0.213947 +v -0.026667 -0.071156 -0.200310 +v -0.048071 -0.068492 -0.195895 +v -0.026667 -0.064606 -0.189453 +v -0.026667 -0.042002 -0.203090 +v -0.048071 -0.045888 -0.209532 +v -0.031658 -0.048552 -0.213947 +v -0.031658 -0.071156 -0.200310 +v -0.031658 -0.067907 -0.194926 +v -0.031658 -0.045303 -0.208562 +v -0.036090 -0.048552 -0.213947 +v -0.036090 -0.068566 -0.196018 +v -0.036090 -0.071156 -0.200310 +v -0.036090 -0.045963 -0.209655 +v -0.046687 -0.083460 -0.205503 +v -0.046687 -0.078566 -0.197680 +v -0.046687 -0.041213 -0.221047 +v -0.046687 -0.046108 -0.228871 +v -0.029205 -0.083460 -0.205503 +v -0.029205 -0.046108 -0.228871 +v -0.029205 -0.041213 -0.221047 +v -0.029205 -0.078566 -0.197680 +v 0.037943 0.002745 -0.133263 +v 0.060187 0.002745 -0.133263 +v 0.037943 -0.002689 -0.133263 +v 0.060187 -0.002689 -0.133263 +v 0.037943 0.005574 -0.135527 +v 0.037867 0.002745 -0.135527 +v 0.037867 -0.002689 -0.135527 +v 0.037943 -0.005518 -0.135527 +v 0.060187 -0.005518 -0.135527 +v 0.060350 -0.002689 -0.135527 +v 0.060350 0.002745 -0.135527 +v 0.060187 0.005574 -0.135527 +v 0.037943 0.005574 -0.139721 +v 0.037867 0.002745 -0.139721 +v 0.037867 -0.002689 -0.139721 +v 0.037943 -0.005518 -0.139721 +v 0.060187 -0.005518 -0.139721 +v 0.060350 -0.002689 -0.139721 +v 0.060350 0.002745 -0.139721 +v 0.060187 0.005574 -0.139721 +v 0.060187 -0.002689 -0.141985 +v 0.037943 -0.002689 -0.141985 +v 0.060187 0.002745 -0.141985 +v 0.037943 0.002745 -0.141985 +# 326 vertices, 0 vertices normals + +f 1 2 11 +f 11 10 1 +f 2 3 12 +f 12 11 2 +f 3 4 13 +f 13 12 3 +f 4 5 14 +f 14 13 4 +f 5 6 15 +f 15 14 5 +f 6 7 16 +f 16 15 6 +f 7 8 17 +f 17 16 7 +f 8 9 18 +f 18 17 8 +f 9 1 10 +f 10 18 9 +f 8 7 6 +f 6 2 8 +f 6 5 4 +f 4 2 6 +f 4 3 2 +f 8 2 1 +f 1 9 8 +f 11 12 13 +f 13 17 11 +f 13 14 15 +f 15 17 13 +f 15 16 17 +f 11 17 18 +f 18 10 11 +f 39 55 40 +f 40 21 39 +f 19 21 40 +f 23 41 60 +f 60 25 23 +f 60 42 25 +f 40 41 23 +f 23 19 40 +f 20 22 26 +f 26 24 20 +f 39 42 26 +f 26 22 39 +f 35 36 37 +f 37 38 35 +f 21 19 28 +f 28 27 21 +f 19 23 29 +f 29 28 19 +f 23 25 30 +f 30 29 23 +f 25 21 27 +f 27 30 25 +f 27 28 32 +f 32 31 27 +f 28 29 33 +f 33 32 28 +f 29 30 34 +f 34 33 29 +f 30 27 31 +f 31 34 30 +f 31 32 36 +f 36 35 31 +f 32 33 37 +f 37 36 32 +f 33 34 38 +f 38 37 33 +f 34 31 35 +f 35 38 34 +f 20 56 55 +f 55 22 20 +f 39 22 55 +f 24 26 42 +f 42 59 24 +f 60 59 42 +f 44 45 46 +f 46 43 44 +f 21 25 42 +f 42 39 21 +f 20 48 47 +f 47 56 20 +f 57 56 47 +f 24 49 48 +f 48 20 24 +f 24 59 58 +f 58 49 24 +f 58 50 49 +f 57 47 50 +f 50 58 57 +f 52 51 47 +f 47 48 52 +f 53 52 48 +f 48 49 53 +f 54 53 49 +f 49 50 54 +f 51 54 50 +f 50 47 51 +f 44 43 51 +f 51 52 44 +f 45 44 52 +f 52 53 45 +f 46 45 53 +f 53 54 46 +f 43 46 54 +f 54 51 43 +f 40 55 56 +f 56 57 40 +f 41 58 59 +f 59 60 41 +f 58 41 40 +f 40 57 58 +f 61 63 64 +f 64 62 61 +f 65 79 80 +f 80 67 65 +f 61 62 77 +f 77 79 61 +f 77 66 79 +f 61 79 65 +f 77 78 68 +f 68 66 77 +f 64 63 67 +f 67 68 64 +f 67 80 68 +f 78 64 68 +f 63 61 69 +f 69 70 63 +f 65 67 72 +f 72 71 65 +f 61 65 71 +f 71 69 61 +f 67 63 70 +f 70 72 67 +f 70 69 73 +f 73 74 70 +f 71 72 76 +f 76 75 71 +f 69 71 75 +f 75 73 69 +f 72 70 74 +f 74 76 72 +f 64 78 77 +f 77 62 64 +f 79 66 68 +f 68 80 79 +f 81 83 84 +f 84 82 81 +f 85 86 88 +f 88 87 85 +f 81 82 86 +f 86 85 81 +f 82 84 88 +f 88 86 82 +f 84 83 87 +f 87 88 84 +f 83 81 85 +f 85 87 83 +f 89 91 92 +f 92 90 89 +f 93 94 96 +f 96 95 93 +f 89 90 94 +f 94 93 89 +f 90 92 96 +f 96 94 90 +f 92 91 95 +f 95 96 92 +f 91 89 93 +f 93 95 91 +f 97 99 100 +f 100 98 97 +f 101 102 104 +f 104 103 101 +f 97 98 102 +f 102 101 97 +f 98 100 104 +f 104 102 98 +f 100 99 103 +f 103 104 100 +f 99 97 101 +f 101 103 99 +f 105 107 108 +f 108 106 105 +f 109 110 112 +f 112 111 109 +f 105 106 110 +f 110 109 105 +f 106 108 112 +f 112 110 106 +f 108 107 111 +f 111 112 108 +f 107 105 109 +f 109 111 107 +f 113 115 116 +f 116 114 113 +f 117 118 120 +f 120 119 117 +f 113 114 118 +f 118 117 113 +f 114 116 120 +f 120 118 114 +f 116 115 119 +f 119 120 116 +f 115 113 117 +f 117 119 115 +f 131 132 127 +f 127 125 131 +f 136 133 134 +f 134 135 136 +f 122 124 128 +f 128 126 122 +f 129 132 128 +f 128 124 129 +f 123 121 125 +f 125 127 123 +f 126 128 132 +f 132 131 126 +f 122 126 131 +f 131 130 122 +f 123 127 132 +f 132 129 123 +f 131 125 134 +f 134 133 131 +f 125 121 135 +f 135 134 125 +f 130 131 133 +f 133 136 130 +f 138 139 140 +f 140 137 138 +f 142 143 144 +f 144 141 142 +f 145 146 147 +f 147 148 145 +f 138 137 141 +f 141 144 138 +f 146 145 140 +f 140 139 146 +f 148 147 143 +f 143 142 148 +f 152 150 149 +f 149 151 152 +f 149 153 154 +f 155 151 149 +f 149 154 155 +f 151 155 156 +f 157 152 151 +f 151 156 157 +f 152 157 158 +f 159 150 152 +f 152 158 159 +f 150 159 160 +f 153 149 150 +f 150 160 153 +f 162 154 153 +f 153 161 162 +f 163 155 154 +f 154 162 163 +f 164 156 155 +f 155 163 164 +f 165 157 156 +f 156 164 165 +f 166 158 157 +f 157 165 166 +f 167 159 158 +f 158 166 167 +f 168 160 159 +f 159 167 168 +f 161 153 160 +f 160 168 161 +f 161 172 162 +f 170 163 162 +f 162 172 170 +f 163 170 164 +f 169 165 164 +f 164 170 169 +f 165 169 166 +f 171 167 166 +f 166 169 171 +f 167 171 168 +f 172 161 168 +f 168 171 172 +f 170 172 171 +f 171 169 170 +f 176 173 174 +f 174 175 176 +f 173 177 178 +f 178 174 173 +f 179 175 174 +f 174 178 179 +f 175 179 180 +f 180 176 175 +f 177 173 176 +f 176 180 177 +f 178 177 180 +f 180 179 178 +f 184 181 182 +f 182 183 184 +f 181 185 186 +f 186 182 181 +f 187 183 182 +f 182 186 187 +f 183 187 188 +f 188 184 183 +f 185 181 184 +f 184 188 185 +f 186 185 188 +f 188 187 186 +f 192 190 189 +f 189 191 192 +f 189 193 194 +f 195 191 189 +f 189 194 195 +f 191 195 196 +f 197 192 191 +f 191 196 197 +f 192 197 198 +f 199 190 192 +f 192 198 199 +f 190 199 200 +f 193 189 190 +f 190 200 193 +f 202 194 193 +f 193 201 202 +f 203 195 194 +f 194 202 203 +f 204 196 195 +f 195 203 204 +f 205 197 196 +f 196 204 205 +f 206 198 197 +f 197 205 206 +f 207 199 198 +f 198 206 207 +f 208 200 199 +f 199 207 208 +f 201 193 200 +f 200 208 201 +f 201 212 202 +f 210 203 202 +f 202 212 210 +f 203 210 204 +f 209 205 204 +f 204 210 209 +f 205 209 206 +f 211 207 206 +f 206 209 211 +f 207 211 208 +f 212 201 208 +f 208 211 212 +f 210 212 211 +f 211 209 210 +f 213 214 223 +f 223 222 213 +f 214 215 224 +f 224 223 214 +f 215 216 225 +f 225 224 215 +f 216 217 226 +f 226 225 216 +f 217 218 227 +f 227 226 217 +f 218 219 228 +f 228 227 218 +f 219 220 229 +f 229 228 219 +f 220 221 230 +f 230 229 220 +f 221 213 222 +f 222 230 221 +f 220 219 218 +f 218 214 220 +f 218 217 216 +f 216 214 218 +f 216 215 214 +f 220 214 213 +f 213 221 220 +f 223 224 225 +f 225 229 223 +f 225 226 227 +f 227 229 225 +f 227 228 229 +f 223 229 230 +f 230 222 223 +f 231 232 236 +f 236 235 231 +f 232 233 237 +f 237 236 232 +f 233 234 238 +f 238 237 233 +f 239 242 238 +f 238 234 239 +f 242 239 240 +f 240 241 242 +f 248 244 243 +f 243 247 248 +f 249 245 244 +f 244 248 249 +f 250 246 245 +f 245 249 250 +f 250 254 251 +f 251 246 250 +f 252 251 254 +f 254 253 252 +f 248 247 235 +f 235 236 248 +f 247 243 231 +f 231 235 247 +f 243 244 232 +f 232 231 243 +f 249 248 236 +f 236 237 249 +f 244 245 233 +f 233 232 244 +f 250 249 237 +f 237 238 250 +f 245 246 234 +f 234 233 245 +f 246 251 239 +f 239 234 246 +f 254 250 238 +f 238 242 254 +f 252 253 241 +f 241 240 252 +f 253 254 242 +f 242 241 253 +f 251 252 240 +f 240 239 251 +f 257 258 255 +f 255 256 257 +f 255 259 260 +f 261 256 255 +f 255 260 261 +f 256 261 262 +f 263 257 256 +f 256 262 263 +f 257 263 264 +f 265 258 257 +f 257 264 265 +f 258 265 266 +f 259 255 258 +f 258 266 259 +f 268 260 259 +f 259 267 268 +f 269 261 260 +f 260 268 269 +f 270 262 261 +f 261 269 270 +f 271 263 262 +f 262 270 271 +f 272 264 263 +f 263 271 272 +f 273 265 264 +f 264 272 273 +f 274 266 265 +f 265 273 274 +f 267 259 266 +f 266 274 267 +f 267 275 268 +f 276 269 268 +f 268 275 276 +f 269 276 270 +f 277 271 270 +f 270 276 277 +f 271 277 272 +f 278 273 272 +f 272 277 278 +f 273 278 274 +f 275 267 274 +f 274 278 275 +f 276 275 278 +f 278 277 276 +f 280 291 293 +f 293 279 280 +f 292 294 286 +f 286 283 292 +f 293 292 283 +f 283 279 293 +f 282 281 285 +f 285 284 282 +f 281 287 290 +f 290 285 281 +f 280 279 283 +f 283 286 280 +f 281 282 288 +f 288 287 281 +f 284 285 290 +f 290 289 284 +f 282 284 289 +f 289 288 282 +f 287 291 294 +f 294 290 287 +f 287 288 293 +f 293 291 287 +f 289 290 294 +f 294 292 289 +f 288 289 292 +f 292 293 288 +f 291 280 286 +f 286 294 291 +f 295 296 297 +f 297 298 295 +f 299 300 301 +f 301 302 299 +f 295 298 300 +f 300 299 295 +f 298 297 301 +f 301 300 298 +f 297 296 302 +f 302 301 297 +f 296 295 299 +f 299 302 296 +f 306 304 303 +f 303 305 306 +f 303 307 308 +f 309 305 303 +f 303 308 309 +f 305 309 310 +f 311 306 305 +f 305 310 311 +f 306 311 312 +f 313 304 306 +f 306 312 313 +f 304 313 314 +f 307 303 304 +f 304 314 307 +f 316 308 307 +f 307 315 316 +f 317 309 308 +f 308 316 317 +f 318 310 309 +f 309 317 318 +f 319 311 310 +f 310 318 319 +f 320 312 311 +f 311 319 320 +f 321 313 312 +f 312 320 321 +f 322 314 313 +f 313 321 322 +f 315 307 314 +f 314 322 315 +f 315 326 316 +f 324 317 316 +f 316 326 324 +f 317 324 318 +f 323 319 318 +f 318 324 323 +f 319 323 320 +f 325 321 320 +f 320 323 325 +f 321 325 322 +f 326 315 322 +f 322 325 326 +f 324 326 325 +f 325 323 324 +# 556 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_clav_chull.obj b/examples/Atlas/urdf/mesh/r_clav_chull.obj new file mode 100644 index 0000000..6e63ded --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_clav_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_clav_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.062902 -0.087363 -0.201382 +v 0.053594 -0.136785 -0.280568 +v 0.053160 -0.143161 -0.225656 +v 0.053160 -0.123170 -0.207714 +v -0.044856 -0.036110 -0.266372 +v 0.062730 -0.046481 -0.229508 +v -0.020601 0.022941 -0.202441 +v 0.018171 -0.113772 -0.292824 +v 0.018170 -0.143100 -0.281406 +v -0.054377 -0.143100 -0.281406 +v -0.054377 -0.113772 -0.292824 +v 0.018170 -0.158705 -0.252495 +v -0.054377 -0.158705 -0.252495 +v -0.054377 -0.153285 -0.219619 +v 0.017751 -0.152482 -0.216816 +v -0.054377 -0.129377 -0.198160 +v 0.050434 -0.050770 -0.292640 +v 0.011242 0.024408 -0.200392 +v 0.009460 -0.050770 -0.292640 +v 0.066203 -0.001142 -0.136629 +v 0.021228 -0.021891 -0.112696 +v -0.054815 -0.037823 -0.215319 +v -0.054787 -0.077552 -0.191161 +v 0.017465 0.023374 -0.112685 +v 0.066280 0.024404 -0.157071 +v -0.023397 0.017708 -0.113760 +v -0.023049 -0.023155 -0.113548 +# 27 vertices, 0 vertices normals + +f 10 13 23 +f 14 23 13 +f 8 2 9 +f 16 27 23 +f 23 14 16 +f 19 11 5 +f 2 12 9 +f 4 21 15 +f 26 23 27 +f 25 6 17 +f 18 25 17 +f 17 6 2 +f 17 2 8 +f 5 7 19 +f 15 12 3 +f 3 12 2 +f 4 15 3 +f 3 1 4 +f 1 20 4 +f 23 26 22 +f 20 25 24 +f 25 20 1 +f 6 25 1 +f 2 6 1 +f 1 3 2 +f 20 21 4 +f 22 5 11 +f 10 22 11 +f 22 10 23 +f 24 18 7 +f 7 26 24 +f 7 5 22 +f 7 22 26 +f 25 18 24 +f 8 9 10 +f 8 10 11 +f 12 10 9 +f 12 13 10 +f 12 14 13 +f 12 15 14 +f 14 15 16 +f 15 21 27 +f 16 15 27 +f 17 7 18 +f 19 7 17 +f 17 8 11 +f 17 11 19 +f 21 20 24 +f 27 21 24 +f 27 24 26 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_farm.obj b/examples/Atlas/urdf/mesh/r_farm.obj new file mode 100644 index 0000000..68300bb --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_farm.obj @@ -0,0 +1,312 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_farm.obj +# +# Vertices: 100 +# Faces: 196 +# +#### +v 0.062026 0.013075 -0.029638 +v 0.062026 0.028576 -0.018376 +v 0.062026 -0.027509 -0.000153 +v 0.062026 -0.006086 -0.029638 +v 0.062026 -0.021588 -0.018376 +v 0.062026 -0.021588 0.018070 +v 0.062026 -0.006086 0.029332 +v 0.062026 0.013075 0.029332 +v 0.062026 0.028576 0.018070 +v 0.062026 0.034496 -0.000153 +v 0.058226 0.035514 -0.031937 +v 0.062242 0.035461 -0.000153 +v 0.052578 0.015511 -0.037140 +v 0.052578 -0.008523 -0.037139 +v 0.052578 -0.027968 -0.023012 +v 0.052578 -0.035395 -0.000153 +v 0.052578 -0.027968 0.022706 +v 0.052578 -0.008523 0.036833 +v 0.052578 0.015511 0.036833 +v 0.058226 0.035514 0.030743 +v 0.014263 0.015511 -0.037140 +v 0.014319 0.035498 -0.031979 +v 0.014263 -0.008523 -0.037139 +v 0.014263 -0.027968 -0.023012 +v 0.014263 -0.035395 -0.000153 +v 0.014263 -0.027968 0.022706 +v 0.014263 -0.008523 0.036833 +v 0.014263 0.015511 0.036833 +v 0.014319 0.035498 0.030748 +v 0.014291 0.035513 -0.000160 +v 0.042293 0.156094 0.030578 +v 0.016151 0.156094 0.049571 +v 0.016151 0.122946 0.049571 +v 0.042293 0.122946 0.030578 +v 0.052278 0.156094 -0.000153 +v 0.052278 0.122946 -0.000153 +v 0.042293 0.156094 -0.030885 +v 0.042293 0.122946 -0.030885 +v 0.016151 0.156094 -0.049878 +v 0.016151 0.122946 -0.049878 +v 0.016151 0.086100 0.039871 +v 0.042293 0.086100 0.030578 +v 0.052278 0.086100 -0.000153 +v 0.042293 0.086100 -0.030885 +v 0.016151 0.086100 -0.040177 +v 0.018373 0.050635 0.039871 +v 0.054031 0.050635 0.030578 +v 0.059468 0.050635 -0.000153 +v 0.054031 0.050635 -0.030885 +v 0.018373 0.050635 -0.040177 +v -0.018526 0.050635 -0.040177 +v -0.014472 0.035498 -0.031979 +v -0.016304 0.156094 0.049571 +v -0.042446 0.156094 0.030578 +v -0.016304 0.156094 -0.049878 +v -0.052431 0.156094 -0.000153 +v -0.042446 0.156094 -0.030885 +v -0.016304 0.086100 0.039871 +v -0.018526 0.050635 0.039871 +v -0.014472 0.035498 0.030748 +v -0.014444 0.035513 -0.000160 +v -0.062178 0.013075 0.029332 +v -0.062178 0.028576 0.018070 +v -0.062178 0.028576 -0.018376 +v -0.062178 -0.006086 0.029332 +v -0.062178 -0.021588 0.018070 +v -0.062178 -0.027509 -0.000153 +v -0.062178 -0.021588 -0.018376 +v -0.062179 -0.006086 -0.029638 +v -0.062179 0.013075 -0.029638 +v -0.062178 0.034496 -0.000153 +v -0.058379 0.035514 -0.031937 +v -0.062395 0.035461 -0.000153 +v -0.052730 0.015511 -0.037140 +v -0.052730 -0.008523 -0.037139 +v -0.052730 -0.027968 -0.023012 +v -0.052730 -0.035395 -0.000153 +v -0.052730 -0.027968 0.022706 +v -0.052730 -0.008523 0.036833 +v -0.052730 0.015511 0.036833 +v -0.058379 0.035514 0.030743 +v -0.014416 0.015511 -0.037140 +v -0.014416 -0.008523 -0.037139 +v -0.014416 -0.027968 -0.023012 +v -0.014416 -0.035395 -0.000153 +v -0.014416 -0.027968 0.022706 +v -0.014416 -0.008523 0.036833 +v -0.014416 0.015511 0.036833 +v -0.016304 0.122946 0.049571 +v -0.042446 0.122946 0.030578 +v -0.052431 0.122946 -0.000153 +v -0.042446 0.122946 -0.030885 +v -0.016304 0.122946 -0.049878 +v -0.042446 0.086100 0.030578 +v -0.052431 0.086100 -0.000153 +v -0.042446 0.086100 -0.030885 +v -0.016304 0.086100 -0.040177 +v -0.054184 0.050635 0.030578 +v -0.059621 0.050635 -0.000153 +v -0.054184 0.050635 -0.030885 +# 100 vertices, 0 vertices normals + +f 2 4 1 +f 4 2 3 +f 3 5 4 +f 3 7 6 +f 7 3 2 +f 7 2 8 +f 2 9 8 +f 9 2 10 +f 12 2 11 +f 2 12 10 +f 13 11 1 +f 4 13 1 +f 13 4 14 +f 5 14 4 +f 14 5 15 +f 16 5 3 +f 16 15 5 +f 6 16 3 +f 16 6 17 +f 18 6 7 +f 18 17 6 +f 19 7 8 +f 7 19 18 +f 20 8 9 +f 12 20 9 +f 9 10 12 +f 22 13 21 +f 13 22 11 +f 23 13 14 +f 13 23 21 +f 24 14 15 +f 14 24 23 +f 25 15 16 +f 15 25 24 +f 26 16 17 +f 16 26 25 +f 27 17 18 +f 17 27 26 +f 28 18 19 +f 18 28 27 +f 29 19 20 +f 19 29 28 +f 22 28 29 +f 22 27 28 +f 27 25 26 +f 25 27 22 +f 25 23 24 +f 23 25 22 +f 22 21 23 +f 22 29 30 +f 32 33 31 +f 31 33 34 +f 34 35 31 +f 35 34 36 +f 36 37 35 +f 37 36 38 +f 38 40 39 +f 38 39 37 +f 33 41 34 +f 34 41 42 +f 42 36 34 +f 36 42 43 +f 43 38 36 +f 38 43 44 +f 44 45 40 +f 44 40 38 +f 41 46 42 +f 42 46 47 +f 47 43 42 +f 43 47 48 +f 48 44 43 +f 44 48 49 +f 50 44 49 +f 44 50 45 +f 47 46 29 +f 47 29 20 +f 47 12 48 +f 12 47 20 +f 12 49 48 +f 49 12 11 +f 22 49 11 +f 49 22 50 +f 51 50 22 +f 51 22 52 +f 39 35 37 +f 35 39 53 +f 35 32 31 +f 32 35 53 +f 53 56 54 +f 56 53 55 +f 55 57 56 +f 55 53 39 +f 58 46 41 +f 46 58 59 +f 46 59 60 +f 46 60 29 +f 60 61 29 +f 29 61 30 +f 20 19 8 +f 11 2 1 +f 64 62 63 +f 64 65 62 +f 65 67 66 +f 67 65 64 +f 67 69 68 +f 69 67 64 +f 64 70 69 +f 64 63 71 +f 64 73 72 +f 73 64 71 +f 72 74 70 +f 69 74 75 +f 74 69 70 +f 68 75 76 +f 75 68 69 +f 67 68 77 +f 76 77 68 +f 66 77 78 +f 77 66 67 +f 65 66 79 +f 78 79 66 +f 65 80 62 +f 80 65 79 +f 62 81 63 +f 81 73 63 +f 63 73 71 +f 74 52 82 +f 52 74 72 +f 75 74 83 +f 83 74 82 +f 75 84 76 +f 84 75 83 +f 77 76 85 +f 85 76 84 +f 78 77 86 +f 86 77 85 +f 78 87 79 +f 87 78 86 +f 80 79 88 +f 88 79 87 +f 60 81 80 +f 60 80 88 +f 52 85 82 +f 82 85 83 +f 85 84 83 +f 85 87 86 +f 87 85 52 +f 87 52 88 +f 52 60 88 +f 60 52 61 +f 54 89 53 +f 89 54 90 +f 54 56 90 +f 90 56 91 +f 56 57 91 +f 91 57 92 +f 93 92 55 +f 92 57 55 +f 40 93 39 +f 93 55 39 +f 90 58 89 +f 58 90 94 +f 90 91 94 +f 94 91 95 +f 91 92 95 +f 95 92 96 +f 97 96 93 +f 96 92 93 +f 97 93 45 +f 45 93 40 +f 94 59 58 +f 59 94 98 +f 94 95 98 +f 98 95 99 +f 95 96 99 +f 99 96 100 +f 51 96 97 +f 96 51 100 +f 50 51 45 +f 51 97 45 +f 60 98 81 +f 98 60 59 +f 98 73 81 +f 73 98 99 +f 99 100 73 +f 73 100 72 +f 100 52 72 +f 52 100 51 +f 32 53 89 +f 32 89 33 +f 33 89 58 +f 33 58 41 +f 30 61 22 +f 61 52 22 +f 80 81 62 +f 64 72 70 +# 196 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_farm_chull.obj b/examples/Atlas/urdf/mesh/r_farm_chull.obj new file mode 100644 index 0000000..7a7f6a1 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_farm_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_farm_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.061657 0.010512 -0.031951 +v -0.063355 0.004923 -0.031086 +v -0.052431 0.156094 -0.000153 +v -0.042446 0.156094 -0.030885 +v 0.042293 0.156094 -0.030885 +v 0.016151 0.156094 -0.049878 +v 0.052278 0.156094 -0.000153 +v -0.016304 0.156094 -0.049878 +v 0.042293 0.156094 0.030578 +v -0.042446 0.156094 0.030578 +v 0.016151 0.156094 0.049571 +v 0.062846 0.024523 0.023622 +v 0.055604 -0.008481 0.036830 +v -0.016304 0.122946 -0.049878 +v 0.016151 0.122946 -0.049878 +v 0.054450 -0.008495 -0.037139 +v -0.054626 -0.008483 -0.037139 +v 0.016151 0.122946 0.049571 +v -0.012522 0.156072 0.052155 +v -0.052730 -0.008523 0.036833 +v -0.063920 -0.003241 0.030623 +v -0.061807 -0.027828 0.022781 +v 0.061814 -0.027809 0.022655 +v -0.061842 -0.035230 -0.000243 +v 0.052578 -0.035395 -0.000153 +v -0.052730 -0.027968 -0.023012 +v 0.061658 -0.027693 -0.023158 +# 27 vertices, 0 vertices normals + +f 1 7 5 +f 9 7 12 +f 12 7 1 +f 1 5 6 +f 2 4 3 +f 21 3 10 +f 13 11 9 +f 16 1 6 +f 2 8 4 +f 15 16 6 +f 21 2 3 +f 12 13 9 +f 10 19 21 +f 8 2 17 +f 8 17 14 +f 12 1 27 +f 1 16 27 +f 27 23 12 +f 25 23 27 +f 22 24 2 +f 2 21 22 +f 17 2 26 +f 2 24 26 +f 19 3 4 +f 19 6 5 +f 19 5 7 +f 4 8 19 +f 19 7 9 +f 10 3 19 +f 11 19 9 +f 19 8 6 +f 23 13 12 +f 15 14 16 +f 14 17 16 +f 6 8 14 +f 14 15 6 +f 13 18 11 +f 18 19 11 +f 20 18 13 +f 18 20 19 +f 20 21 19 +f 22 20 13 +f 13 23 22 +f 22 25 24 +f 22 23 25 +f 20 22 21 +f 25 27 26 +f 26 24 25 +f 26 16 17 +f 26 27 16 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_foot.obj b/examples/Atlas/urdf/mesh/r_foot.obj new file mode 100644 index 0000000..eb4490a --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_foot.obj @@ -0,0 +1,875 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_foot.obj +# +# Vertices: 319 +# Faces: 540 +# +#### +v 0.006721 -0.023371 -0.026154 +v 0.004797 -0.000567 -0.016974 +v 0.008825 -0.000567 -0.014058 +v 0.012783 -0.023371 -0.014664 +v -0.004495 -0.023371 -0.026428 +v -0.003427 -0.000567 -0.017521 +v -0.017024 -0.023371 -0.020487 +v -0.011218 -0.000567 -0.013809 +v -0.018372 -0.023371 -0.020170 +v -0.016315 -0.000567 -0.012421 +v 0.020293 -0.000567 -0.013043 +v 0.021040 -0.023371 -0.013649 +v 0.012783 -0.023371 -0.029887 +v 0.006721 -0.023371 -0.029891 +v -0.004495 -0.023371 -0.029891 +v -0.017024 -0.023371 -0.029889 +v -0.018372 -0.023371 -0.029889 +v 0.021040 -0.023371 -0.029886 +v 0.020293 -0.000567 -0.020558 +v 0.021040 -0.023371 -0.021164 +v 0.006721 0.022237 -0.026154 +v 0.012783 0.022237 -0.014664 +v -0.004495 0.022237 -0.026428 +v -0.017024 0.022237 -0.020487 +v -0.018372 0.022237 -0.020170 +v 0.021040 0.022237 -0.013649 +v 0.006721 0.022237 -0.029891 +v 0.012783 0.022237 -0.029887 +v -0.004495 0.022237 -0.029891 +v -0.017024 0.022237 -0.029889 +v -0.018372 0.022237 -0.029889 +v 0.021040 0.022237 -0.029886 +v 0.021040 0.022237 -0.021164 +v -0.063258 0.013124 -0.014953 +v -0.017861 0.013124 -0.014953 +v -0.017861 0.010424 -0.004854 +v -0.051059 0.010424 -0.004854 +v -0.033160 0.003925 0.009945 +v -0.038459 0.009324 0.005246 +v -0.017861 0.009324 0.005246 +v -0.017861 0.003925 0.009945 +v -0.033160 -0.003175 0.010145 +v -0.017861 -0.003175 0.010145 +v -0.038459 -0.008775 0.005646 +v -0.017861 -0.008775 0.005646 +v -0.017861 -0.012874 -0.014453 +v -0.063258 -0.012874 -0.014453 +v -0.051059 -0.010075 -0.004354 +v -0.017861 -0.010075 -0.004354 +v -0.069657 0.023123 -0.019953 +v -0.017861 0.023123 -0.019953 +v -0.017861 -0.022974 -0.019453 +v -0.069657 -0.022974 -0.019453 +v -0.069657 0.023123 -0.029795 +v -0.017861 0.023123 -0.029795 +v -0.017861 -0.022974 -0.029295 +v -0.069657 -0.022974 -0.029295 +v 0.055317 -0.012752 -0.016871 +v 0.017281 -0.012752 -0.014953 +v 0.017281 -0.010052 -0.004854 +v 0.049529 -0.010052 -0.006606 +v 0.032208 -0.003553 0.009945 +v 0.037138 -0.008952 0.005245 +v 0.017281 -0.008952 0.005245 +v 0.017281 -0.003553 0.009945 +v 0.032208 0.003547 0.010144 +v 0.017281 0.003547 0.010145 +v 0.037138 0.009147 0.005645 +v 0.017281 0.009147 0.005646 +v 0.017281 0.013247 -0.014453 +v 0.055317 0.013247 -0.016371 +v 0.049529 0.010447 -0.006106 +v 0.017281 0.010447 -0.004354 +v 0.071675 -0.022751 -0.019953 +v 0.017281 -0.022751 -0.019953 +v 0.017281 0.023346 -0.019453 +v 0.071675 0.023346 -0.019453 +v 0.071675 -0.022751 -0.029795 +v 0.017281 -0.022751 -0.029795 +v 0.017281 0.023346 -0.029295 +v 0.071675 0.023346 -0.029295 +v 0.110890 -0.066087 -0.050160 +v 0.110890 -0.066087 -0.076451 +v -0.063498 -0.066087 -0.076451 +v -0.061798 -0.066087 -0.050160 +v 0.154187 -0.047489 -0.076451 +v 0.135488 -0.056788 -0.076451 +v 0.135488 -0.056788 -0.058089 +v 0.154187 -0.047489 -0.062993 +v -0.087697 0.012407 -0.076451 +v -0.087697 0.012407 -0.050160 +v -0.087697 -0.015891 -0.050160 +v -0.087697 -0.015891 -0.076451 +v 0.110890 0.062604 -0.050160 +v -0.061498 0.062604 -0.050160 +v -0.063498 0.062604 -0.076451 +v 0.110890 0.062604 -0.076451 +v 0.154187 0.044005 -0.062993 +v 0.148888 0.044005 -0.049534 +v 0.127989 0.053304 -0.039623 +v 0.135488 0.053305 -0.058089 +v -0.060298 0.062604 -0.039049 +v -0.085497 0.040705 -0.039049 +v -0.087697 0.040705 -0.050160 +v 0.154187 0.013507 -0.076451 +v 0.135488 0.016607 -0.076451 +v 0.135488 -0.020090 -0.076451 +v 0.154187 -0.016991 -0.076451 +v 0.172786 0.009208 -0.055794 +v 0.172786 0.009208 -0.066122 +v 0.172786 -0.012691 -0.066122 +v 0.172786 -0.012691 -0.055794 +v 0.136460 0.017915 -0.039623 +v 0.154187 0.013507 -0.049534 +v 0.154187 -0.016991 -0.049534 +v 0.136460 -0.021399 -0.039623 +v 0.172786 -0.034690 -0.076451 +v 0.172786 -0.034690 -0.066122 +v 0.127989 -0.056788 -0.039623 +v 0.113564 -0.066087 -0.039049 +v 0.126652 -0.057540 -0.039017 +v 0.172786 0.031206 -0.066122 +v 0.172786 0.031206 -0.055794 +v 0.135488 0.053305 -0.076451 +v 0.110890 0.019707 -0.076451 +v 0.110890 -0.023190 -0.076451 +v 0.172786 -0.012691 -0.076451 +v 0.172786 0.009208 -0.076451 +v 0.148888 -0.047489 -0.049534 +v -0.087697 -0.044189 -0.076451 +v -0.087697 -0.044189 -0.050160 +v 0.154187 0.044005 -0.076451 +v -0.087697 0.040705 -0.076451 +v 0.172786 -0.034690 -0.055794 +v 0.172786 0.031206 -0.076451 +v 0.126652 0.054057 -0.039017 +v 0.113564 0.062604 -0.039049 +v -0.019401 0.049105 -0.021890 +v -0.019401 -0.051588 -0.021890 +v -0.059399 0.049105 -0.021890 +v -0.024201 0.053904 -0.021890 +v -0.054599 0.053904 -0.021890 +v -0.059399 -0.051588 -0.021890 +v -0.054599 -0.056388 -0.021890 +v -0.024201 -0.056388 -0.021890 +v -0.019401 0.049105 -0.036621 +v -0.019401 -0.051588 -0.036621 +v -0.054599 0.053904 -0.036621 +v -0.024201 0.053904 -0.036621 +v -0.059399 -0.051588 -0.036621 +v -0.059399 0.049105 -0.036621 +v -0.024201 -0.056388 -0.036621 +v -0.054599 -0.056388 -0.036621 +v 0.100891 -0.028090 -0.022232 +v 0.100891 -0.052089 -0.022232 +v 0.063893 -0.028090 -0.022232 +v 0.097591 -0.024490 -0.022232 +v 0.067193 -0.024490 -0.022232 +v 0.063893 -0.052089 -0.022232 +v 0.067193 -0.055388 -0.022232 +v 0.097591 -0.055388 -0.022232 +v 0.100891 -0.028090 -0.035056 +v 0.100891 -0.052089 -0.035056 +v 0.067193 -0.024490 -0.035056 +v 0.097591 -0.024490 -0.035056 +v 0.063893 -0.052089 -0.035056 +v 0.063893 -0.028090 -0.035056 +v 0.097591 -0.055388 -0.035056 +v 0.067193 -0.055388 -0.035056 +v 0.100891 0.050905 -0.022232 +v 0.100891 0.026906 -0.022232 +v 0.063893 0.050905 -0.022232 +v 0.097591 0.054204 -0.022232 +v 0.067193 0.054204 -0.022232 +v 0.063893 0.026906 -0.022232 +v 0.067193 0.023207 -0.022232 +v 0.097591 0.023207 -0.022232 +v 0.100891 0.050905 -0.035056 +v 0.100891 0.026906 -0.035056 +v 0.067193 0.054204 -0.035056 +v 0.097591 0.054204 -0.035056 +v 0.063893 0.026906 -0.035056 +v 0.063893 0.050905 -0.035056 +v 0.097591 0.023207 -0.035056 +v 0.067193 0.023207 -0.035056 +v 0.110090 0.017507 -0.020801 +v 0.110090 -0.017591 -0.020801 +v 0.073793 0.017507 -0.020801 +v 0.106790 0.022307 -0.020801 +v 0.077092 0.022306 -0.020801 +v 0.073792 -0.017591 -0.020801 +v 0.077092 -0.022890 -0.020801 +v 0.106790 -0.022890 -0.020801 +v 0.110090 0.017507 -0.035838 +v 0.110090 -0.017591 -0.035838 +v 0.077092 0.022306 -0.035838 +v 0.106790 0.022307 -0.035838 +v 0.073792 -0.017591 -0.035838 +v 0.073793 0.017507 -0.035838 +v 0.106790 -0.022890 -0.035838 +v 0.077092 -0.022890 -0.035838 +v 0.135602 0.016858 -0.039017 +v -0.085497 -0.015891 -0.039049 +v -0.085497 -0.044189 -0.039049 +v 0.059693 -0.028090 -0.026931 +v 0.059693 -0.052088 -0.026931 +v -0.012202 -0.028090 -0.026931 +v 0.056294 -0.024490 -0.026931 +v -0.008902 -0.024490 -0.026931 +v -0.012202 -0.052088 -0.026931 +v -0.008902 -0.055388 -0.026931 +v 0.056294 -0.055388 -0.026931 +v 0.059693 -0.028090 -0.033831 +v 0.059693 -0.052088 -0.033831 +v -0.008902 -0.024490 -0.033831 +v 0.056294 -0.024490 -0.033831 +v -0.012202 -0.052088 -0.033831 +v -0.012202 -0.028090 -0.033831 +v 0.056294 -0.055388 -0.033831 +v -0.008902 -0.055388 -0.033831 +v 0.059693 0.050905 -0.026931 +v 0.059693 0.026906 -0.026931 +v -0.012202 0.050905 -0.026931 +v 0.056294 0.054204 -0.026931 +v -0.008902 0.054204 -0.026931 +v -0.012202 0.026906 -0.026931 +v -0.008902 0.023207 -0.026931 +v 0.056294 0.023207 -0.026931 +v 0.059693 0.050905 -0.033831 +v 0.059693 0.026906 -0.033831 +v -0.008902 0.054204 -0.033831 +v 0.056294 0.054204 -0.033831 +v -0.012202 0.026906 -0.033831 +v -0.012202 0.050905 -0.033831 +v 0.056294 0.023207 -0.033831 +v -0.008902 0.023207 -0.033831 +v -0.060449 -0.066087 -0.039049 +v 0.135602 -0.020341 -0.039017 +v -0.085497 0.012407 -0.039049 +v -0.090164 -0.025202 -0.039049 +v -0.071747 -0.071664 -0.039049 +v -0.071584 0.068181 -0.039049 +v -0.090164 0.021719 -0.039049 +v 0.108368 -0.071664 -0.039048 +v 0.116658 -0.062376 -0.039017 +v 0.135826 -0.021953 -0.039017 +v 0.135826 0.018470 -0.039017 +v -0.090164 0.006078 -0.039049 +v -0.090164 -0.009562 -0.039049 +v 0.108368 0.068181 -0.039049 +v 0.116659 0.058893 -0.039017 +v -0.090164 -0.025202 -0.028170 +v -0.071747 -0.071664 -0.028170 +v -0.071584 0.068181 -0.028170 +v -0.090164 0.021719 -0.028170 +v 0.108368 -0.071664 -0.028169 +v 0.116659 -0.062376 -0.028138 +v 0.135826 -0.021953 -0.028138 +v 0.135826 0.018470 -0.028138 +v -0.090164 0.006078 -0.028170 +v -0.090164 -0.009562 -0.028170 +v 0.108368 0.068181 -0.028170 +v 0.116658 0.058893 -0.028138 +v 0.037418 -0.032957 -0.007357 +v 0.041405 -0.032957 -0.007357 +v 0.041404 -0.032957 -0.026011 +v 0.036187 -0.032957 -0.009913 +v 0.017412 -0.032957 -0.026009 +v 0.033421 -0.032957 -0.010545 +v 0.017416 -0.032957 -0.014107 +v 0.031203 -0.032957 -0.008776 +v 0.027385 -0.032957 -0.004100 +v 0.031203 -0.032957 -0.005938 +v 0.032478 -0.032957 -0.000038 +v 0.033421 -0.032957 -0.004169 +v 0.038830 -0.032957 -0.001487 +v 0.036187 -0.032957 -0.004801 +v 0.037418 -0.025219 -0.007357 +v 0.036187 -0.025219 -0.009913 +v 0.041404 -0.025219 -0.026011 +v 0.041405 -0.025219 -0.007357 +v 0.033421 -0.025219 -0.010545 +v 0.017412 -0.025219 -0.026009 +v 0.031203 -0.025219 -0.008776 +v 0.017416 -0.025219 -0.014107 +v 0.031203 -0.025219 -0.005938 +v 0.027385 -0.025219 -0.004100 +v 0.033421 -0.025219 -0.004169 +v 0.032478 -0.025219 -0.000038 +v 0.036187 -0.025219 -0.004801 +v 0.038830 -0.025219 -0.001487 +v 0.037418 0.024718 -0.007357 +v 0.041405 0.024718 -0.007357 +v 0.041404 0.024719 -0.026011 +v 0.036187 0.024718 -0.009913 +v 0.017412 0.024719 -0.026009 +v 0.033421 0.024718 -0.010545 +v 0.017416 0.024719 -0.014107 +v 0.031203 0.024718 -0.008776 +v 0.027385 0.024718 -0.004100 +v 0.031203 0.024718 -0.005938 +v 0.032478 0.024718 -0.000038 +v 0.033421 0.024718 -0.004169 +v 0.038830 0.024718 -0.001487 +v 0.036187 0.024718 -0.004801 +v 0.037418 0.032456 -0.007357 +v 0.036187 0.032456 -0.009913 +v 0.041404 0.032456 -0.026011 +v 0.041405 0.032456 -0.007357 +v 0.033421 0.032456 -0.010545 +v 0.017412 0.032456 -0.026009 +v 0.031203 0.032456 -0.008776 +v 0.017416 0.032456 -0.014107 +v 0.031203 0.032456 -0.005938 +v 0.027385 0.032456 -0.004100 +v 0.033421 0.032456 -0.004169 +v 0.032478 0.032456 -0.000038 +v 0.036187 0.032456 -0.004801 +v 0.038830 0.032456 -0.001487 +# 319 vertices, 0 vertices normals + +f 1 4 3 +f 3 2 1 +f 5 1 2 +f 2 6 5 +f 7 5 6 +f 6 8 7 +f 9 7 8 +f 8 10 9 +f 11 3 4 +f 4 12 11 +f 13 4 1 +f 1 14 13 +f 14 1 5 +f 5 15 14 +f 15 5 7 +f 7 16 15 +f 16 7 9 +f 9 17 16 +f 18 12 4 +f 4 13 18 +f 19 11 12 +f 12 20 19 +f 3 22 21 +f 21 2 3 +f 2 21 23 +f 23 6 2 +f 6 23 24 +f 24 8 6 +f 8 24 25 +f 25 10 8 +f 22 3 11 +f 11 26 22 +f 21 22 28 +f 28 27 21 +f 23 21 27 +f 27 29 23 +f 24 23 29 +f 29 30 24 +f 25 24 30 +f 30 31 25 +f 22 26 32 +f 32 28 22 +f 26 11 19 +f 19 33 26 +f 34 37 36 +f 36 35 34 +f 38 41 40 +f 40 39 38 +f 42 43 41 +f 41 38 42 +f 44 45 43 +f 43 42 44 +f 46 49 48 +f 48 47 46 +f 48 37 34 +f 34 47 48 +f 35 36 49 +f 49 46 35 +f 50 34 35 +f 35 51 50 +f 40 36 37 +f 37 39 40 +f 52 46 47 +f 47 53 52 +f 44 48 49 +f 49 45 44 +f 42 38 37 +f 37 44 42 +f 37 38 39 +f 37 48 44 +f 53 47 34 +f 34 50 53 +f 51 35 46 +f 46 52 51 +f 41 43 49 +f 49 40 41 +f 49 43 45 +f 49 36 40 +f 54 50 51 +f 51 55 54 +f 56 52 53 +f 53 57 56 +f 57 53 50 +f 50 54 57 +f 55 51 52 +f 52 56 55 +f 58 61 60 +f 60 59 58 +f 62 65 64 +f 64 63 62 +f 66 67 65 +f 65 62 66 +f 68 69 67 +f 67 66 68 +f 70 73 72 +f 72 71 70 +f 72 61 58 +f 58 71 72 +f 59 60 73 +f 73 70 59 +f 74 58 59 +f 59 75 74 +f 64 60 61 +f 61 63 64 +f 76 70 71 +f 71 77 76 +f 68 72 73 +f 73 69 68 +f 66 62 61 +f 61 68 66 +f 61 62 63 +f 61 72 68 +f 77 71 58 +f 58 74 77 +f 75 59 70 +f 70 76 75 +f 65 67 73 +f 73 64 65 +f 73 67 69 +f 73 60 64 +f 78 74 75 +f 75 79 78 +f 80 76 77 +f 77 81 80 +f 81 77 74 +f 74 78 81 +f 79 75 76 +f 76 80 79 +f 82 85 84 +f 84 83 82 +f 86 89 88 +f 88 87 86 +f 90 93 92 +f 92 91 90 +f 94 97 96 +f 96 95 94 +f 98 101 100 +f 100 99 98 +f 102 95 104 +f 104 103 102 +f 105 108 107 +f 107 106 105 +f 109 112 111 +f 111 110 109 +f 113 116 115 +f 115 114 113 +f 117 118 89 +f 89 86 117 +f 119 121 120 +f 120 82 119 +f 88 119 82 +f 122 98 99 +f 99 123 122 +f 94 101 124 +f 124 97 94 +f 106 107 126 +f 126 125 106 +f 108 105 128 +f 128 127 108 +f 114 115 112 +f 112 109 114 +f 125 126 93 +f 93 90 125 +f 119 88 89 +f 89 129 119 +f 84 85 131 +f 131 130 84 +f 132 124 101 +f 101 98 132 +f 133 104 95 +f 95 96 133 +f 110 111 127 +f 127 128 110 +f 129 89 118 +f 118 134 129 +f 87 88 82 +f 82 83 87 +f 135 132 98 +f 98 122 135 +f 94 137 136 +f 136 100 94 +f 101 94 100 +f 138 141 140 +f 140 139 138 +f 140 141 142 +f 143 144 139 +f 139 140 143 +f 144 145 139 +f 146 138 139 +f 139 147 146 +f 148 142 141 +f 141 149 148 +f 150 143 140 +f 140 151 150 +f 152 145 144 +f 144 153 152 +f 154 157 156 +f 156 155 154 +f 156 157 158 +f 159 160 155 +f 155 156 159 +f 160 161 155 +f 162 154 155 +f 155 163 162 +f 164 158 157 +f 157 165 164 +f 166 159 156 +f 156 167 166 +f 168 161 160 +f 160 169 168 +f 165 157 154 +f 154 162 165 +f 161 168 163 +f 163 155 161 +f 167 156 158 +f 158 164 167 +f 169 160 159 +f 159 166 169 +f 170 173 172 +f 172 171 170 +f 172 173 174 +f 175 176 171 +f 171 172 175 +f 176 177 171 +f 178 170 171 +f 171 179 178 +f 180 174 173 +f 173 181 180 +f 182 175 172 +f 172 183 182 +f 184 177 176 +f 176 185 184 +f 181 173 170 +f 170 178 181 +f 177 184 179 +f 179 171 177 +f 183 172 174 +f 174 180 183 +f 185 176 175 +f 175 182 185 +f 186 189 188 +f 188 187 186 +f 188 189 190 +f 191 192 187 +f 187 188 191 +f 192 193 187 +f 194 186 187 +f 187 195 194 +f 196 190 189 +f 189 197 196 +f 198 191 188 +f 188 199 198 +f 200 193 192 +f 192 201 200 +f 197 189 186 +f 186 194 197 +f 193 200 195 +f 195 187 193 +f 199 188 190 +f 190 196 199 +f 201 192 191 +f 191 198 201 +f 149 141 138 +f 138 146 149 +f 145 152 147 +f 147 139 145 +f 151 140 142 +f 142 148 151 +f 153 144 143 +f 143 150 153 +f 133 90 91 +f 91 104 133 +f 131 92 93 +f 93 130 131 +f 124 132 105 +f 105 106 124 +f 87 107 108 +f 108 86 87 +f 123 109 110 +f 110 122 123 +f 118 111 112 +f 112 134 118 +f 100 113 114 +f 114 99 100 +f 119 129 115 +f 115 116 119 +f 97 124 106 +f 106 125 97 +f 83 126 107 +f 107 87 83 +f 86 108 127 +f 127 117 86 +f 132 135 128 +f 128 105 132 +f 99 114 109 +f 109 123 99 +f 129 134 112 +f 112 115 129 +f 113 100 136 +f 136 202 113 +f 97 125 133 +f 133 96 97 +f 125 90 133 +f 130 93 83 +f 83 84 130 +f 93 126 83 +f 203 92 131 +f 131 204 203 +f 122 110 128 +f 128 135 122 +f 117 127 111 +f 111 118 117 +f 205 208 207 +f 207 206 205 +f 207 208 209 +f 210 211 206 +f 206 207 210 +f 211 212 206 +f 213 205 206 +f 206 214 213 +f 215 209 208 +f 208 216 215 +f 217 210 207 +f 207 218 217 +f 219 212 211 +f 211 220 219 +f 216 208 205 +f 205 213 216 +f 212 219 214 +f 214 206 212 +f 218 207 209 +f 209 215 218 +f 220 211 210 +f 210 217 220 +f 221 224 223 +f 223 222 221 +f 223 224 225 +f 226 227 222 +f 222 223 226 +f 227 228 222 +f 229 221 222 +f 222 230 229 +f 231 225 224 +f 224 232 231 +f 233 226 223 +f 223 234 233 +f 235 228 227 +f 227 236 235 +f 232 224 221 +f 221 229 232 +f 228 235 230 +f 230 222 228 +f 234 223 225 +f 225 231 234 +f 236 227 226 +f 226 233 236 +f 131 85 237 +f 237 204 131 +f 116 113 202 +f 202 238 116 +f 85 82 120 +f 120 237 85 +f 91 92 203 +f 203 239 91 +f 95 102 137 +f 137 94 95 +f 116 238 121 +f 121 119 116 +f 104 91 239 +f 239 103 104 +f 204 237 241 +f 241 240 204 +f 102 103 243 +f 243 242 102 +f 120 121 245 +f 245 244 120 +f 238 202 247 +f 247 246 238 +f 237 120 244 +f 244 241 237 +f 239 203 249 +f 249 248 239 +f 137 102 242 +f 242 250 137 +f 136 137 250 +f 250 251 136 +f 121 238 246 +f 246 245 121 +f 202 136 251 +f 251 247 202 +f 103 239 248 +f 248 243 103 +f 203 204 240 +f 240 249 203 +f 240 241 253 +f 253 252 240 +f 242 243 255 +f 255 254 242 +f 244 245 257 +f 257 256 244 +f 246 247 259 +f 259 258 246 +f 241 244 256 +f 256 253 241 +f 248 249 261 +f 261 260 248 +f 250 242 254 +f 254 262 250 +f 251 250 262 +f 262 263 251 +f 245 246 258 +f 258 257 245 +f 247 251 263 +f 263 259 247 +f 243 248 260 +f 260 255 243 +f 249 240 252 +f 252 261 249 +f 261 252 253 +f 253 256 261 +f 257 258 261 +f 261 256 257 +f 263 254 261 +f 261 258 263 +f 263 258 259 +f 254 263 262 +f 255 260 261 +f 261 254 255 +f 264 267 266 +f 266 265 264 +f 267 269 268 +f 268 266 267 +f 269 271 270 +f 270 268 269 +f 271 273 272 +f 272 270 271 +f 273 275 274 +f 274 272 273 +f 275 277 276 +f 276 274 275 +f 277 264 265 +f 265 276 277 +f 278 281 280 +f 280 279 278 +f 279 280 283 +f 283 282 279 +f 282 283 285 +f 285 284 282 +f 284 285 287 +f 287 286 284 +f 286 287 289 +f 289 288 286 +f 288 289 291 +f 291 290 288 +f 290 291 281 +f 281 278 290 +f 280 281 265 +f 265 266 280 +f 278 279 267 +f 267 264 278 +f 283 280 266 +f 266 268 283 +f 279 282 269 +f 269 267 279 +f 285 283 268 +f 268 270 285 +f 282 284 271 +f 271 269 282 +f 287 285 270 +f 270 272 287 +f 284 286 273 +f 273 271 284 +f 289 287 272 +f 272 274 289 +f 286 288 275 +f 275 273 286 +f 291 289 274 +f 274 276 291 +f 288 290 277 +f 277 275 288 +f 281 291 276 +f 276 265 281 +f 290 278 264 +f 264 277 290 +f 292 295 294 +f 294 293 292 +f 295 297 296 +f 296 294 295 +f 297 299 298 +f 298 296 297 +f 299 301 300 +f 300 298 299 +f 301 303 302 +f 302 300 301 +f 303 305 304 +f 304 302 303 +f 305 292 293 +f 293 304 305 +f 306 309 308 +f 308 307 306 +f 307 308 311 +f 311 310 307 +f 310 311 313 +f 313 312 310 +f 312 313 315 +f 315 314 312 +f 314 315 317 +f 317 316 314 +f 316 317 319 +f 319 318 316 +f 318 319 309 +f 309 306 318 +f 308 309 293 +f 293 294 308 +f 306 307 295 +f 295 292 306 +f 311 308 294 +f 294 296 311 +f 307 310 297 +f 297 295 307 +f 313 311 296 +f 296 298 313 +f 310 312 299 +f 299 297 310 +f 315 313 298 +f 298 300 315 +f 312 314 301 +f 301 299 312 +f 317 315 300 +f 300 302 317 +f 314 316 303 +f 303 301 314 +f 319 317 302 +f 302 304 319 +f 316 318 305 +f 305 303 316 +f 309 319 304 +f 304 293 309 +f 318 306 292 +f 292 305 318 +# 540 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_foot_chull.obj b/examples/Atlas/urdf/mesh/r_foot_chull.obj new file mode 100644 index 0000000..1c2a2db --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_foot_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_foot_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.032478 0.032456 -0.000038 +v -0.030949 0.000206 0.012026 +v 0.029024 0.000680 0.011616 +v 0.032478 -0.032957 -0.000038 +v -0.090794 0.021605 -0.028558 +v -0.087663 0.040716 -0.048187 +v -0.087697 0.040705 -0.076451 +v -0.071584 0.068181 -0.039049 +v -0.071584 0.068181 -0.028170 +v 0.135826 -0.021953 -0.028138 +v 0.172786 0.031206 -0.055794 +v 0.172786 -0.034690 -0.055794 +v 0.134984 0.021567 -0.028083 +v -0.087697 -0.044189 -0.076451 +v -0.071747 -0.071664 -0.039049 +v 0.108368 -0.071664 -0.039048 +v 0.111018 -0.071299 -0.027900 +v -0.071747 -0.071664 -0.028170 +v 0.108368 0.068181 -0.039049 +v 0.108368 0.068181 -0.028170 +v -0.063498 0.062604 -0.076451 +v 0.115398 0.062582 -0.076451 +v -0.090933 -0.030079 -0.029310 +v 0.172699 -0.037354 -0.076448 +v 0.172760 0.033536 -0.076444 +v -0.063498 -0.066087 -0.076451 +v 0.110890 -0.066087 -0.076451 +# 27 vertices, 0 vertices normals + +f 2 5 23 +f 23 18 2 +f 2 9 5 +f 21 7 8 +f 24 12 17 +f 9 1 20 +f 2 1 9 +f 6 5 9 +f 13 11 20 +f 25 20 11 +f 15 26 27 +f 15 27 16 +f 15 14 26 +f 12 10 17 +f 10 3 17 +f 4 2 18 +f 4 18 17 +f 17 3 4 +f 2 3 1 +f 20 1 3 +f 3 13 20 +f 3 10 13 +f 4 3 2 +f 27 24 16 +f 7 5 6 +f 8 7 6 +f 6 9 8 +f 12 11 10 +f 10 11 13 +f 14 23 5 +f 14 5 7 +f 15 16 17 +f 18 15 17 +f 19 8 9 +f 19 9 20 +f 19 22 21 +f 19 21 8 +f 19 25 22 +f 19 20 25 +f 23 15 18 +f 14 15 23 +f 16 24 17 +f 25 11 12 +f 24 25 12 +f 27 21 22 +f 7 21 27 +f 14 27 26 +f 27 14 7 +f 27 25 24 +f 22 25 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_hand.obj b/examples/Atlas/urdf/mesh/r_hand.obj new file mode 100644 index 0000000..d5553c0 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_hand.obj @@ -0,0 +1,456 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_hand.obj +# +# Vertices: 148 +# Faces: 292 +# +#### +v -0.009549 -0.113904 0.028781 +v 0.024465 -0.113904 -0.018036 +v 0.024465 -0.113904 0.017729 +v 0.009254 -0.113904 0.028781 +v -0.030571 -0.113904 -0.000153 +v -0.024760 -0.113904 0.017729 +v -0.009549 -0.113904 -0.029087 +v -0.024760 -0.113904 -0.018036 +v 0.009254 -0.113904 -0.029087 +v 0.030276 -0.113904 -0.000153 +v 0.030276 -0.093460 -0.000153 +v 0.024465 -0.093460 0.017729 +v 0.009254 -0.093460 0.028781 +v -0.009549 -0.093460 0.028781 +v -0.024760 -0.093460 0.017729 +v -0.030571 -0.093460 -0.000153 +v -0.024760 -0.093460 -0.018036 +v -0.009549 -0.093460 -0.029087 +v 0.009254 -0.093460 -0.029087 +v 0.024465 -0.093460 -0.018036 +v 0.038430 -0.093460 -0.000153 +v 0.031063 -0.093460 0.022522 +v 0.011774 -0.093460 0.036537 +v -0.012069 -0.093460 0.036537 +v -0.031358 -0.093460 0.022522 +v -0.038725 -0.093460 -0.000153 +v -0.031358 -0.093460 -0.022829 +v -0.012069 -0.093460 -0.036843 +v 0.011774 -0.093460 -0.036843 +v 0.031063 -0.093460 -0.022829 +v 0.040541 -0.082531 0.016705 +v 0.038734 -0.082531 0.021941 +v 0.038734 -0.093295 0.021941 +v 0.040541 -0.093295 0.016705 +v 0.031063 -0.082366 0.022522 +v 0.011774 -0.082366 0.036537 +v -0.012069 -0.082366 0.036537 +v -0.031358 -0.082366 0.022522 +v -0.039263 -0.082531 0.021910 +v -0.040739 -0.082531 0.017275 +v -0.040739 -0.093295 0.017275 +v -0.039263 -0.093295 0.021910 +v -0.043969 -0.082531 -0.008515 +v -0.041970 -0.082531 -0.013429 +v -0.041970 -0.093295 -0.013429 +v -0.043969 -0.093295 -0.008515 +v -0.031358 -0.082366 -0.022829 +v -0.012069 -0.082366 -0.036843 +v 0.011774 -0.082366 -0.036843 +v 0.031063 -0.082366 -0.022829 +v 0.038777 -0.082531 -0.022133 +v 0.040571 -0.082531 -0.017855 +v 0.040571 -0.093295 -0.017855 +v 0.038777 -0.093295 -0.022133 +v 0.050900 -0.082366 -0.000153 +v 0.041151 -0.082366 0.029852 +v 0.038430 -0.082366 -0.000153 +v 0.015627 -0.082366 0.048396 +v -0.015922 -0.082366 0.048396 +v -0.041446 -0.082366 0.029852 +v -0.051195 -0.082366 -0.000153 +v -0.038725 -0.082366 -0.000153 +v -0.041446 -0.082366 -0.030158 +v -0.015922 -0.082366 -0.048702 +v 0.015627 -0.082366 -0.048702 +v 0.041151 -0.082366 -0.030158 +v 0.050900 -0.068177 -0.000153 +v 0.041151 -0.068176 0.029852 +v 0.015627 -0.068176 0.048396 +v -0.015922 -0.068176 0.048396 +v -0.041446 -0.068176 0.029852 +v -0.051195 -0.068177 -0.000153 +v -0.041446 -0.068177 -0.030158 +v -0.015922 -0.068177 -0.048702 +v 0.015627 -0.068177 -0.048702 +v 0.041151 -0.068177 -0.030158 +v 0.040327 -0.050848 -0.000153 +v 0.032597 -0.050848 0.023637 +v 0.012360 -0.050848 0.038340 +v -0.012655 -0.050848 0.038340 +v -0.032892 -0.050848 0.023637 +v -0.040622 -0.050848 -0.000153 +v -0.032892 -0.050848 -0.023943 +v -0.012655 -0.050848 -0.038647 +v 0.012360 -0.050848 -0.038647 +v 0.032597 -0.050848 -0.023943 +v 0.040327 -0.038334 -0.000153 +v 0.032597 -0.033297 0.023637 +v 0.012360 -0.041588 0.038340 +v -0.012655 -0.041588 0.038340 +v -0.032892 -0.033297 0.023637 +v -0.040622 -0.038334 -0.000153 +v -0.032892 -0.033297 -0.023943 +v -0.012655 -0.040500 -0.038647 +v 0.012360 -0.040500 -0.038647 +v 0.032597 -0.033297 -0.023943 +v -0.014411 -0.037767 -0.000153 +v -0.014541 -0.030282 0.028260 +v -0.014724 -0.029626 -0.028482 +v 0.013925 -0.030282 0.028259 +v 0.014710 -0.037767 -0.000153 +v 0.014292 -0.029626 -0.028482 +v -0.014674 -0.011171 -0.038196 +v -0.014674 0.033552 -0.023665 +v -0.014674 0.013551 -0.038196 +v -0.014674 -0.011171 0.037890 +v -0.014674 0.033552 0.023359 +v -0.014674 0.013551 0.037890 +v -0.014674 0.041191 -0.000153 +v 0.014281 0.041191 -0.000153 +v 0.014281 0.033552 0.023359 +v 0.014281 0.013551 0.037890 +v 0.014281 -0.011171 0.037890 +v 0.014281 -0.011171 -0.038196 +v 0.014281 0.013551 -0.038196 +v 0.014281 0.033552 -0.023665 +v 0.035154 -0.093295 0.009943 +v 0.031274 -0.093295 0.021871 +v 0.035154 -0.082531 0.009943 +v 0.031274 -0.082531 0.021871 +v 0.031147 -0.093295 -0.022730 +v 0.035072 -0.093295 -0.010594 +v 0.031147 -0.082531 -0.022730 +v 0.035072 -0.082531 -0.010594 +v -0.031481 -0.093295 0.022193 +v -0.035325 -0.093295 0.010391 +v -0.031481 -0.082531 0.022193 +v -0.035325 -0.082531 0.010391 +v -0.037763 -0.093295 -0.003150 +v -0.034362 -0.093295 -0.013582 +v -0.037763 -0.082531 -0.003150 +v -0.034362 -0.082531 -0.013582 +v -0.034760 -0.093295 0.023232 +v -0.037806 -0.093295 0.012912 +v -0.034760 -0.082531 0.023232 +v -0.037806 -0.082531 0.012912 +v -0.040855 -0.093295 -0.004158 +v -0.037453 -0.093295 -0.014590 +v -0.040855 -0.082531 -0.004158 +v -0.037453 -0.082531 -0.014590 +v 0.037575 -0.093295 0.012485 +v 0.034337 -0.093295 0.023043 +v 0.037575 -0.082531 0.012485 +v 0.034337 -0.082531 0.023043 +v 0.034733 -0.093295 -0.023615 +v 0.038731 -0.093295 -0.014007 +v 0.034733 -0.082531 -0.023615 +v 0.038731 -0.082531 -0.014007 +# 148 vertices, 0 vertices normals + +f 3 4 1 +f 1 2 3 +f 1 6 5 +f 5 2 1 +f 5 8 7 +f 7 2 5 +f 7 9 2 +f 10 3 2 +f 3 10 11 +f 11 12 3 +f 4 3 12 +f 12 13 4 +f 1 4 13 +f 13 14 1 +f 6 1 14 +f 14 15 6 +f 5 6 15 +f 15 16 5 +f 8 5 16 +f 16 17 8 +f 7 8 17 +f 17 18 7 +f 9 7 18 +f 18 19 9 +f 2 9 19 +f 19 20 2 +f 10 2 20 +f 20 11 10 +f 12 11 21 +f 21 22 12 +f 13 12 22 +f 22 23 13 +f 14 13 23 +f 23 24 14 +f 15 14 24 +f 24 25 15 +f 16 15 25 +f 25 26 16 +f 17 16 26 +f 26 27 17 +f 18 17 27 +f 27 28 18 +f 19 18 28 +f 28 29 19 +f 20 19 29 +f 29 30 20 +f 11 20 30 +f 30 21 11 +f 33 34 31 +f 31 32 33 +f 23 22 35 +f 35 36 23 +f 24 23 36 +f 36 37 24 +f 25 24 37 +f 37 38 25 +f 41 42 39 +f 39 40 41 +f 45 46 43 +f 43 44 45 +f 28 27 47 +f 47 48 28 +f 29 28 48 +f 48 49 29 +f 30 29 49 +f 49 50 30 +f 53 54 51 +f 51 52 53 +f 35 57 55 +f 55 56 35 +f 36 35 56 +f 56 58 36 +f 37 36 58 +f 58 59 37 +f 38 37 59 +f 59 60 38 +f 62 38 60 +f 60 61 62 +f 47 62 61 +f 61 63 47 +f 48 47 63 +f 63 64 48 +f 49 48 64 +f 64 65 49 +f 50 49 65 +f 65 66 50 +f 57 50 66 +f 66 55 57 +f 56 55 67 +f 67 68 56 +f 58 56 68 +f 68 69 58 +f 59 58 69 +f 69 70 59 +f 60 59 70 +f 70 71 60 +f 61 60 71 +f 71 72 61 +f 63 61 72 +f 72 73 63 +f 64 63 73 +f 73 74 64 +f 65 64 74 +f 74 75 65 +f 66 65 75 +f 75 76 66 +f 55 66 76 +f 76 67 55 +f 68 67 77 +f 77 78 68 +f 69 68 78 +f 78 79 69 +f 70 69 79 +f 79 80 70 +f 71 70 80 +f 80 81 71 +f 72 71 81 +f 81 82 72 +f 73 72 82 +f 82 83 73 +f 74 73 83 +f 83 84 74 +f 75 74 84 +f 84 85 75 +f 76 75 85 +f 85 86 76 +f 67 76 86 +f 86 77 67 +f 78 77 87 +f 87 88 78 +f 79 78 88 +f 88 89 79 +f 80 79 89 +f 89 90 80 +f 81 80 90 +f 90 91 81 +f 82 81 91 +f 91 92 82 +f 83 82 92 +f 92 93 83 +f 84 83 93 +f 93 94 84 +f 85 84 94 +f 94 95 85 +f 86 85 95 +f 95 96 86 +f 77 86 96 +f 96 87 77 +f 91 98 97 +f 97 92 91 +f 93 92 97 +f 97 99 93 +f 91 90 98 +f 94 93 99 +f 89 88 100 +f 88 87 101 +f 101 100 88 +f 101 87 96 +f 96 102 101 +f 102 96 95 +f 90 89 100 +f 100 98 90 +f 99 102 95 +f 95 94 99 +f 104 105 103 +f 103 97 104 +f 103 99 97 +f 97 98 106 +f 106 104 97 +f 106 108 107 +f 107 104 106 +f 109 104 107 +f 107 111 110 +f 110 109 107 +f 108 112 111 +f 111 107 108 +f 106 113 112 +f 112 108 106 +f 98 100 113 +f 113 106 98 +f 103 114 102 +f 102 99 103 +f 105 115 114 +f 114 103 105 +f 104 116 115 +f 115 105 104 +f 109 110 116 +f 116 104 109 +f 111 112 113 +f 113 101 111 +f 113 100 101 +f 101 102 114 +f 114 111 101 +f 114 115 116 +f 116 111 114 +f 110 111 116 +f 22 21 117 +f 117 118 22 +f 21 57 119 +f 119 117 21 +f 57 35 120 +f 120 119 57 +f 35 22 118 +f 118 120 35 +f 21 30 121 +f 121 122 21 +f 30 50 123 +f 123 121 30 +f 50 57 124 +f 124 123 50 +f 57 21 122 +f 122 124 57 +f 26 25 125 +f 125 126 26 +f 25 38 127 +f 127 125 25 +f 38 62 128 +f 128 127 38 +f 62 26 126 +f 126 128 62 +f 27 26 129 +f 129 130 27 +f 26 62 131 +f 131 129 26 +f 62 47 132 +f 132 131 62 +f 47 27 130 +f 130 132 47 +f 126 125 133 +f 133 134 126 +f 125 127 135 +f 135 133 125 +f 127 128 136 +f 136 135 127 +f 128 126 134 +f 134 136 128 +f 134 133 42 +f 42 41 134 +f 133 135 39 +f 39 42 133 +f 135 136 40 +f 40 39 135 +f 136 134 41 +f 41 40 136 +f 130 129 137 +f 137 138 130 +f 129 131 139 +f 139 137 129 +f 131 132 140 +f 140 139 131 +f 132 130 138 +f 138 140 132 +f 138 137 46 +f 46 45 138 +f 137 139 43 +f 43 46 137 +f 139 140 44 +f 44 43 139 +f 140 138 45 +f 45 44 140 +f 118 117 141 +f 141 142 118 +f 117 119 143 +f 143 141 117 +f 119 120 144 +f 144 143 119 +f 120 118 142 +f 142 144 120 +f 142 141 34 +f 34 33 142 +f 141 143 31 +f 31 34 141 +f 143 144 32 +f 32 31 143 +f 144 142 33 +f 33 32 144 +f 122 121 145 +f 145 146 122 +f 121 123 147 +f 147 145 121 +f 123 124 148 +f 148 147 123 +f 124 122 146 +f 146 148 124 +f 146 145 54 +f 54 53 146 +f 145 147 51 +f 51 54 145 +f 147 148 52 +f 52 51 147 +f 148 146 53 +f 53 52 148 +# 292 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_hand_chull.obj b/examples/Atlas/urdf/mesh/r_hand_chull.obj new file mode 100644 index 0000000..23f3b0b --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_hand_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_hand_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.044882 -0.080279 -0.028992 +v 0.053309 -0.076225 -0.000152 +v 0.014281 0.041191 -0.000153 +v -0.014674 0.033552 0.023359 +v 0.014281 0.033552 0.023359 +v -0.014674 0.041191 -0.000153 +v -0.014674 0.033552 -0.023665 +v 0.014281 0.033552 -0.023665 +v -0.045125 -0.080198 0.028724 +v -0.053416 -0.075618 -0.000096 +v -0.014674 0.013551 0.037890 +v 0.014281 0.013551 0.037890 +v -0.044974 -0.079756 -0.029092 +v -0.016073 -0.080021 -0.050154 +v 0.044807 -0.080117 0.028751 +v 0.015779 -0.079970 0.049844 +v -0.016122 -0.080027 0.049802 +v 0.014281 0.013551 -0.038196 +v -0.014674 0.013551 -0.038196 +v 0.015851 -0.080056 -0.050108 +v -0.000148 -0.114023 -0.030469 +v -0.015107 -0.113979 0.025886 +v 0.030276 -0.113904 -0.000153 +v 0.012683 -0.114219 0.027614 +v 0.024465 -0.113904 -0.018036 +v -0.024760 -0.113904 -0.018036 +v -0.030571 -0.113904 -0.000153 +# 27 vertices, 0 vertices normals + +f 14 13 19 +f 10 4 6 +f 12 15 5 +f 7 19 13 +f 7 13 10 +f 7 10 6 +f 2 1 8 +f 5 15 2 +f 5 2 3 +f 3 2 8 +f 4 10 9 +f 15 12 16 +f 11 9 17 +f 9 11 4 +f 1 2 23 +f 1 23 25 +f 15 23 2 +f 15 24 23 +f 24 15 16 +f 22 17 9 +f 18 8 1 +f 1 20 18 +f 25 21 20 +f 20 1 25 +f 26 13 14 +f 26 14 21 +f 13 27 10 +f 13 26 27 +f 27 9 10 +f 22 9 27 +f 3 4 5 +f 6 4 3 +f 3 7 6 +f 3 8 7 +f 11 16 12 +f 17 16 11 +f 11 5 4 +f 11 12 5 +f 24 17 22 +f 17 24 16 +f 18 7 8 +f 19 7 18 +f 18 14 19 +f 18 20 14 +f 20 21 14 +f 22 23 24 +f 22 21 25 +f 23 22 25 +f 27 26 22 +f 22 26 21 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_larm.obj b/examples/Atlas/urdf/mesh/r_larm.obj new file mode 100644 index 0000000..2ef7dfe --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_larm.obj @@ -0,0 +1,641 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_larm.obj +# +# Vertices: 217 +# Faces: 408 +# +#### +v 0.048129 -0.090646 -0.038389 +v 0.061391 -0.090646 -0.038389 +v 0.048129 -0.066514 -0.038389 +v 0.061391 -0.066514 -0.038389 +v 0.048129 -0.090646 0.020936 +v 0.061391 -0.090646 0.020936 +v 0.048129 -0.066514 0.020936 +v 0.061391 -0.066514 0.020936 +v 0.051284 -0.060320 -0.027988 +v 0.061391 -0.060320 -0.027988 +v 0.051284 -0.060320 0.020936 +v 0.061391 -0.060320 0.020936 +v 0.051284 -0.034224 -0.027988 +v 0.061391 -0.034224 -0.027988 +v 0.051284 -0.023692 0.020936 +v 0.061391 -0.023692 0.020936 +v 0.051284 -0.022644 -0.034589 +v 0.061391 -0.022644 -0.034589 +v 0.051284 -0.015214 0.028246 +v 0.061391 -0.015214 0.028246 +v 0.051284 -0.000722 -0.034589 +v 0.061391 -0.000722 -0.034589 +v 0.051284 0.000823 0.032348 +v 0.061391 0.000823 0.032348 +v 0.051284 0.016745 -0.034589 +v 0.061391 0.016745 -0.034589 +v 0.051284 0.018290 0.026311 +v 0.061391 0.018290 0.026311 +v 0.051284 0.025626 -0.032383 +v 0.061391 0.025626 -0.032383 +v 0.051284 0.027171 0.016867 +v 0.061391 0.027171 0.016867 +v 0.051284 0.032066 -0.025937 +v 0.061391 0.032066 -0.025937 +v 0.051284 0.032075 0.002879 +v 0.061391 0.032075 0.002879 +v -0.066860 0.025800 -0.007185 +v -0.066860 0.025809 0.005549 +v -0.058102 0.025809 0.005549 +v -0.058102 0.025800 -0.007185 +v -0.066860 0.020544 -0.017703 +v -0.066860 0.020553 0.016068 +v -0.058102 0.020553 0.016068 +v -0.058102 0.020544 -0.017703 +v -0.066860 0.009440 -0.025833 +v -0.066860 0.009449 0.024198 +v -0.058102 0.009450 0.024198 +v -0.058102 0.009440 -0.025833 +v -0.066860 -0.000152 -0.028976 +v -0.066860 -0.000143 0.025921 +v -0.058102 -0.000143 0.025921 +v -0.058102 -0.000152 -0.028976 +v -0.066860 -0.011272 -0.034183 +v -0.066860 -0.011263 0.023490 +v -0.058102 -0.011262 0.023490 +v -0.058102 -0.011272 -0.034183 +v -0.066860 -0.023928 -0.038781 +v -0.066860 -0.023918 0.011828 +v -0.058102 -0.023918 0.011828 +v -0.058102 -0.023928 -0.038781 +v -0.071527 -0.032102 -0.038781 +v -0.071527 -0.032092 0.007581 +v -0.061493 -0.032092 0.007581 +v -0.061493 -0.032102 -0.038781 +v -0.071527 -0.053703 -0.038781 +v -0.071527 -0.053694 0.007581 +v -0.061493 -0.053694 0.007581 +v -0.061493 -0.053703 -0.038781 +v -0.071527 -0.067301 -0.038781 +v -0.071527 -0.067292 0.021157 +v -0.061493 -0.067292 0.021157 +v -0.061493 -0.067301 -0.038781 +v -0.071527 -0.092961 -0.038781 +v -0.071527 -0.090326 0.021157 +v -0.061493 -0.090326 0.021157 +v -0.061493 -0.092961 -0.038781 +v -0.081892 -0.090413 -0.036857 +v -0.058294 -0.090413 -0.036857 +v -0.058294 -0.090403 0.019233 +v -0.081892 -0.090403 0.019233 +v -0.081892 -0.147050 -0.036857 +v -0.058294 -0.147050 -0.036857 +v -0.058294 -0.147041 0.019233 +v -0.081892 -0.147041 0.019233 +v -0.081892 -0.153337 -0.029257 +v -0.058294 -0.153337 -0.029257 +v -0.058294 -0.153328 0.011633 +v -0.081892 -0.153328 0.011633 +v -0.046757 -0.138361 -0.045359 +v -0.052272 -0.146707 -0.036957 +v -0.081892 -0.146707 -0.036957 +v -0.081892 -0.141839 -0.041878 +v -0.071867 -0.132932 -0.050765 +v -0.066103 -0.132932 -0.050765 +v -0.055857 -0.138361 -0.045359 +v -0.078537 -0.137113 -0.046586 +v -0.060976 -0.134578 -0.049114 +v -0.046757 -0.115218 -0.045359 +v -0.052272 -0.115264 -0.036957 +v -0.081892 -0.088421 -0.036957 +v -0.081892 -0.088651 -0.041878 +v -0.071867 -0.096590 -0.050765 +v -0.066103 -0.096590 -0.050765 +v -0.055857 -0.093485 -0.045359 +v -0.078537 -0.092238 -0.046586 +v -0.060976 -0.098236 -0.049114 +v -0.046757 -0.057084 -0.045359 +v -0.053101 -0.058916 -0.037580 +v -0.081892 -0.036868 -0.036957 +v -0.081892 -0.042118 -0.041878 +v -0.055857 -0.057369 -0.045359 +v -0.078537 -0.048567 -0.046586 +v -0.034962 -0.115103 -0.036916 +v -0.034960 -0.115058 -0.045317 +v -0.034960 -0.056923 -0.045317 +v -0.034962 -0.058755 -0.037539 +v -0.080250 -0.030817 0.003277 +v -0.080250 -0.030822 -0.020901 +v -0.080250 -0.063465 -0.020901 +v -0.080250 -0.063460 0.003277 +v -0.071535 -0.030817 0.003277 +v -0.071535 -0.030822 -0.020901 +v -0.071535 -0.063465 -0.020901 +v -0.071535 -0.063460 0.003277 +v 0.042151 -0.143759 0.021378 +v 0.052136 -0.143759 -0.009353 +v 0.052136 -0.128425 -0.009353 +v 0.042151 -0.124020 0.021378 +v 0.016009 -0.143759 0.040371 +v 0.016009 -0.118034 0.040371 +v -0.016304 -0.143759 0.040371 +v -0.016304 -0.118034 0.040371 +v -0.042446 -0.143759 0.021378 +v -0.042446 -0.124020 0.021378 +v -0.052431 -0.143759 -0.009353 +v -0.050404 -0.128425 0.001405 +v -0.042446 -0.143759 -0.040085 +v -0.042446 -0.128425 -0.040085 +v -0.016304 -0.143759 -0.059078 +v -0.013997 -0.128425 -0.059078 +v 0.016009 -0.143759 -0.059078 +v 0.016009 -0.128425 -0.059078 +v 0.042151 -0.143759 -0.040085 +v 0.042151 -0.128425 -0.040085 +v 0.047948 -0.096130 -0.009353 +v 0.036801 -0.096130 0.020154 +v 0.014715 -0.096130 0.036388 +v -0.015010 -0.096130 0.036388 +v -0.036795 -0.096130 0.020570 +v -0.050221 -0.096130 0.001350 +v -0.013992 -0.096130 -0.055095 +v 0.014715 -0.096130 -0.055095 +v 0.035146 -0.096130 -0.039513 +v 0.055223 -0.063277 -0.009353 +v 0.055208 -0.063277 0.020299 +v 0.055208 -0.091082 0.020299 +v 0.055223 -0.091082 -0.009353 +v 0.036801 -0.055595 0.020154 +v 0.014715 -0.055595 0.036388 +v -0.015010 -0.055595 0.036388 +v -0.036795 -0.055595 0.020570 +v -0.054179 -0.063277 0.020078 +v -0.054195 -0.063277 0.003501 +v -0.054195 -0.091082 0.003448 +v -0.054179 -0.091082 0.020082 +v -0.013992 -0.055595 -0.055095 +v 0.014715 -0.055595 -0.055095 +v 0.035146 -0.055595 -0.039513 +v 0.055208 -0.063277 -0.039006 +v 0.055208 -0.091082 -0.039006 +v 0.047948 -0.055595 -0.009353 +v 0.014715 -0.055595 0.001405 +v -0.050313 -0.128425 -0.059031 +v -0.037691 -0.128425 -0.060006 +v -0.013997 -0.128425 -0.061836 +v -0.050265 -0.096130 -0.057568 +v -0.054195 -0.063277 -0.037488 +v -0.054195 -0.091082 -0.038266 +v -0.013992 -0.096130 -0.076251 +v -0.013992 -0.048069 -0.076251 +v -0.050264 -0.047694 -0.056155 +v -0.050221 -0.047694 0.001405 +v -0.039058 -0.047694 -0.037623 +v -0.036280 -0.047694 -0.055746 +v -0.013992 -0.047694 -0.055095 +v -0.031926 -0.128425 -0.084157 +v -0.031926 -0.096132 -0.084157 +v -0.013997 -0.128425 -0.076251 +v -0.050279 -0.096130 -0.076246 +v -0.050287 -0.128425 -0.076246 +v -0.031925 -0.048069 -0.084157 +v -0.050279 -0.048069 -0.076246 +v -0.014501 -0.055595 0.001405 +v -0.050221 -0.055595 0.001405 +v -0.014501 -0.047694 0.001405 +v 0.014715 -0.047694 0.001405 +v 0.014715 -0.047694 -0.055095 +v -0.036280 -0.016583 -0.055746 +v -0.013992 -0.016583 -0.055095 +v -0.013992 -0.016583 -0.076251 +v -0.031925 -0.016583 -0.084157 +v -0.050279 -0.016583 -0.076246 +v -0.050264 -0.016583 -0.056155 +v -0.050264 -0.055595 -0.056155 +v -0.036280 -0.055595 -0.055746 +v 0.047948 -0.092379 -0.009353 +v 0.038143 -0.092379 0.020299 +v 0.036319 -0.092379 -0.039183 +v 0.036319 -0.061979 -0.039183 +v 0.047948 -0.061979 -0.009353 +v 0.038143 -0.061979 0.020299 +v -0.037928 -0.092200 0.020213 +v -0.050419 -0.092200 0.003636 +v -0.037923 -0.062159 0.020210 +v -0.050416 -0.062159 0.003689 +v -0.050257 -0.061953 -0.040299 +v -0.050258 -0.092406 -0.041076 +# 217 vertices, 0 vertices normals + +f 4 2 1 +f 1 3 4 +f 8 7 5 +f 5 6 8 +f 6 5 1 +f 1 2 6 +f 8 6 2 +f 2 4 8 +f 5 7 3 +f 3 1 5 +f 9 10 4 +f 4 3 9 +f 12 11 7 +f 7 8 12 +f 10 12 8 +f 8 4 10 +f 11 9 3 +f 3 7 11 +f 13 14 10 +f 10 9 13 +f 16 15 11 +f 11 12 16 +f 14 16 12 +f 12 10 14 +f 15 13 9 +f 9 11 15 +f 17 18 14 +f 14 13 17 +f 20 19 15 +f 15 16 20 +f 18 20 16 +f 16 14 18 +f 19 17 13 +f 13 15 19 +f 21 22 18 +f 18 17 21 +f 24 23 19 +f 19 20 24 +f 22 24 20 +f 20 18 22 +f 23 21 17 +f 17 19 23 +f 25 26 22 +f 22 21 25 +f 28 27 23 +f 23 24 28 +f 26 28 24 +f 24 22 26 +f 27 25 21 +f 21 23 27 +f 29 30 26 +f 26 25 29 +f 32 31 27 +f 27 28 32 +f 30 32 28 +f 28 26 30 +f 31 29 25 +f 25 27 31 +f 33 34 30 +f 30 29 33 +f 36 35 31 +f 31 32 36 +f 34 36 32 +f 32 30 34 +f 35 33 29 +f 29 31 35 +f 34 33 35 +f 35 36 34 +f 40 37 38 +f 38 39 40 +f 41 42 38 +f 38 37 41 +f 42 43 39 +f 39 38 42 +f 43 44 40 +f 40 39 43 +f 44 41 37 +f 37 40 44 +f 45 46 42 +f 42 41 45 +f 46 47 43 +f 43 42 46 +f 47 48 44 +f 44 43 47 +f 48 45 41 +f 41 44 48 +f 49 50 46 +f 46 45 49 +f 50 51 47 +f 47 46 50 +f 51 52 48 +f 48 47 51 +f 52 49 45 +f 45 48 52 +f 53 54 50 +f 50 49 53 +f 54 55 51 +f 51 50 54 +f 55 56 52 +f 52 51 55 +f 56 53 49 +f 49 52 56 +f 57 58 54 +f 54 53 57 +f 58 59 55 +f 55 54 58 +f 59 60 56 +f 56 55 59 +f 60 57 53 +f 53 56 60 +f 61 62 58 +f 58 57 61 +f 62 63 59 +f 59 58 62 +f 63 64 60 +f 60 59 63 +f 64 61 57 +f 57 60 64 +f 65 66 62 +f 62 61 65 +f 66 67 63 +f 63 62 66 +f 67 68 64 +f 64 63 67 +f 68 65 61 +f 61 64 68 +f 69 70 66 +f 66 65 69 +f 70 71 67 +f 67 66 70 +f 71 72 68 +f 68 67 71 +f 72 69 65 +f 65 68 72 +f 73 74 70 +f 70 69 73 +f 74 75 71 +f 71 70 74 +f 75 76 72 +f 72 71 75 +f 76 73 69 +f 69 72 76 +f 74 73 76 +f 76 75 74 +f 80 79 78 +f 78 77 80 +f 82 81 77 +f 77 78 82 +f 83 82 78 +f 78 79 83 +f 84 83 79 +f 79 80 84 +f 81 84 80 +f 80 77 81 +f 86 85 81 +f 81 82 86 +f 87 86 82 +f 82 83 87 +f 88 87 83 +f 83 84 88 +f 85 88 84 +f 84 81 85 +f 85 86 87 +f 87 88 85 +f 92 96 90 +f 90 91 92 +f 93 94 90 +f 90 96 93 +f 97 95 90 +f 90 94 97 +f 89 90 95 +f 98 99 90 +f 90 89 98 +f 99 100 91 +f 91 90 99 +f 100 101 92 +f 92 91 100 +f 101 105 96 +f 96 92 101 +f 102 103 94 +f 94 93 102 +f 103 106 97 +f 97 94 103 +f 104 98 89 +f 89 95 104 +f 105 102 93 +f 93 96 105 +f 106 104 95 +f 95 97 106 +f 115 116 113 +f 113 114 115 +f 108 109 100 +f 100 99 108 +f 109 110 101 +f 101 100 109 +f 110 112 105 +f 105 101 110 +f 111 107 98 +f 98 104 111 +f 111 104 105 +f 105 112 111 +f 103 105 104 +f 104 106 103 +f 102 105 103 +f 114 113 99 +f 99 98 114 +f 115 114 98 +f 98 107 115 +f 116 115 107 +f 107 108 116 +f 113 116 108 +f 108 99 113 +f 110 108 111 +f 111 112 110 +f 110 109 108 +f 107 111 108 +f 119 120 117 +f 117 118 119 +f 121 122 118 +f 118 117 121 +f 122 123 119 +f 119 118 122 +f 123 124 120 +f 120 119 123 +f 124 121 117 +f 117 120 124 +f 127 128 125 +f 125 126 127 +f 128 130 129 +f 129 125 128 +f 130 132 131 +f 131 129 130 +f 132 134 133 +f 133 131 132 +f 134 136 135 +f 135 133 134 +f 136 138 137 +f 137 135 136 +f 138 140 139 +f 139 137 138 +f 140 142 141 +f 141 139 140 +f 142 144 143 +f 143 141 142 +f 144 127 126 +f 126 143 144 +f 125 129 131 +f 131 143 125 +f 131 133 135 +f 135 143 131 +f 135 137 139 +f 139 143 135 +f 139 141 143 +f 126 125 143 +f 128 127 145 +f 145 146 128 +f 130 128 146 +f 146 147 130 +f 132 130 147 +f 147 148 132 +f 134 132 148 +f 148 149 134 +f 136 134 149 +f 149 150 136 +f 142 140 151 +f 151 152 142 +f 144 142 152 +f 152 153 144 +f 127 144 153 +f 153 145 127 +f 156 157 154 +f 154 155 156 +f 147 146 158 +f 158 159 147 +f 148 147 159 +f 159 160 148 +f 149 148 160 +f 160 161 149 +f 164 165 162 +f 162 163 164 +f 152 151 166 +f 166 167 152 +f 153 152 167 +f 167 168 153 +f 157 170 169 +f 169 154 157 +f 172 159 158 +f 158 171 172 +f 173 174 138 +f 138 136 173 +f 140 138 174 +f 174 175 140 +f 136 150 176 +f 176 173 136 +f 151 140 175 +f 164 163 177 +f 177 178 164 +f 166 151 179 +f 179 180 166 +f 183 184 181 +f 181 182 183 +f 183 185 184 +f 179 188 186 +f 186 187 179 +f 186 190 189 +f 189 187 186 +f 189 192 191 +f 191 187 189 +f 191 180 179 +f 179 187 191 +f 161 160 193 +f 193 194 161 +f 193 160 159 +f 159 172 193 +f 168 167 172 +f 172 171 168 +f 196 197 185 +f 185 195 196 +f 195 185 183 +f 183 182 195 +f 200 201 198 +f 198 199 200 +f 198 201 202 +f 202 203 198 +f 192 189 176 +f 176 204 192 +f 189 190 173 +f 173 176 189 +f 190 186 174 +f 174 173 190 +f 186 188 175 +f 175 174 186 +f 151 175 188 +f 188 179 151 +f 166 180 200 +f 200 199 166 +f 180 191 201 +f 201 200 180 +f 191 192 202 +f 202 201 191 +f 192 204 203 +f 203 202 192 +f 204 205 198 +f 198 203 204 +f 205 166 199 +f 199 198 205 +f 146 145 206 +f 206 207 146 +f 145 153 208 +f 208 206 145 +f 153 168 209 +f 209 208 153 +f 168 171 210 +f 210 209 168 +f 171 158 211 +f 211 210 171 +f 158 146 207 +f 207 211 158 +f 150 149 212 +f 212 213 150 +f 149 161 214 +f 214 212 149 +f 161 194 215 +f 215 214 161 +f 194 204 216 +f 216 215 194 +f 204 176 217 +f 217 216 204 +f 176 150 213 +f 213 217 176 +f 207 206 157 +f 157 156 207 +f 206 208 170 +f 170 157 206 +f 208 209 169 +f 169 170 208 +f 209 210 154 +f 154 169 209 +f 210 211 155 +f 155 154 210 +f 211 207 156 +f 156 155 211 +f 213 212 165 +f 165 164 213 +f 212 214 162 +f 162 165 212 +f 214 215 163 +f 163 162 214 +f 215 216 177 +f 177 163 215 +f 216 217 178 +f 178 177 216 +f 217 213 164 +f 164 178 217 +f 167 166 185 +f 185 197 167 +f 166 205 184 +f 184 185 166 +f 205 204 181 +f 181 184 205 +f 204 194 182 +f 182 181 204 +f 194 193 195 +f 195 182 194 +f 193 172 196 +f 196 195 193 +f 172 167 197 +f 197 196 172 +# 408 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_larm_chull.obj b/examples/Atlas/urdf/mesh/r_larm_chull.obj new file mode 100644 index 0000000..1f4ea26 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_larm_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_larm_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.067883 0.004815 0.025513 +v 0.042151 -0.143759 -0.040085 +v -0.066926 0.025355 0.010415 +v 0.051899 -0.143745 0.007179 +v -0.068724 0.024822 -0.010525 +v -0.050279 -0.016583 -0.076246 +v 0.061360 0.002422 0.032561 +v 0.061343 0.023685 0.023759 +v -0.014212 -0.056357 0.036535 +v -0.011171 -0.142955 0.042057 +v 0.013793 -0.143694 0.041662 +v 0.061469 -0.088409 -0.038787 +v -0.013992 -0.016583 -0.076251 +v 0.061391 -0.090646 0.020936 +v 0.061391 0.022711 -0.034283 +v 0.061391 0.032600 0.002655 +v 0.056645 0.032368 -0.026631 +v 0.016009 -0.143759 -0.059078 +v -0.072094 -0.154371 -0.030013 +v -0.028778 -0.129125 -0.083564 +v -0.031925 -0.016583 -0.084157 +v -0.079363 -0.155075 0.008877 +v -0.082069 -0.042508 -0.042713 +v -0.081579 -0.045244 0.010440 +v -0.081892 -0.147041 0.019233 +v -0.081890 -0.141295 -0.043010 +v -0.050287 -0.128425 -0.076246 +# 27 vertices, 0 vertices normals + +f 7 14 11 +f 1 8 7 +f 13 15 21 +f 21 15 17 +f 8 3 16 +f 4 11 14 +f 18 2 12 +f 18 19 2 +f 19 20 27 +f 23 3 24 +f 1 25 24 +f 9 10 1 +f 1 7 9 +f 9 7 11 +f 10 25 1 +f 15 13 12 +f 16 3 17 +f 17 5 21 +f 3 8 1 +f 1 24 3 +f 19 4 2 +f 12 2 4 +f 4 14 12 +f 22 25 10 +f 20 18 12 +f 19 18 20 +f 5 3 23 +f 5 17 3 +f 11 4 22 +f 22 4 19 +f 6 27 21 +f 6 21 5 +f 23 6 5 +f 19 27 26 +f 23 27 6 +f 10 9 11 +f 20 12 13 +f 16 14 7 +f 12 14 16 +f 15 12 16 +f 16 17 15 +f 16 7 8 +f 21 27 20 +f 20 13 21 +f 22 10 11 +f 26 23 24 +f 22 26 25 +f 26 24 25 +f 26 22 19 +f 23 26 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_lglut.obj b/examples/Atlas/urdf/mesh/r_lglut.obj new file mode 100644 index 0000000..e4ab0a9 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_lglut.obj @@ -0,0 +1,1309 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_lglut.obj +# +# Vertices: 446 +# Faces: 847 +# +#### +v 0.049216 -0.015040 -0.015218 +v 0.082320 -0.015040 -0.015218 +v 0.082320 -0.000371 -0.021294 +v 0.049216 -0.000371 -0.021294 +v 0.049216 -0.021116 -0.000550 +v 0.082320 -0.021116 -0.000550 +v 0.049216 -0.015040 0.014119 +v 0.082320 -0.015040 0.014119 +v 0.049216 -0.000371 0.020195 +v 0.082320 -0.000371 0.020195 +v 0.049216 0.014298 0.014119 +v 0.082320 0.014298 0.014119 +v 0.049216 0.020374 -0.000550 +v 0.082320 0.020374 -0.000550 +v 0.049216 0.014298 -0.015218 +v 0.082320 0.014298 -0.015218 +v 0.082320 -0.010812 -0.010991 +v 0.082320 -0.000371 -0.015316 +v 0.082320 -0.015137 -0.000550 +v 0.082320 -0.010812 0.009892 +v 0.082320 -0.000371 0.014217 +v 0.082320 0.010071 0.009892 +v 0.082320 0.014395 -0.000550 +v 0.082320 0.010071 -0.010991 +v 0.055189 -0.007506 -0.007684 +v 0.055189 -0.000371 -0.010640 +v 0.055189 -0.010461 -0.000550 +v 0.055189 -0.007506 0.006585 +v 0.055189 -0.000371 0.009540 +v 0.055189 0.006764 0.006585 +v 0.055189 0.009719 -0.000550 +v 0.055189 0.006764 -0.007684 +v 0.049216 -0.000371 -0.010346 +v 0.049216 -0.007298 -0.007477 +v 0.049216 -0.010167 -0.000550 +v 0.049216 -0.007298 0.006377 +v 0.049216 -0.000371 0.009247 +v 0.049216 0.006556 0.006377 +v 0.049216 0.009426 -0.000550 +v 0.049216 0.006556 -0.007477 +v 0.055284 -0.048024 -0.002475 +v 0.071703 -0.048024 -0.002475 +v 0.071703 -0.047241 -0.010830 +v 0.055284 -0.047241 -0.010830 +v 0.055284 -0.044645 0.006092 +v 0.071703 -0.044645 0.006092 +v 0.055284 -0.036078 0.009641 +v 0.071703 -0.036078 0.009641 +v 0.055284 -0.036078 -0.014591 +v 0.055284 -0.036078 -0.007716 +v 0.055284 -0.039783 -0.006181 +v 0.071703 -0.039783 -0.006181 +v 0.071703 -0.036078 -0.007716 +v 0.071703 -0.036078 -0.014591 +v 0.055284 -0.041318 -0.002475 +v 0.071703 -0.041318 -0.002475 +v 0.055284 -0.039783 0.001231 +v 0.071703 -0.039783 0.001231 +v 0.055284 -0.036078 0.002765 +v 0.071703 -0.036078 0.002765 +v 0.055284 -0.032372 0.001231 +v 0.055284 -0.027510 0.006092 +v 0.071703 -0.027510 0.006092 +v 0.071703 -0.032372 0.001231 +v 0.055284 -0.030837 -0.002475 +v 0.055284 -0.023962 -0.002475 +v 0.071703 -0.023962 -0.002475 +v 0.071703 -0.030837 -0.002475 +v 0.055284 -0.032372 -0.006181 +v 0.055284 -0.027510 -0.011042 +v 0.071703 -0.027510 -0.011042 +v 0.071703 -0.032372 -0.006181 +v 0.055284 -0.046783 -0.017370 +v 0.055284 -0.030021 -0.017370 +v 0.071703 -0.046783 -0.017407 +v 0.071703 -0.030021 -0.017174 +v 0.055284 -0.003273 0.018663 +v 0.071703 -0.003273 0.018663 +v 0.055284 -0.017042 0.008892 +v 0.071703 -0.017042 0.008892 +v 0.055284 -0.019831 -0.002475 +v 0.071703 -0.019831 -0.002475 +v 0.055284 -0.011314 -0.017407 +v 0.071703 -0.011309 -0.017407 +v 0.080771 -0.031880 -0.033083 +v 0.080771 -0.046241 -0.033083 +v 0.072395 -0.046241 -0.023942 +v 0.072395 -0.031880 -0.023942 +v 0.080230 -0.031880 -0.045470 +v 0.080230 -0.046241 -0.045470 +v 0.070474 -0.031880 -0.067285 +v 0.068248 -0.031880 -0.046040 +v 0.062213 -0.031880 -0.045777 +v 0.058702 -0.031880 -0.053306 +v 0.058702 -0.046241 -0.053306 +v 0.062213 -0.046241 -0.045777 +v 0.068248 -0.046241 -0.046040 +v 0.070474 -0.046241 -0.067285 +v 0.058132 -0.031880 -0.041323 +v 0.050326 -0.031880 -0.049531 +v 0.050326 -0.046241 -0.049531 +v 0.058132 -0.046241 -0.041323 +v 0.058396 -0.031880 -0.035289 +v 0.050867 -0.031880 -0.031778 +v 0.050867 -0.046241 -0.031778 +v 0.058396 -0.046241 -0.035289 +v 0.062849 -0.031880 -0.031208 +v 0.060008 -0.031880 -0.023402 +v 0.060008 -0.046241 -0.023402 +v 0.062849 -0.046241 -0.031208 +v 0.068884 -0.031880 -0.031471 +v 0.068884 -0.046241 -0.031471 +v 0.072965 -0.031880 -0.035925 +v 0.072965 -0.046241 -0.035925 +v 0.072701 -0.031880 -0.041959 +v 0.072701 -0.046241 -0.041959 +v 0.044195 -0.046819 -0.017370 +v 0.043404 -0.033423 -0.017370 +v 0.044104 -0.031880 -0.031778 +v 0.044658 -0.031880 -0.049531 +v 0.044658 -0.046241 -0.049531 +v 0.044104 -0.046241 -0.031778 +v 0.047869 -0.031880 -0.023402 +v 0.047869 -0.046241 -0.023402 +v 0.035365 -0.046763 -0.031948 +v 0.035365 -0.047518 -0.045987 +v 0.035365 -0.046433 -0.023528 +v 0.035365 -0.046819 -0.017416 +v 0.035365 -0.035831 -0.012919 +v 0.035365 -0.035831 -0.006900 +v 0.035365 -0.039640 -0.005322 +v 0.035365 -0.041217 -0.001514 +v 0.035365 -0.047237 -0.001514 +v 0.035365 -0.039640 0.002295 +v 0.035365 -0.043896 0.006551 +v 0.035365 -0.035831 0.003872 +v 0.035365 -0.035831 0.009892 +v 0.035365 -0.032022 0.002295 +v 0.035365 -0.027766 0.006551 +v 0.035365 -0.030445 -0.001514 +v 0.035365 -0.024425 -0.001514 +v 0.035365 -0.032022 -0.005322 +v 0.035365 -0.020730 -0.010746 +v 0.044195 -0.039640 -0.005322 +v 0.044195 -0.035831 -0.006900 +v 0.044195 -0.041217 -0.001514 +v 0.044195 -0.047237 -0.001514 +v 0.044195 -0.039640 0.002295 +v 0.044195 -0.043896 0.006551 +v 0.044195 -0.035831 0.003872 +v 0.044195 -0.035831 0.009892 +v 0.044195 -0.032022 0.002295 +v 0.044195 -0.027766 0.006551 +v 0.044195 -0.030445 -0.001514 +v 0.044195 -0.024425 -0.001514 +v 0.044195 -0.032022 -0.005322 +v 0.044195 -0.020730 -0.010746 +v 0.064714 0.009702 -0.081368 +v 0.060487 0.009702 -0.077141 +v 0.050046 0.009702 -0.081466 +v 0.050046 0.009702 -0.087444 +v 0.070790 0.009702 -0.066700 +v 0.064812 0.009702 -0.066700 +v 0.064714 0.009702 -0.052031 +v 0.060487 0.009702 -0.056258 +v 0.050046 0.009702 -0.045955 +v 0.050046 0.009702 -0.051933 +v 0.035377 0.009702 -0.052031 +v 0.039604 0.009702 -0.056258 +v 0.029301 0.009702 -0.066700 +v 0.035279 0.009702 -0.066700 +v 0.035377 0.009702 -0.081368 +v 0.039604 0.009702 -0.077141 +v 0.050046 -0.055867 -0.081466 +v 0.060487 -0.055867 -0.077141 +v 0.064714 -0.055867 -0.081368 +v 0.050046 -0.055867 -0.087444 +v 0.064812 -0.055867 -0.066700 +v 0.070790 -0.055867 -0.066700 +v 0.060487 -0.055867 -0.056258 +v 0.064714 -0.055867 -0.052031 +v 0.050046 -0.055867 -0.051933 +v 0.050046 -0.055867 -0.045955 +v 0.039604 -0.055867 -0.056258 +v 0.035377 -0.055867 -0.052031 +v 0.035279 -0.055867 -0.066700 +v 0.029301 -0.055867 -0.066700 +v 0.039604 -0.055867 -0.077141 +v 0.035377 -0.055867 -0.081368 +v 0.080399 0.000769 -0.033083 +v 0.080399 -0.013592 -0.033083 +v 0.072023 -0.013592 -0.023942 +v 0.072023 0.000769 -0.023942 +v 0.079858 0.000769 -0.045470 +v 0.079858 -0.013592 -0.045470 +v 0.070102 0.000769 -0.067285 +v 0.067876 0.000769 -0.046040 +v 0.061841 0.000769 -0.045777 +v 0.058330 0.000769 -0.053306 +v 0.058330 -0.013592 -0.053306 +v 0.061841 -0.013592 -0.045777 +v 0.067876 -0.013592 -0.046040 +v 0.070102 -0.013592 -0.067285 +v 0.057760 0.000769 -0.041323 +v 0.049954 0.000769 -0.049531 +v 0.049954 -0.013592 -0.049531 +v 0.057760 -0.013592 -0.041323 +v 0.058024 0.000769 -0.035289 +v 0.050495 0.000769 -0.031778 +v 0.050495 -0.013592 -0.031778 +v 0.058024 -0.013592 -0.035289 +v 0.062477 0.000769 -0.031208 +v 0.059636 0.000769 -0.023402 +v 0.059636 -0.013592 -0.023402 +v 0.062477 -0.013592 -0.031208 +v 0.068512 0.000769 -0.031471 +v 0.068512 -0.013592 -0.031471 +v 0.072593 0.000769 -0.035925 +v 0.072593 -0.013592 -0.035925 +v 0.072329 0.000769 -0.041959 +v 0.072329 -0.013592 -0.041959 +v 0.071331 -0.014134 -0.017407 +v 0.054912 -0.014134 -0.017407 +v 0.071331 0.002628 -0.017174 +v 0.054912 0.002628 -0.017174 +v 0.049954 -0.033141 -0.049531 +v 0.050495 -0.033141 -0.031778 +v 0.059636 -0.033141 -0.023402 +v 0.054912 -0.033683 -0.017407 +v 0.035365 -0.035637 -0.019159 +v 0.035365 -0.012374 -0.019303 +v 0.046799 -0.012374 -0.019303 +v 0.035365 -0.036296 -0.027621 +v 0.035365 0.001251 -0.030211 +v 0.051187 0.001251 -0.030211 +v 0.035365 -0.037807 -0.045949 +v 0.035365 0.004153 -0.045979 +v 0.049838 0.004153 -0.047749 +v 0.043404 -0.014483 -0.017370 +v 0.055284 -0.011081 -0.017370 +v -0.061574 -0.000371 -0.021294 +v -0.061574 -0.015040 -0.015218 +v -0.032467 -0.015040 -0.015218 +v -0.032467 -0.000371 -0.021294 +v -0.061574 -0.021116 -0.000550 +v -0.032467 -0.021116 -0.000550 +v -0.061574 -0.015040 0.014119 +v -0.032467 -0.015040 0.014119 +v -0.061574 -0.000371 0.020195 +v -0.032467 -0.000371 0.020195 +v -0.061574 0.014298 0.014119 +v -0.032467 0.014298 0.014119 +v -0.061574 0.020374 -0.000550 +v -0.032467 0.020374 -0.000550 +v -0.061574 0.014298 -0.015218 +v -0.032467 0.014298 -0.015218 +v -0.061574 -0.000371 -0.015316 +v -0.061574 -0.010812 -0.010991 +v -0.061574 -0.015137 -0.000550 +v -0.061574 -0.010812 0.009892 +v -0.061574 -0.000371 0.014217 +v -0.061574 0.010070 0.009892 +v -0.061574 0.014395 -0.000550 +v -0.061574 0.010070 -0.010991 +v -0.035239 -0.000371 -0.010640 +v -0.035239 -0.007506 -0.007684 +v -0.035239 -0.010461 -0.000550 +v -0.035239 -0.007506 0.006585 +v -0.035239 -0.000371 0.009540 +v -0.035239 0.006764 0.006585 +v -0.035239 0.009719 -0.000550 +v -0.035239 0.006764 -0.007684 +v -0.032467 -0.007298 -0.007477 +v -0.032467 -0.000371 -0.010346 +v -0.032467 -0.010167 -0.000550 +v -0.032467 -0.007298 0.006377 +v -0.032467 -0.000371 0.009247 +v -0.032467 0.006556 0.006377 +v -0.032467 0.009426 -0.000550 +v -0.032467 0.006556 -0.007477 +v -0.052643 -0.046136 -0.010830 +v -0.052643 -0.048024 -0.002475 +v -0.037053 -0.048024 -0.002475 +v -0.037053 -0.046136 -0.010830 +v -0.052643 -0.044645 0.006092 +v -0.037053 -0.044645 0.006092 +v -0.052643 -0.036078 0.009641 +v -0.037053 -0.036078 0.009641 +v -0.037053 -0.039783 -0.006181 +v -0.037053 -0.036078 -0.007716 +v -0.037053 -0.036078 -0.014591 +v -0.052643 -0.036078 -0.007716 +v -0.052643 -0.039783 -0.006181 +v -0.052643 -0.036078 -0.014591 +v -0.037053 -0.041318 -0.002475 +v -0.052643 -0.041318 -0.002475 +v -0.037053 -0.039783 0.001231 +v -0.052643 -0.039783 0.001231 +v -0.037053 -0.036078 0.002765 +v -0.052643 -0.036078 0.002765 +v -0.037053 -0.032372 0.001231 +v -0.037053 -0.027510 0.006092 +v -0.052643 -0.032372 0.001231 +v -0.052643 -0.027510 0.006092 +v -0.037053 -0.030837 -0.002475 +v -0.037053 -0.023962 -0.002475 +v -0.052643 -0.030837 -0.002475 +v -0.052643 -0.023962 -0.002475 +v -0.037053 -0.032372 -0.006181 +v -0.037053 -0.027510 -0.011042 +v -0.052643 -0.032372 -0.006181 +v -0.052643 -0.027510 -0.011042 +v -0.037053 -0.030021 -0.019513 +v -0.037053 -0.044502 -0.019512 +v -0.052643 -0.044502 -0.019512 +v -0.052643 -0.030021 -0.019512 +v -0.052643 -0.003273 0.018663 +v -0.037053 -0.003273 0.018663 +v -0.037053 -0.017042 0.008892 +v -0.052643 -0.017042 0.008892 +v -0.037053 -0.019831 -0.002475 +v -0.052643 -0.019831 -0.002475 +v -0.031870 -0.011314 -0.019513 +v -0.052643 -0.011309 -0.019512 +v -0.017183 -0.039640 -0.005322 +v -0.017183 -0.035831 -0.006900 +v -0.017183 -0.024109 -0.019003 +v -0.017183 -0.044538 -0.019003 +v -0.017183 -0.041217 -0.001514 +v -0.017183 -0.047237 -0.001514 +v -0.017183 -0.039640 0.002295 +v -0.017183 -0.043896 0.006551 +v -0.017183 -0.035831 0.003872 +v -0.017183 -0.035831 0.009892 +v -0.017183 -0.032022 0.002295 +v -0.017183 -0.027766 0.006551 +v -0.017183 -0.030445 -0.001514 +v -0.017183 -0.024425 -0.001514 +v -0.017183 -0.032022 -0.005322 +v -0.021687 -0.012825 -0.019003 +v -0.025691 -0.033423 -0.019003 +v -0.026481 -0.035831 -0.006900 +v -0.026481 -0.039640 -0.005322 +v -0.026482 -0.044538 -0.019003 +v -0.026481 -0.041217 -0.001514 +v -0.026481 -0.047237 -0.001514 +v -0.026481 -0.039640 0.002295 +v -0.026481 -0.043896 0.006551 +v -0.026481 -0.035831 0.003872 +v -0.026481 -0.035831 0.009892 +v -0.026481 -0.032022 0.002295 +v -0.026481 -0.027766 0.006551 +v -0.026481 -0.030445 -0.001514 +v -0.026481 -0.024425 -0.001514 +v -0.026481 -0.032022 -0.005322 +v -0.026481 -0.012825 -0.019003 +v -0.037625 -0.037302 -0.043660 +v -0.050721 -0.037302 -0.043660 +v -0.050721 -0.022822 -0.043660 +v -0.050721 -0.011454 -0.043656 +v -0.020934 -0.037338 -0.043651 +v -0.028745 -0.037338 -0.043651 +v -0.020934 -0.016910 -0.043651 +v -0.024186 -0.006030 -0.043601 +v -0.028745 -0.004781 -0.038559 +v -0.024717 -0.004781 -0.038559 +v -0.021687 -0.002393 -0.025170 +v -0.026481 -0.002393 -0.025170 +v -0.050720 -0.006026 -0.043688 +v -0.032442 -0.006026 -0.043672 +v -0.031869 0.009803 -0.019545 +v -0.052642 0.009807 -0.019545 +v -0.028745 -0.006030 -0.043655 +v -0.031985 -0.002393 -0.025170 +v -0.034248 -0.004781 -0.038559 +v -0.031985 -0.012825 -0.019003 +v -0.034248 -0.006071 -0.043655 +v -0.034742 -0.037302 -0.052930 +v -0.047639 -0.037302 -0.055204 +v -0.047639 -0.022822 -0.055204 +v -0.047639 -0.011454 -0.055200 +v -0.018306 -0.037338 -0.050023 +v -0.025998 -0.037338 -0.051379 +v -0.018306 -0.016910 -0.050023 +v -0.019751 -0.006030 -0.049493 +v -0.025997 -0.006030 -0.051384 +v -0.047633 -0.006026 -0.055232 +v -0.029632 -0.006026 -0.052058 +v -0.032363 -0.037302 -0.063888 +v -0.047229 -0.037302 -0.072471 +v -0.047229 -0.022822 -0.072471 +v -0.047231 -0.011454 -0.072467 +v -0.014210 -0.037338 -0.054305 +v -0.022286 -0.037338 -0.058060 +v -0.013419 -0.016910 -0.052941 +v -0.014588 -0.006030 -0.053024 +v -0.022284 -0.006030 -0.058064 +v -0.047214 -0.006026 -0.072495 +v -0.026464 -0.006026 -0.060515 +v -0.011960 -0.037302 -0.077426 +v -0.019187 -0.037302 -0.097281 +v -0.019187 -0.022822 -0.097281 +v -0.019187 -0.011454 -0.097281 +v -0.005553 -0.037338 -0.060729 +v -0.008928 -0.037338 -0.068912 +v -0.002749 -0.016910 -0.053048 +v -0.003204 -0.006030 -0.053055 +v -0.007059 -0.006030 -0.063962 +v -0.019186 -0.006026 -0.097280 +v -0.009099 -0.006026 -0.069566 +v 0.009065 -0.037302 -0.077391 +v 0.009065 -0.037302 -0.097203 +v 0.009065 -0.022822 -0.097203 +v 0.009064 -0.011454 -0.097203 +v 0.009375 -0.037338 -0.060626 +v 0.009002 -0.037338 -0.068918 +v 0.009382 -0.016910 -0.052959 +v 0.008957 -0.006030 -0.053111 +v 0.009064 -0.006030 -0.063957 +v 0.009065 -0.006026 -0.097201 +v 0.009065 -0.006026 -0.069549 +v 0.021910 -0.042659 -0.072008 +v 0.021910 -0.042659 -0.087439 +v 0.021910 -0.023851 -0.087439 +v 0.021910 -0.009087 -0.087439 +v 0.022221 -0.042706 -0.058949 +v 0.021848 -0.042706 -0.065408 +v 0.022228 -0.016173 -0.052977 +v 0.021803 -0.002517 -0.053096 +v 0.021910 -0.002517 -0.061544 +v 0.021911 -0.001919 -0.087438 +v 0.021911 -0.001919 -0.065899 +v 0.045781 -0.050171 -0.070876 +v 0.049775 -0.050171 -0.085781 +v 0.049775 -0.026157 -0.085781 +v 0.049775 -0.007306 -0.085781 +v 0.042701 -0.050231 -0.058182 +v 0.044013 -0.050231 -0.064517 +v 0.041162 -0.016354 -0.052412 +v 0.040782 0.001081 -0.052636 +v 0.043073 0.001081 -0.060768 +v 0.049775 0.001845 -0.085780 +v 0.044200 0.001845 -0.064975 +v 0.046522 -0.047518 -0.050409 +v 0.046522 -0.037807 -0.050371 +v 0.049198 0.004153 -0.047692 +# 446 vertices, 0 vertices normals + +f 1 4 3 +f 3 2 1 +f 5 1 2 +f 2 6 5 +f 7 5 6 +f 6 8 7 +f 9 7 8 +f 8 10 9 +f 11 9 10 +f 10 12 11 +f 13 11 12 +f 12 14 13 +f 15 13 14 +f 14 16 15 +f 4 15 16 +f 16 3 4 +f 2 3 18 +f 18 17 2 +f 6 2 17 +f 17 19 6 +f 8 6 19 +f 19 20 8 +f 10 8 20 +f 20 21 10 +f 12 10 21 +f 21 22 12 +f 14 12 22 +f 22 23 14 +f 16 14 23 +f 23 24 16 +f 3 16 24 +f 24 18 3 +f 17 18 26 +f 26 25 17 +f 19 17 25 +f 25 27 19 +f 20 19 27 +f 27 28 20 +f 21 20 28 +f 28 29 21 +f 22 21 29 +f 29 30 22 +f 23 22 30 +f 30 31 23 +f 24 23 31 +f 31 32 24 +f 18 24 32 +f 32 26 18 +f 4 1 34 +f 34 33 4 +f 1 5 35 +f 35 34 1 +f 5 7 36 +f 36 35 5 +f 7 9 37 +f 37 36 7 +f 9 11 38 +f 38 37 9 +f 11 13 39 +f 39 38 11 +f 13 15 40 +f 40 39 13 +f 15 4 33 +f 33 40 15 +f 25 26 33 +f 33 34 25 +f 27 25 34 +f 34 35 27 +f 28 27 35 +f 35 36 28 +f 29 28 36 +f 36 37 29 +f 30 29 37 +f 37 38 30 +f 31 30 38 +f 38 39 31 +f 32 31 39 +f 39 40 32 +f 26 32 40 +f 40 33 26 +f 41 44 43 +f 43 42 41 +f 45 41 42 +f 42 46 45 +f 47 45 46 +f 46 48 47 +f 49 44 51 +f 51 50 49 +f 43 54 53 +f 53 52 43 +f 44 41 55 +f 55 51 44 +f 42 43 52 +f 52 56 42 +f 41 45 57 +f 57 55 41 +f 46 42 56 +f 56 58 46 +f 45 47 59 +f 59 57 45 +f 48 46 58 +f 58 60 48 +f 47 62 61 +f 61 59 47 +f 63 48 60 +f 60 64 63 +f 62 66 65 +f 65 61 62 +f 67 63 64 +f 64 68 67 +f 66 70 69 +f 69 65 66 +f 71 67 68 +f 68 72 71 +f 70 49 50 +f 50 69 70 +f 54 71 72 +f 72 53 54 +f 50 51 52 +f 52 53 50 +f 69 50 53 +f 53 72 69 +f 65 69 72 +f 72 68 65 +f 61 65 68 +f 68 64 61 +f 59 61 64 +f 64 60 59 +f 57 59 60 +f 60 58 57 +f 55 57 58 +f 58 56 55 +f 51 55 56 +f 56 52 51 +f 44 49 74 +f 74 73 44 +f 43 44 73 +f 73 75 43 +f 43 75 76 +f 76 54 43 +f 47 48 78 +f 78 77 47 +f 62 47 77 +f 77 79 62 +f 48 63 80 +f 80 78 48 +f 66 62 79 +f 79 81 66 +f 63 67 82 +f 82 80 63 +f 70 66 81 +f 81 83 70 +f 67 71 84 +f 84 82 67 +f 70 83 74 +f 74 49 70 +f 71 54 76 +f 76 84 71 +f 85 88 87 +f 87 86 85 +f 89 85 86 +f 86 90 89 +f 91 94 93 +f 93 92 91 +f 95 98 97 +f 97 96 95 +f 94 100 99 +f 99 93 94 +f 101 95 96 +f 96 102 101 +f 100 104 103 +f 103 99 100 +f 105 101 102 +f 102 106 105 +f 104 108 107 +f 107 103 104 +f 109 105 106 +f 106 110 109 +f 108 88 111 +f 111 107 108 +f 87 109 110 +f 110 112 87 +f 88 85 113 +f 113 111 88 +f 86 87 112 +f 112 114 86 +f 85 89 115 +f 115 113 85 +f 90 86 114 +f 114 116 90 +f 89 91 92 +f 92 115 89 +f 98 90 116 +f 116 97 98 +f 103 107 110 +f 110 106 103 +f 99 103 106 +f 106 102 99 +f 93 99 102 +f 102 96 93 +f 92 93 96 +f 96 97 92 +f 115 92 97 +f 97 116 115 +f 113 115 116 +f 116 114 113 +f 111 113 114 +f 114 112 111 +f 107 111 112 +f 112 110 107 +f 76 74 83 +f 83 84 76 +f 75 73 109 +f 109 87 75 +f 76 75 87 +f 87 88 76 +f 74 76 88 +f 88 108 74 +f 117 73 74 +f 74 118 117 +f 119 104 100 +f 100 120 119 +f 121 101 105 +f 105 122 121 +f 108 104 119 +f 119 123 108 +f 122 105 109 +f 109 124 122 +f 109 73 117 +f 117 124 109 +f 125 126 121 +f 121 122 125 +f 125 122 124 +f 124 127 125 +f 128 127 124 +f 124 117 128 +f 129 128 131 +f 131 130 129 +f 128 133 132 +f 132 131 128 +f 133 135 134 +f 134 132 133 +f 135 137 136 +f 136 134 135 +f 137 139 138 +f 138 136 137 +f 139 141 140 +f 140 138 139 +f 141 143 142 +f 142 140 141 +f 143 129 130 +f 130 142 143 +f 144 117 118 +f 118 145 144 +f 146 147 117 +f 117 144 146 +f 148 149 147 +f 147 146 148 +f 150 151 149 +f 149 148 150 +f 152 153 151 +f 151 150 152 +f 154 155 153 +f 153 152 154 +f 156 157 155 +f 155 154 156 +f 145 118 157 +f 157 156 145 +f 132 134 148 +f 148 146 132 +f 131 132 146 +f 146 144 131 +f 130 131 144 +f 144 145 130 +f 142 130 145 +f 145 156 142 +f 140 142 156 +f 156 154 140 +f 138 140 154 +f 154 152 138 +f 136 138 152 +f 152 150 136 +f 134 136 150 +f 150 148 134 +f 133 128 117 +f 117 147 133 +f 135 133 147 +f 147 149 135 +f 137 135 149 +f 149 151 137 +f 139 137 151 +f 151 153 139 +f 141 139 153 +f 153 155 141 +f 143 141 155 +f 155 157 143 +f 158 161 160 +f 160 159 158 +f 162 158 159 +f 159 163 162 +f 164 162 163 +f 163 165 164 +f 166 164 165 +f 165 167 166 +f 168 166 167 +f 167 169 168 +f 170 168 169 +f 169 171 170 +f 172 170 171 +f 171 173 172 +f 161 172 173 +f 173 160 161 +f 174 177 176 +f 176 175 174 +f 175 176 179 +f 179 178 175 +f 178 179 181 +f 181 180 178 +f 180 181 183 +f 183 182 180 +f 182 183 185 +f 185 184 182 +f 184 185 187 +f 187 186 184 +f 186 187 189 +f 189 188 186 +f 188 189 177 +f 177 174 188 +f 161 158 176 +f 176 177 161 +f 172 161 177 +f 177 189 172 +f 170 172 189 +f 189 187 170 +f 168 170 187 +f 187 185 168 +f 166 168 185 +f 185 183 166 +f 164 166 183 +f 183 181 164 +f 162 164 181 +f 181 179 162 +f 158 162 179 +f 179 176 158 +f 160 173 188 +f 188 174 160 +f 159 160 174 +f 174 175 159 +f 163 159 175 +f 175 178 163 +f 165 163 178 +f 178 180 165 +f 167 165 180 +f 180 182 167 +f 169 167 182 +f 182 184 169 +f 171 169 184 +f 184 186 171 +f 173 171 186 +f 186 188 173 +f 190 193 192 +f 192 191 190 +f 194 190 191 +f 191 195 194 +f 196 199 198 +f 198 197 196 +f 200 203 202 +f 202 201 200 +f 199 205 204 +f 204 198 199 +f 206 200 201 +f 201 207 206 +f 205 209 208 +f 208 204 205 +f 210 206 207 +f 207 211 210 +f 209 213 212 +f 212 208 209 +f 214 210 211 +f 211 215 214 +f 213 193 216 +f 216 212 213 +f 192 214 215 +f 215 217 192 +f 193 190 218 +f 218 216 193 +f 191 192 217 +f 217 219 191 +f 190 194 220 +f 220 218 190 +f 195 191 219 +f 219 221 195 +f 194 196 197 +f 197 220 194 +f 203 195 221 +f 221 202 203 +f 208 212 215 +f 215 211 208 +f 204 208 211 +f 211 207 204 +f 198 204 207 +f 207 201 198 +f 197 198 201 +f 201 202 197 +f 220 197 202 +f 202 221 220 +f 218 220 221 +f 221 219 218 +f 216 218 219 +f 219 217 216 +f 212 216 217 +f 217 215 212 +f 222 223 214 +f 214 192 222 +f 224 222 192 +f 192 193 224 +f 225 224 193 +f 193 213 225 +f 203 196 194 +f 194 195 203 +f 89 90 98 +f 98 91 89 +f 206 210 227 +f 227 226 206 +f 210 214 228 +f 228 227 210 +f 214 223 229 +f 229 228 214 +f 128 129 230 +f 230 127 128 +f 129 143 231 +f 231 230 129 +f 143 157 232 +f 232 231 143 +f 127 230 233 +f 233 125 127 +f 230 231 234 +f 234 233 230 +f 231 232 235 +f 235 234 231 +f 125 233 236 +f 236 126 125 +f 233 234 237 +f 237 236 233 +f 234 235 238 +f 238 237 234 +f 118 74 240 +f 240 239 118 +f 239 240 213 +f 213 209 239 +f 81 225 213 +f 213 83 81 +f 241 244 243 +f 243 242 241 +f 242 243 246 +f 246 245 242 +f 245 246 248 +f 248 247 245 +f 247 248 250 +f 250 249 247 +f 249 250 252 +f 252 251 249 +f 251 252 254 +f 254 253 251 +f 253 254 256 +f 256 255 253 +f 255 256 244 +f 244 241 255 +f 257 241 242 +f 242 258 257 +f 258 242 245 +f 245 259 258 +f 259 245 247 +f 247 260 259 +f 260 247 249 +f 249 261 260 +f 261 249 251 +f 251 262 261 +f 262 251 253 +f 253 263 262 +f 263 253 255 +f 255 264 263 +f 264 255 241 +f 241 257 264 +f 265 257 258 +f 258 266 265 +f 266 258 259 +f 259 267 266 +f 267 259 260 +f 260 268 267 +f 268 260 261 +f 261 269 268 +f 269 261 262 +f 262 270 269 +f 270 262 263 +f 263 271 270 +f 271 263 264 +f 264 272 271 +f 272 264 257 +f 257 265 272 +f 273 243 244 +f 244 274 273 +f 275 246 243 +f 243 273 275 +f 276 248 246 +f 246 275 276 +f 277 250 248 +f 248 276 277 +f 278 252 250 +f 250 277 278 +f 279 254 252 +f 252 278 279 +f 280 256 254 +f 254 279 280 +f 274 244 256 +f 256 280 274 +f 274 265 266 +f 266 273 274 +f 273 266 267 +f 267 275 273 +f 275 267 268 +f 268 276 275 +f 276 268 269 +f 269 277 276 +f 277 269 270 +f 270 278 277 +f 278 270 271 +f 271 279 278 +f 279 271 272 +f 272 280 279 +f 280 272 265 +f 265 274 280 +f 281 284 283 +f 283 282 281 +f 282 283 286 +f 286 285 282 +f 285 286 288 +f 288 287 285 +f 289 284 291 +f 291 290 289 +f 292 294 281 +f 281 293 292 +f 295 283 284 +f 284 289 295 +f 293 281 282 +f 282 296 293 +f 297 286 283 +f 283 295 297 +f 296 282 285 +f 285 298 296 +f 299 288 286 +f 286 297 299 +f 298 285 287 +f 287 300 298 +f 301 302 288 +f 288 299 301 +f 300 287 304 +f 304 303 300 +f 305 306 302 +f 302 301 305 +f 303 304 308 +f 308 307 303 +f 309 310 306 +f 306 305 309 +f 307 308 312 +f 312 311 307 +f 290 291 310 +f 310 309 290 +f 311 312 294 +f 294 292 311 +f 293 289 290 +f 290 292 293 +f 292 290 309 +f 309 311 292 +f 311 309 305 +f 305 307 311 +f 307 305 301 +f 301 303 307 +f 303 301 299 +f 299 300 303 +f 300 299 297 +f 297 298 300 +f 298 297 295 +f 295 296 298 +f 296 295 289 +f 289 293 296 +f 313 291 284 +f 284 314 313 +f 314 284 281 +f 281 315 314 +f 316 315 281 +f 281 294 316 +f 317 287 288 +f 288 318 317 +f 318 288 302 +f 302 319 318 +f 320 304 287 +f 287 317 320 +f 319 302 306 +f 306 321 319 +f 322 308 304 +f 304 320 322 +f 321 306 310 +f 310 323 321 +f 324 312 308 +f 308 322 324 +f 313 323 310 +f 310 291 313 +f 316 294 312 +f 312 324 316 +f 325 328 327 +f 327 326 325 +f 329 330 328 +f 328 325 329 +f 331 332 330 +f 330 329 331 +f 333 334 332 +f 332 331 333 +f 335 336 334 +f 334 333 335 +f 337 338 336 +f 336 335 337 +f 339 340 338 +f 338 337 339 +f 326 327 340 +f 340 339 326 +f 341 344 343 +f 343 342 341 +f 344 346 345 +f 345 343 344 +f 346 348 347 +f 347 345 346 +f 348 350 349 +f 349 347 348 +f 350 352 351 +f 351 349 350 +f 352 354 353 +f 353 351 352 +f 354 356 355 +f 355 353 354 +f 356 341 342 +f 342 355 356 +f 347 331 329 +f 329 345 347 +f 345 329 325 +f 325 343 345 +f 343 325 326 +f 326 342 343 +f 342 326 339 +f 339 355 342 +f 355 339 337 +f 337 353 355 +f 353 337 335 +f 335 351 353 +f 351 335 333 +f 333 349 351 +f 349 333 331 +f 331 347 349 +f 344 328 330 +f 330 346 344 +f 346 330 332 +f 332 348 346 +f 348 332 334 +f 334 350 348 +f 350 334 336 +f 336 352 350 +f 352 336 338 +f 338 354 352 +f 354 338 340 +f 340 356 354 +f 321 323 324 +f 324 322 321 +f 344 341 313 +f 313 314 344 +f 341 356 323 +f 323 313 341 +f 357 314 315 +f 315 358 357 +f 358 315 316 +f 316 359 358 +f 359 316 324 +f 324 360 359 +f 361 328 344 +f 344 362 361 +f 363 327 328 +f 328 361 363 +f 364 340 327 +f 327 363 364 +f 365 368 367 +f 367 366 365 +f 369 372 371 +f 371 370 369 +f 362 344 314 +f 314 357 362 +f 370 323 356 +f 356 373 370 +f 371 323 370 +f 369 360 324 +f 324 372 369 +f 368 356 340 +f 340 367 368 +f 367 340 364 +f 364 366 367 +f 366 364 373 +f 373 365 366 +f 374 368 365 +f 365 375 374 +f 376 356 368 +f 368 374 376 +f 375 365 373 +f 373 377 375 +f 378 357 358 +f 358 379 378 +f 379 358 359 +f 359 380 379 +f 380 359 360 +f 360 381 380 +f 382 361 362 +f 362 383 382 +f 384 363 361 +f 361 382 384 +f 385 364 363 +f 363 384 385 +f 386 373 364 +f 364 385 386 +f 383 362 357 +f 357 378 383 +f 387 369 370 +f 370 388 387 +f 388 370 373 +f 373 386 388 +f 381 360 369 +f 369 387 381 +f 389 378 379 +f 379 390 389 +f 390 379 380 +f 380 391 390 +f 391 380 381 +f 381 392 391 +f 393 382 383 +f 383 394 393 +f 395 384 382 +f 382 393 395 +f 396 385 384 +f 384 395 396 +f 397 386 385 +f 385 396 397 +f 394 383 378 +f 378 389 394 +f 398 387 388 +f 388 399 398 +f 392 381 387 +f 387 398 392 +f 400 389 390 +f 390 401 400 +f 401 390 391 +f 391 402 401 +f 402 391 392 +f 392 403 402 +f 404 393 394 +f 394 405 404 +f 406 395 393 +f 393 404 406 +f 407 396 395 +f 395 406 407 +f 408 397 396 +f 396 407 408 +f 405 394 389 +f 389 400 405 +f 409 398 399 +f 399 410 409 +f 403 392 398 +f 398 409 403 +f 411 400 401 +f 401 412 411 +f 412 401 402 +f 402 413 412 +f 413 402 403 +f 403 414 413 +f 415 404 405 +f 405 416 415 +f 417 406 404 +f 404 415 417 +f 418 407 406 +f 406 417 418 +f 419 408 407 +f 407 418 419 +f 416 405 400 +f 400 411 416 +f 420 409 410 +f 410 421 420 +f 414 403 409 +f 409 420 414 +f 422 411 412 +f 412 423 422 +f 423 412 413 +f 413 424 423 +f 424 413 414 +f 414 425 424 +f 426 415 416 +f 416 427 426 +f 428 417 415 +f 415 426 428 +f 429 418 417 +f 417 428 429 +f 430 419 418 +f 418 429 430 +f 427 416 411 +f 411 422 427 +f 431 420 421 +f 421 432 431 +f 432 421 419 +f 419 430 432 +f 425 414 420 +f 420 431 425 +f 433 422 423 +f 423 434 433 +f 434 423 424 +f 424 435 434 +f 435 424 425 +f 425 436 435 +f 437 426 427 +f 427 438 437 +f 439 428 426 +f 426 437 439 +f 440 429 428 +f 428 439 440 +f 441 430 429 +f 429 440 441 +f 438 427 422 +f 422 433 438 +f 442 431 432 +f 432 443 442 +f 443 432 430 +f 430 441 443 +f 436 425 431 +f 431 442 436 +f 419 421 410 +f 410 408 419 +f 408 410 399 +f 399 397 408 +f 397 399 388 +f 388 386 397 +f 444 126 236 +f 236 445 444 +f 445 236 237 +f 237 446 445 +# 847 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_lglut_chull.obj b/examples/Atlas/urdf/mesh/r_lglut_chull.obj new file mode 100644 index 0000000..e65fa9a --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_lglut_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_lglut_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.047223 -0.006026 -0.072487 +v 0.080771 -0.046241 -0.033083 +v 0.047751 0.009608 -0.088147 +v -0.047229 -0.037302 -0.072471 +v 0.082758 -0.012784 0.016603 +v 0.080886 0.003439 -0.041910 +v -0.061574 0.020374 -0.000550 +v 0.082320 0.020374 -0.000550 +v 0.082320 0.014298 0.014119 +v -0.061574 0.014298 0.014119 +v -0.061574 -0.000371 0.020195 +v 0.082320 -0.000371 0.020195 +v 0.071703 -0.048024 -0.002475 +v 0.071703 -0.044645 0.006092 +v -0.052643 -0.048024 -0.002475 +v 0.009065 -0.037302 -0.097203 +v 0.050046 -0.055867 -0.087444 +v -0.019187 -0.006026 -0.097281 +v -0.019187 -0.037302 -0.097281 +v 0.064714 -0.055867 -0.081368 +v 0.063420 -0.057638 -0.056244 +v 0.035377 -0.055867 -0.081368 +v 0.064714 0.009702 -0.081368 +v 0.080317 -0.045838 -0.045336 +v -0.061582 0.011621 -0.020886 +v -0.062002 -0.021164 -0.001191 +v -0.052572 -0.043957 0.007482 +# 27 vertices, 0 vertices normals + +f 27 15 26 +f 22 17 19 +f 18 25 1 +f 25 18 7 +f 5 2 14 +f 13 21 15 +f 14 2 13 +f 2 21 13 +f 19 17 16 +f 18 1 19 +f 15 22 4 +f 4 26 15 +f 4 22 19 +f 19 1 4 +f 4 1 25 +f 3 7 18 +f 27 26 11 +f 14 27 5 +f 21 22 15 +f 23 8 3 +f 24 5 6 +f 24 2 5 +f 24 21 2 +f 24 20 21 +f 3 18 16 +f 26 4 25 +f 27 12 5 +f 23 6 8 +f 6 23 24 +f 3 8 7 +f 7 9 10 +f 9 7 8 +f 11 10 9 +f 9 12 11 +f 27 14 13 +f 13 15 27 +f 16 17 3 +f 19 16 18 +f 9 5 12 +f 5 9 8 +f 8 6 5 +f 20 17 21 +f 17 22 21 +f 23 17 20 +f 17 23 3 +f 24 23 20 +f 26 10 11 +f 26 7 10 +f 7 26 25 +f 11 12 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_lleg.obj b/examples/Atlas/urdf/mesh/r_lleg.obj new file mode 100644 index 0000000..3d31de4 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_lleg.obj @@ -0,0 +1,2319 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_lleg.obj +# +# Vertices: 809 +# Faces: 1494 +# +#### +v -0.014057 -0.011209 -0.114512 +v -0.040907 -0.011209 -0.115410 +v -0.041007 -0.003223 -0.123695 +v -0.018749 -0.003223 -0.123695 +v -0.030527 -0.003223 -0.147550 +v -0.030527 -0.011209 -0.147550 +v -0.029528 -0.011209 -0.144556 +v -0.029528 -0.003223 -0.144556 +v -0.041207 -0.003223 -0.147550 +v -0.041107 -0.011209 -0.135773 +v -0.027632 -0.040354 -0.140863 +v -0.036316 -0.040354 -0.140863 +v -0.036016 -0.040354 -0.130582 +v -0.022342 -0.040354 -0.130582 +v -0.029528 -0.031571 -0.144556 +v -0.041107 -0.031571 -0.140863 +v -0.027632 -0.031571 -0.140863 +v -0.030527 -0.031571 -0.147550 +v -0.041207 -0.031571 -0.147550 +v -0.041007 -0.031571 -0.130582 +v -0.041007 -0.035962 -0.130582 +v -0.041107 -0.035962 -0.140863 +v -0.022342 -0.031571 -0.130582 +v -0.041007 -0.031571 -0.123695 +v -0.018749 -0.031571 -0.123695 +v -0.041307 -0.024284 -0.153739 +v -0.041107 -0.024284 -0.135773 +v -0.030527 -0.024284 -0.147550 +v -0.032623 -0.024284 -0.154138 +v -0.032623 -0.011209 -0.154138 +v -0.041307 -0.011209 -0.153739 +v -0.040907 -0.024284 -0.115410 +v -0.014057 -0.024284 -0.114512 +v -0.029528 -0.024284 -0.144556 +v -0.020135 -0.050041 0.002602 +v 0.000826 -0.050041 0.022066 +v 0.030271 -0.050041 0.021267 +v -0.019836 -0.050041 -0.037024 +v -0.014346 -0.050041 0.015478 +v -0.014645 -0.050041 -0.078148 +v -0.007359 -0.050041 -0.061578 +v 0.011406 -0.050041 -0.038920 +v -0.012150 -0.050041 -0.079046 +v 0.009909 -0.028780 -0.418514 +v 0.005717 -0.024189 -0.430092 +v -0.008157 -0.026684 -0.425801 +v -0.016043 -0.039560 -0.325288 +v 0.021188 -0.040359 -0.334471 +v 0.021188 -0.040359 -0.345151 +v -0.015643 -0.039560 -0.368707 +v -0.015444 -0.035967 -0.392862 +v -0.023229 -0.035967 -0.390467 +v -0.031913 -0.039560 -0.360821 +v -0.040797 -0.033072 -0.317103 +v -0.041894 -0.033072 -0.264201 +v -0.016342 -0.039560 -0.269192 +v -0.017739 -0.050041 -0.105297 +v 0.032966 -0.050041 -0.122565 +v 0.026877 -0.050041 -0.139234 +v -0.010952 -0.050041 -0.139633 +v 0.021188 -0.050041 -0.173370 +v 0.021188 -0.050041 -0.254819 +v -0.009754 -0.050041 -0.255817 +v -0.010553 -0.050041 -0.184150 +v 0.021188 -0.040359 -0.270989 +v 0.004918 -0.035967 -0.395058 +v 0.010708 -0.039560 -0.375195 +v -0.041695 -0.041756 -0.166982 +v -0.038900 -0.050041 -0.139933 +v -0.041695 -0.032873 -0.192834 +v 0.047539 -0.038762 -0.254619 +v 0.039454 -0.039860 -0.254719 +v 0.039953 -0.039860 -0.239747 +v 0.047539 -0.038762 -0.240745 +v 0.039454 -0.027283 -0.255617 +v 0.047539 -0.000134 -0.254619 +v 0.047539 -0.000134 -0.240745 +v 0.039480 -0.014107 -0.239747 +v 0.039480 -0.000134 -0.239747 +v 0.025779 -0.040359 -0.333572 +v 0.025779 -0.040359 -0.345151 +v 0.025680 -0.040359 -0.271288 +v 0.020789 -0.039860 -0.239846 +v 0.025181 -0.039860 -0.254719 +v 0.021188 -0.039959 -0.254819 +v 0.029373 -0.032773 -0.331276 +v 0.029173 -0.032673 -0.271588 +v 0.039454 -0.024388 -0.264501 +v 0.037857 -0.024788 -0.330777 +v 0.029373 -0.032873 -0.342456 +v 0.039654 -0.020096 -0.338064 +v 0.058918 -0.024388 -0.264800 +v 0.059018 -0.024788 -0.330777 +v 0.031369 -0.031475 -0.351838 +v 0.021188 -0.033072 -0.356230 +v 0.039654 -0.020096 -0.374596 +v 0.031369 -0.031276 -0.374995 +v 0.021188 -0.032573 -0.375095 +v 0.029173 -0.032673 -0.258911 +v 0.058918 -0.019897 -0.260009 +v 0.041051 -0.019897 -0.259710 +v 0.058918 -0.012710 -0.260009 +v 0.041151 -0.012710 -0.259710 +v 0.058918 -0.008618 -0.265000 +v 0.041151 -0.008618 -0.264601 +v 0.058918 -0.008119 -0.275480 +v 0.041151 -0.008119 -0.275181 +v 0.058918 -0.000134 -0.279672 +v 0.037258 -0.000134 -0.279373 +v 0.035561 -0.000134 -0.255617 +v 0.036360 -0.000134 -0.264800 +v 0.059018 -0.020096 -0.337465 +v 0.039654 -0.013109 -0.338064 +v 0.059018 -0.013109 -0.337465 +v 0.039654 -0.008119 -0.330977 +v 0.059018 -0.008119 -0.330378 +v 0.039654 -0.013109 -0.374596 +v 0.039654 -0.008119 -0.321894 +v 0.059018 -0.008119 -0.321295 +v 0.035761 -0.000134 -0.317602 +v 0.059018 -0.000134 -0.317003 +v 0.039654 -0.000134 -0.330977 +v 0.031169 -0.013109 -0.374596 +v 0.021188 -0.013109 -0.374596 +v 0.031169 -0.000134 -0.374596 +v 0.021188 -0.000134 -0.374596 +v 0.021188 -0.039560 -0.356230 +v 0.010708 -0.030577 -0.375195 +v -0.008157 -0.017801 -0.425801 +v 0.005717 -0.017701 -0.430092 +v 0.009909 -0.018100 -0.418514 +v -0.023229 -0.017900 -0.390467 +v 0.004918 -0.020496 -0.393361 +v -0.029018 -0.012012 -0.374396 +v -0.031913 -0.017401 -0.360821 +v -0.031913 -0.000134 -0.360821 +v -0.040797 -0.000134 -0.317103 +v 0.030271 -0.044651 0.021267 +v 0.000826 -0.044651 0.022066 +v -0.011351 -0.050041 -0.050000 +v -0.019836 -0.044651 -0.037024 +v -0.020135 -0.044651 0.002602 +v -0.014346 -0.044651 0.015478 +v 0.045343 -0.050041 0.016177 +v -0.027122 -0.050041 -0.102003 +v 0.030471 -0.031675 -0.139334 +v 0.039480 -0.023590 -0.139434 +v 0.039480 -0.023590 -0.147718 +v 0.039480 -0.023590 -0.216790 +v 0.030471 -0.031675 -0.239846 +v 0.039480 -0.023590 -0.239747 +v 0.020789 -0.033072 -0.239846 +v 0.021188 -0.033072 -0.173370 +v 0.026877 -0.033072 -0.139234 +v 0.039480 -0.014507 -0.147718 +v 0.039480 -0.016803 -0.143625 +v 0.046740 -0.016703 -0.143625 +v 0.046740 -0.014207 -0.147518 +v 0.039480 -0.014507 -0.139434 +v 0.046740 -0.014207 -0.139633 +v 0.039480 -0.014507 -0.216889 +v 0.046740 -0.000134 -0.147518 +v 0.039480 -0.000134 -0.147718 +v 0.039480 -0.000134 -0.224775 +v 0.031668 -0.021394 -0.137836 +v 0.031668 -0.021394 -0.122066 +v 0.039654 -0.044950 0.018073 +v 0.048537 -0.026684 0.013881 +v 0.039654 -0.020695 0.018073 +v 0.016297 -0.026684 -0.038920 +v 0.057820 -0.020096 0.007892 +v 0.071195 -0.020096 -0.009974 +v -0.010453 -0.036566 -0.085833 +v -0.003965 -0.026684 -0.072159 +v 0.048038 -0.032673 -0.098509 +v 0.062611 -0.019996 -0.072059 +v 0.075986 -0.020096 -0.031335 +v 0.046740 -0.000134 -0.139633 +v 0.031668 -0.000134 -0.122165 +v 0.048038 -0.000134 -0.098509 +v 0.062611 -0.000134 -0.072059 +v 0.075986 -0.000134 -0.031335 +v 0.073291 -0.000134 -0.018958 +v 0.072393 -0.010714 -0.015265 +v 0.071195 -0.014906 -0.009974 +v 0.057820 -0.014906 0.007892 +v 0.039654 -0.015405 0.018073 +v 0.030171 -0.015405 0.021667 +v 0.030171 -0.020695 0.021667 +v 0.001225 -0.015405 0.021667 +v 0.001225 -0.020695 0.021667 +v -0.014745 -0.015405 0.015678 +v -0.014745 -0.020695 0.015678 +v -0.019736 -0.015405 0.002702 +v -0.019736 -0.020695 0.002702 +v -0.019836 -0.015106 -0.037024 +v -0.019836 -0.021094 -0.037024 +v -0.041695 -0.000134 -0.192834 +v -0.041695 -0.000134 -0.166982 +v -0.038900 -0.000134 -0.139933 +v -0.014645 -0.000134 -0.078148 +v -0.012848 -0.000134 -0.074055 +v -0.007359 -0.015106 -0.061578 +v -0.011351 -0.015106 -0.050000 +v -0.027122 -0.000134 -0.102003 +v -0.041894 -0.000134 -0.264201 +v -0.001769 -0.012111 -0.374995 +v -0.001769 -0.000134 -0.374695 +v 0.039654 -0.000134 -0.374596 +v -0.029917 -0.000134 -0.371502 +v 0.040153 -0.000134 -0.139533 +v 0.031668 -0.000134 -0.138036 +v 0.030271 0.049773 0.021267 +v 0.000826 0.049773 0.022066 +v -0.020135 0.049773 0.002602 +v -0.019836 0.049773 -0.037024 +v -0.014346 0.049773 0.015478 +v 0.011406 0.049773 -0.038920 +v -0.007359 0.049773 -0.061578 +v -0.014645 0.049773 -0.078148 +v -0.012150 0.049773 -0.079046 +v 0.005717 0.023922 -0.430092 +v 0.009909 0.028513 -0.418514 +v -0.008157 0.026517 -0.425801 +v 0.021188 0.040092 -0.345151 +v 0.021188 0.040092 -0.334471 +v -0.016043 0.039293 -0.325288 +v -0.015643 0.039293 -0.368707 +v -0.015444 0.035800 -0.392862 +v -0.023229 0.035800 -0.390467 +v -0.031913 0.039293 -0.360821 +v -0.041894 0.032805 -0.264201 +v -0.040797 0.032805 -0.317103 +v -0.016342 0.039293 -0.269192 +v 0.026877 0.049773 -0.139234 +v 0.032966 0.049773 -0.122565 +v -0.017739 0.049773 -0.105297 +v -0.010952 0.049773 -0.139633 +v -0.009754 0.049773 -0.255817 +v 0.021188 0.049773 -0.254819 +v 0.021188 0.049773 -0.173370 +v -0.010553 0.049773 -0.184150 +v 0.021188 0.040092 -0.270989 +v 0.004918 0.035800 -0.395058 +v 0.010707 0.039293 -0.375195 +v -0.038900 0.049773 -0.139933 +v -0.041695 0.041489 -0.166982 +v -0.041695 0.032606 -0.192834 +v 0.039953 0.039692 -0.239747 +v 0.039454 0.039692 -0.254719 +v 0.047539 0.038495 -0.254619 +v 0.047539 0.038495 -0.240745 +v 0.039454 0.027116 -0.255617 +v 0.039480 0.013840 -0.239747 +v 0.025779 0.040092 -0.333572 +v 0.025779 0.040092 -0.345151 +v 0.025680 0.040092 -0.271288 +v 0.025181 0.039692 -0.254719 +v 0.020789 0.039692 -0.239846 +v 0.021188 0.039692 -0.254819 +v 0.039454 0.024121 -0.264501 +v 0.029173 0.032406 -0.271588 +v 0.029373 0.032506 -0.331276 +v 0.037857 0.024520 -0.330777 +v 0.029373 0.032606 -0.342456 +v 0.039654 0.019829 -0.338064 +v 0.058918 0.024121 -0.264800 +v 0.059018 0.024521 -0.330777 +v 0.021188 0.032805 -0.356230 +v 0.031369 0.031308 -0.351838 +v 0.039654 0.019829 -0.374596 +v 0.021188 0.032406 -0.375095 +v 0.031369 0.031009 -0.374995 +v 0.029173 0.032406 -0.258911 +v 0.058918 0.019630 -0.260009 +v 0.041051 0.019630 -0.259710 +v 0.058918 0.012543 -0.260009 +v 0.041151 0.012543 -0.259710 +v 0.058918 0.008351 -0.265000 +v 0.041151 0.008351 -0.264601 +v 0.058918 0.007852 -0.275480 +v 0.041151 0.007852 -0.275181 +v 0.059018 0.019830 -0.337465 +v 0.039654 0.012842 -0.338064 +v 0.059018 0.012842 -0.337465 +v 0.039654 0.007852 -0.330977 +v 0.059018 0.007852 -0.330378 +v 0.039653 0.012842 -0.374596 +v 0.039654 0.007852 -0.321894 +v 0.059018 0.007852 -0.321295 +v 0.031169 0.012842 -0.374596 +v 0.021188 0.012842 -0.374596 +v 0.021188 0.039293 -0.356230 +v 0.010708 0.030310 -0.375195 +v -0.008157 0.017534 -0.425801 +v 0.005717 0.017434 -0.430092 +v 0.009909 0.017833 -0.418514 +v -0.023229 0.017633 -0.390467 +v 0.004918 0.020228 -0.393361 +v -0.029018 0.011744 -0.374396 +v -0.031913 0.017134 -0.360821 +v 0.030271 0.044384 0.021267 +v 0.000826 0.044384 0.022066 +v -0.019836 0.044384 -0.037024 +v -0.011351 0.049773 -0.050000 +v -0.020135 0.044384 0.002602 +v -0.014346 0.044384 0.015478 +v 0.045343 0.049773 0.016177 +v -0.027122 0.049773 -0.102003 +v 0.039480 0.023323 -0.139434 +v 0.030471 0.031408 -0.139334 +v 0.039480 0.023323 -0.147718 +v 0.030471 0.031408 -0.239846 +v 0.039480 0.023323 -0.216790 +v 0.039480 0.023323 -0.239747 +v 0.020789 0.032805 -0.239846 +v 0.021188 0.032805 -0.173370 +v 0.026877 0.032805 -0.139234 +v 0.046740 0.016436 -0.143625 +v 0.039480 0.016536 -0.143625 +v 0.039480 0.014240 -0.147718 +v 0.046740 0.013940 -0.147518 +v 0.046740 0.013940 -0.139633 +v 0.039480 0.014240 -0.139434 +v 0.039480 0.014240 -0.216889 +v 0.031668 0.021127 -0.137836 +v 0.031668 0.021127 -0.122066 +v 0.039654 0.044683 0.018073 +v 0.048537 0.026417 0.013881 +v 0.039654 0.020428 0.018073 +v 0.016297 0.026417 -0.038920 +v 0.057820 0.019829 0.007892 +v 0.071195 0.019829 -0.009974 +v 0.048038 0.032406 -0.098509 +v -0.003965 0.026417 -0.072159 +v -0.010453 0.036299 -0.085833 +v 0.062611 0.019730 -0.072059 +v 0.075986 0.019829 -0.031335 +v 0.072393 0.010447 -0.015265 +v 0.071195 0.014639 -0.009974 +v 0.057820 0.014739 0.007892 +v 0.039654 0.015138 0.018073 +v 0.030171 0.015138 0.021667 +v 0.030171 0.020428 0.021667 +v 0.001225 0.015138 0.021667 +v 0.001225 0.020428 0.021667 +v -0.014745 0.015138 0.015678 +v -0.014745 0.020428 0.015678 +v -0.019736 0.015138 0.002702 +v -0.019736 0.020428 0.002702 +v -0.019836 0.014838 -0.037024 +v -0.019836 0.020828 -0.037024 +v -0.007359 0.014838 -0.061578 +v -0.011351 0.014838 -0.050000 +v -0.001769 0.011844 -0.374995 +v -0.041007 0.003162 -0.123695 +v -0.040907 0.011147 -0.115410 +v -0.014057 0.011147 -0.114512 +v -0.018749 0.003162 -0.123695 +v -0.029528 0.011147 -0.144556 +v -0.030527 0.011147 -0.147550 +v -0.030527 0.003162 -0.147550 +v -0.029528 0.003162 -0.144556 +v -0.041207 0.003162 -0.147550 +v -0.041107 0.011147 -0.135773 +v -0.036016 0.040292 -0.130582 +v -0.036316 0.040292 -0.140863 +v -0.027632 0.040292 -0.140863 +v -0.022342 0.040292 -0.130582 +v -0.041107 0.031509 -0.140863 +v -0.029528 0.031509 -0.144556 +v -0.027632 0.031509 -0.140863 +v -0.041207 0.031509 -0.147550 +v -0.030527 0.031509 -0.147550 +v -0.041107 0.035901 -0.140863 +v -0.041007 0.035901 -0.130582 +v -0.041007 0.031509 -0.130582 +v -0.022342 0.031509 -0.130582 +v -0.018749 0.031509 -0.123695 +v -0.041007 0.031509 -0.123695 +v -0.041107 0.024222 -0.135773 +v -0.041307 0.024222 -0.153739 +v -0.032623 0.024222 -0.154138 +v -0.030527 0.024222 -0.147550 +v -0.032623 0.011147 -0.154138 +v -0.041307 0.011147 -0.153739 +v -0.040907 0.024222 -0.115410 +v -0.014057 0.024222 -0.114512 +v -0.029528 0.024222 -0.144556 +v 0.094851 -0.000134 -0.040118 +v 0.094751 -0.000134 -0.109988 +v 0.091757 -0.005424 -0.109789 +v 0.091856 -0.005424 -0.045409 +v 0.085668 -0.005424 -0.109489 +v 0.085668 -0.005424 -0.045409 +v 0.082574 -0.000134 -0.109290 +v 0.082674 -0.000134 -0.040118 +v 0.085668 0.005157 -0.109489 +v 0.085668 0.005157 -0.045409 +v 0.091757 0.005157 -0.109789 +v 0.091857 0.005157 -0.045409 +v 0.067302 -0.005424 -0.343454 +v 0.070097 -0.000133 -0.349143 +v 0.061214 -0.005424 -0.342855 +v 0.057920 -0.000133 -0.347846 +v 0.061213 0.005157 -0.342855 +v 0.067302 0.005157 -0.343454 +v 0.012005 -0.042455 -0.365912 +v 0.006416 -0.042455 -0.364615 +v 0.006915 -0.044850 -0.363816 +v 0.011805 -0.044850 -0.364914 +v 0.002623 -0.042455 -0.359324 +v 0.003621 -0.044850 -0.359125 +v 0.004419 -0.042455 -0.353036 +v 0.005118 -0.044850 -0.353635 +v 0.009210 -0.042455 -0.349942 +v 0.009310 -0.044850 -0.350840 +v 0.039354 -0.042455 -0.361021 +v 0.039155 -0.044850 -0.360023 +v 0.049635 -0.042455 -0.357029 +v 0.049036 -0.044850 -0.356330 +v 0.047539 -0.042455 -0.345450 +v 0.052130 -0.042455 -0.350640 +v 0.051132 -0.044850 -0.350840 +v 0.047239 -0.044850 -0.346348 +v 0.036559 -0.042455 -0.345250 +v 0.036659 -0.044850 -0.346249 +v 0.006914 0.044583 -0.363816 +v 0.006415 0.042288 -0.364615 +v 0.012005 0.042288 -0.365912 +v 0.011805 0.044583 -0.364914 +v 0.003621 0.044583 -0.359125 +v 0.002623 0.042288 -0.359324 +v 0.005118 0.044583 -0.353635 +v 0.004419 0.042288 -0.353036 +v 0.009310 0.044583 -0.350840 +v 0.009210 0.042288 -0.349942 +v 0.039354 0.042288 -0.361021 +v 0.039155 0.044583 -0.360023 +v 0.049635 0.042288 -0.357029 +v 0.049036 0.044583 -0.356330 +v 0.051132 0.044583 -0.350840 +v 0.052131 0.042288 -0.350640 +v 0.047539 0.042288 -0.345450 +v 0.047239 0.044583 -0.346348 +v 0.036659 0.044583 -0.346249 +v 0.036559 0.042288 -0.345250 +v 0.023284 0.050772 -0.224176 +v 0.020888 0.050772 -0.224176 +v 0.020888 0.048875 -0.229067 +v 0.023284 0.048875 -0.229067 +v 0.020889 0.043286 -0.231562 +v 0.023284 0.043286 -0.231562 +v 0.020889 0.037696 -0.229067 +v 0.023284 0.037696 -0.229067 +v 0.020889 0.035800 -0.224176 +v 0.023284 0.035800 -0.224176 +v 0.023384 0.035800 -0.173271 +v 0.020988 0.035800 -0.173271 +v 0.020988 0.037696 -0.168479 +v 0.023384 0.037696 -0.168479 +v 0.020988 0.043286 -0.165884 +v 0.023384 0.043286 -0.165884 +v 0.020988 0.048875 -0.168479 +v 0.023384 0.048875 -0.168479 +v 0.020988 0.050772 -0.173271 +v 0.023384 0.050772 -0.173271 +v 0.020889 -0.049142 -0.229067 +v 0.020889 -0.051039 -0.224176 +v 0.023284 -0.051039 -0.224176 +v 0.023284 -0.049142 -0.229067 +v 0.020889 -0.043553 -0.231562 +v 0.023284 -0.043553 -0.231562 +v 0.020889 -0.037963 -0.229067 +v 0.023284 -0.037963 -0.229067 +v 0.020889 -0.036067 -0.224176 +v 0.023284 -0.036067 -0.224176 +v 0.020988 -0.037963 -0.168479 +v 0.020988 -0.036067 -0.173271 +v 0.023384 -0.036067 -0.173271 +v 0.023384 -0.037963 -0.168479 +v 0.020988 -0.043553 -0.165884 +v 0.023384 -0.043553 -0.165884 +v 0.020988 -0.049142 -0.168479 +v 0.023384 -0.049142 -0.168479 +v 0.020988 -0.051039 -0.173271 +v 0.023384 -0.051039 -0.173271 +v 0.042947 -0.052037 -0.015464 +v 0.049336 -0.052037 -0.004485 +v 0.049336 -0.050440 -0.004485 +v 0.042947 -0.050440 -0.015464 +v 0.027277 -0.052037 0.011086 +v 0.027277 -0.050440 0.011086 +v 0.008911 -0.052037 0.018672 +v 0.008911 -0.050440 0.018672 +v -0.018139 -0.052037 0.002502 +v -0.016242 -0.052037 -0.009375 +v -0.016242 -0.050440 -0.009375 +v -0.018139 -0.050440 0.002502 +v -0.013547 -0.052037 0.013582 +v -0.013547 -0.050440 0.013582 +v -0.003067 -0.052037 0.019371 +v -0.003067 -0.050440 0.019371 +v -0.005762 -0.052037 -0.028540 +v -0.005762 -0.050440 -0.028540 +v 0.018493 -0.052037 -0.057586 +v 0.018493 -0.050440 -0.057586 +v 0.025280 -0.052037 -0.045907 +v 0.025280 -0.050440 -0.045907 +v 0.034563 -0.052037 -0.016961 +v 0.034563 -0.050440 -0.016961 +v 0.025380 -0.052037 -0.025645 +v 0.025380 -0.050440 -0.025645 +v 0.022486 -0.052037 -0.037823 +v 0.022486 -0.050440 -0.037823 +v -0.011252 -0.050041 -0.003087 +v -0.002168 -0.050041 -0.012170 +v -0.002168 -0.052037 -0.012170 +v -0.011252 -0.052037 -0.003087 +v -0.007858 -0.050041 0.009390 +v -0.007858 -0.052037 0.009390 +v 0.004619 -0.050041 0.012584 +v 0.004619 -0.052037 0.012584 +v 0.013702 -0.050041 0.003501 +v 0.013702 -0.052037 0.003501 +v 0.010308 -0.050041 -0.008876 +v 0.010308 -0.052037 -0.008876 +v 0.049336 0.050173 -0.004485 +v 0.049336 0.051770 -0.004485 +v 0.042947 0.051770 -0.015464 +v 0.042947 0.050173 -0.015464 +v 0.027277 0.050173 0.011086 +v 0.027277 0.051770 0.011086 +v 0.008911 0.050173 0.018672 +v 0.008911 0.051770 0.018672 +v -0.016242 0.050173 -0.009375 +v -0.016242 0.051770 -0.009375 +v -0.018139 0.051770 0.002502 +v -0.018139 0.050173 0.002502 +v -0.013547 0.051770 0.013582 +v -0.013547 0.050173 0.013582 +v -0.003067 0.051770 0.019371 +v -0.003067 0.050173 0.019371 +v -0.005762 0.050173 -0.028540 +v -0.005762 0.051770 -0.028540 +v 0.018493 0.050173 -0.057586 +v 0.018493 0.051770 -0.057586 +v 0.025280 0.050173 -0.045907 +v 0.025280 0.051770 -0.045907 +v 0.034563 0.051770 -0.016961 +v 0.034563 0.050173 -0.016961 +v 0.025380 0.051770 -0.025645 +v 0.025380 0.050173 -0.025645 +v 0.022486 0.051770 -0.037823 +v 0.022486 0.050173 -0.037823 +v -0.002168 0.051770 -0.012170 +v -0.002168 0.049774 -0.012170 +v -0.011252 0.049774 -0.003087 +v -0.011252 0.051770 -0.003087 +v -0.007858 0.049774 0.009390 +v -0.007858 0.051770 0.009390 +v 0.004619 0.049774 0.012584 +v 0.004619 0.051770 0.012584 +v 0.013702 0.049774 0.003501 +v 0.013702 0.051770 0.003501 +v 0.010308 0.049774 -0.008876 +v 0.010308 0.051770 -0.008876 +v 0.094651 -0.000134 -0.037224 +v 0.094352 -0.000134 -0.040418 +v 0.094152 -0.000134 -0.043612 +v 0.088962 -0.028281 -0.032932 +v 0.088064 -0.029978 -0.038920 +v 0.088363 -0.000134 -0.046307 +v 0.082773 -0.028281 -0.041915 +v 0.083173 -0.000134 -0.042613 +v 0.078282 -0.025087 -0.038920 +v 0.084470 -0.025087 -0.029937 +v 0.072293 -0.048444 -0.021553 +v 0.069498 -0.043253 -0.019556 +v 0.070696 -0.050839 -0.027142 +v 0.066204 -0.047945 -0.030736 +v 0.063409 -0.042654 -0.028740 +v 0.079180 -0.023390 -0.032932 +v 0.065106 -0.040259 -0.023250 +v 0.049336 -0.057926 -0.011971 +v 0.052829 -0.055031 -0.007778 +v 0.046541 -0.054632 -0.016862 +v 0.045443 -0.048544 -0.015963 +v 0.050933 -0.045549 -0.013268 +v 0.051232 -0.049043 -0.006581 +v 0.032667 -0.058126 -0.000592 +v 0.031070 -0.054732 0.007693 +v 0.024681 -0.054333 -0.001390 +v 0.027676 -0.051837 0.010188 +v 0.049036 -0.052037 -0.004884 +v 0.043347 -0.051438 -0.014266 +v 0.021288 -0.051438 0.001205 +v 0.089361 -0.000134 -0.033630 +v 0.083472 -0.000134 -0.039519 +v 0.083672 -0.000134 -0.036325 +v 0.088064 0.029711 -0.038920 +v 0.088962 0.028114 -0.032932 +v 0.082773 0.028014 -0.041915 +v 0.078282 0.024820 -0.038920 +v 0.072293 0.048276 -0.021553 +v 0.084470 0.024820 -0.029937 +v 0.069498 0.042986 -0.019556 +v 0.070696 0.050572 -0.027142 +v 0.066204 0.047677 -0.030736 +v 0.063409 0.042387 -0.028740 +v 0.065106 0.039992 -0.023250 +v 0.079180 0.023223 -0.032932 +v 0.051232 0.048776 -0.006581 +v 0.052829 0.054764 -0.007778 +v 0.049336 0.057659 -0.011971 +v 0.046541 0.054365 -0.016862 +v 0.045443 0.048276 -0.015963 +v 0.050933 0.045282 -0.013268 +v 0.032667 0.057859 -0.000592 +v 0.031070 0.054465 0.007693 +v 0.024681 0.054066 -0.001390 +v 0.049036 0.051770 -0.004884 +v 0.027676 0.051570 0.010188 +v 0.043347 0.051171 -0.014266 +v 0.021288 0.051271 0.001205 +v 0.093254 -0.000134 -0.114380 +v 0.092755 -0.000134 -0.117574 +v 0.092256 -0.000134 -0.120668 +v 0.074489 -0.034769 -0.099907 +v 0.074489 -0.037664 -0.105497 +v 0.086267 -0.000134 -0.122864 +v 0.069698 -0.036466 -0.109589 +v 0.081376 -0.000134 -0.118772 +v 0.065106 -0.032374 -0.108092 +v 0.069897 -0.030777 -0.098410 +v 0.046042 -0.054233 -0.071560 +v 0.044944 -0.048044 -0.071959 +v 0.042349 -0.058126 -0.074754 +v 0.037558 -0.055830 -0.078347 +v 0.036460 -0.049641 -0.078746 +v 0.065206 -0.029579 -0.102502 +v 0.040153 -0.045749 -0.075552 +v 0.024781 -0.057926 -0.055689 +v 0.027975 -0.055031 -0.051098 +v 0.021687 -0.054632 -0.060480 +v 0.020789 -0.048543 -0.059382 +v 0.025979 -0.045549 -0.057386 +v 0.026678 -0.049043 -0.049501 +v 0.005717 -0.058126 -0.032432 +v 0.006116 -0.054732 -0.023948 +v -0.002268 -0.054333 -0.031135 +v 0.003421 -0.051837 -0.020654 +v 0.024981 -0.052037 -0.047405 +v 0.019192 -0.051438 -0.057286 +v -0.004863 -0.051438 -0.027841 +v 0.088363 -0.000134 -0.110388 +v 0.081975 -0.000134 -0.115677 +v 0.082474 -0.000134 -0.112583 +v 0.074489 0.037397 -0.105497 +v 0.074489 0.034502 -0.099907 +v 0.069698 0.036199 -0.109589 +v 0.065106 0.032206 -0.108092 +v 0.046042 0.053966 -0.071560 +v 0.069897 0.030510 -0.098410 +v 0.044944 0.047777 -0.071959 +v 0.042349 0.057859 -0.074754 +v 0.037558 0.055563 -0.078347 +v 0.036460 0.049474 -0.078746 +v 0.040153 0.045482 -0.075552 +v 0.065206 0.029312 -0.102502 +v 0.024781 0.057659 -0.055689 +v 0.027975 0.054764 -0.051098 +v 0.021687 0.054365 -0.060480 +v 0.020789 0.048276 -0.059382 +v 0.025979 0.045282 -0.057386 +v 0.026678 0.048776 -0.049501 +v 0.005717 0.057859 -0.032432 +v 0.006116 0.054465 -0.023948 +v -0.002268 0.054066 -0.031135 +v 0.024981 0.051770 -0.047405 +v 0.003421 0.051570 -0.020654 +v 0.019192 0.051171 -0.057286 +v -0.004863 0.051271 -0.027841 +v 0.046142 -0.054233 -0.074055 +v 0.066803 -0.041756 -0.175666 +v 0.061214 -0.043952 -0.176365 +v 0.040851 -0.056728 -0.075752 +v 0.056422 -0.040159 -0.176864 +v 0.036659 -0.053334 -0.078646 +v 0.057321 -0.034170 -0.176564 +v 0.037757 -0.047446 -0.079844 +v 0.063010 -0.031974 -0.175866 +v 0.043047 -0.044950 -0.078148 +v 0.067701 -0.035767 -0.175466 +v 0.047239 -0.048344 -0.075153 +v 0.052330 -0.036466 -0.345450 +v 0.058020 -0.034470 -0.350341 +v 0.047639 -0.032573 -0.345250 +v 0.048737 -0.026584 -0.349942 +v 0.054526 -0.024488 -0.344252 +v 0.059117 -0.028481 -0.344552 +v 0.061214 0.043785 -0.176365 +v 0.066803 0.041489 -0.175666 +v 0.046142 0.053966 -0.074055 +v 0.040851 0.056461 -0.075752 +v 0.056422 0.039892 -0.176864 +v 0.036659 0.053068 -0.078646 +v 0.057321 0.033903 -0.176564 +v 0.037757 0.047179 -0.079844 +v 0.063010 0.031707 -0.175866 +v 0.043047 0.044683 -0.078148 +v 0.067701 0.035500 -0.175466 +v 0.047240 0.048077 -0.075153 +v 0.052330 0.036199 -0.345450 +v 0.058020 0.034203 -0.350341 +v 0.047639 0.032306 -0.345250 +v 0.048737 0.026317 -0.349942 +v 0.054526 0.024321 -0.344252 +v 0.059117 0.028214 -0.344552 +v 0.023084 -0.037564 -0.176664 +v 0.023084 -0.042854 -0.179758 +v 0.060315 -0.037963 -0.178261 +v 0.056822 -0.032673 -0.175167 +v 0.023084 -0.037564 -0.170575 +v 0.057421 -0.032274 -0.169178 +v 0.023084 -0.042854 -0.167581 +v 0.061413 -0.037065 -0.166084 +v 0.023084 -0.048144 -0.170575 +v 0.064907 -0.042355 -0.169078 +v 0.023084 -0.048144 -0.176664 +v 0.064408 -0.042754 -0.175167 +v 0.077483 -0.000134 -0.192635 +v 0.072493 -0.000134 -0.188343 +v 0.073890 -0.000134 -0.182353 +v 0.080278 -0.000134 -0.180657 +v 0.085269 -0.000134 -0.184949 +v 0.083871 -0.000134 -0.190938 +v 0.060315 0.037696 -0.178261 +v 0.023084 0.042587 -0.179758 +v 0.023084 0.037297 -0.176664 +v 0.056822 0.032506 -0.175167 +v 0.023084 0.037297 -0.170575 +v 0.057421 0.032007 -0.169178 +v 0.023084 0.042587 -0.167581 +v 0.061413 0.036798 -0.166084 +v 0.023084 0.047877 -0.170575 +v 0.064907 0.042088 -0.169078 +v 0.023084 0.047877 -0.176664 +v 0.064408 0.042487 -0.175167 +v 0.023084 -0.037564 -0.227370 +v 0.023084 -0.042854 -0.230464 +v 0.056123 -0.034370 -0.240845 +v 0.052630 -0.029180 -0.237750 +v 0.023084 -0.037564 -0.221281 +v 0.053228 -0.028680 -0.231762 +v 0.023084 -0.042854 -0.218287 +v 0.057321 -0.033471 -0.228667 +v 0.023084 -0.048144 -0.221281 +v 0.060715 -0.038762 -0.231662 +v 0.023084 -0.048144 -0.227370 +v 0.060215 -0.039161 -0.237750 +v 0.070896 -0.000134 -0.251824 +v 0.065905 -0.000134 -0.247532 +v 0.067202 -0.000134 -0.241444 +v 0.073690 -0.000134 -0.239747 +v 0.078681 -0.000134 -0.244039 +v 0.077284 -0.000134 -0.250028 +v 0.056123 0.034103 -0.240845 +v 0.023084 0.042587 -0.230464 +v 0.023084 0.037297 -0.227370 +v 0.052630 0.028913 -0.237750 +v 0.023084 0.037297 -0.221281 +v 0.053228 0.028413 -0.231762 +v 0.023084 0.042587 -0.218287 +v 0.057321 0.033205 -0.228667 +v 0.023084 0.047877 -0.221281 +v 0.060715 0.038495 -0.231662 +v 0.023084 0.047877 -0.227370 +v 0.060215 0.038994 -0.237750 +v 0.047239 -0.042056 -0.356829 +v 0.052230 -0.042056 -0.350341 +v 0.060914 -0.031874 -0.350042 +v 0.058020 -0.030377 -0.355731 +v 0.035162 -0.042056 -0.358825 +v 0.052230 -0.028281 -0.355531 +v 0.028075 -0.042056 -0.354433 +v 0.049436 -0.027682 -0.349642 +v 0.033066 -0.042056 -0.347946 +v 0.052230 -0.029180 -0.343853 +v 0.045143 -0.042056 -0.345949 +v 0.058020 -0.031276 -0.344053 +v 0.069897 -0.000134 -0.348744 +v 0.066803 -0.000134 -0.354433 +v 0.060615 -0.000134 -0.354234 +v 0.057520 -0.000134 -0.348345 +v 0.060615 -0.000134 -0.342555 +v 0.066803 -0.000134 -0.342755 +v 0.060914 0.031608 -0.350042 +v 0.052230 0.041789 -0.350341 +v 0.047239 0.041789 -0.356829 +v 0.058020 0.030110 -0.355731 +v 0.035162 0.041789 -0.358825 +v 0.052230 0.028014 -0.355531 +v 0.028075 0.041789 -0.354433 +v 0.049436 0.027415 -0.349642 +v 0.033066 0.041789 -0.347946 +v 0.052230 0.028913 -0.343853 +v 0.045143 0.041789 -0.345949 +v 0.058020 0.031009 -0.344053 +# 809 vertices, 0 vertices normals + +f 1 4 3 +f 3 2 1 +f 5 8 7 +f 7 6 5 +f 4 8 9 +f 9 3 4 +f 2 3 10 +f 11 14 13 +f 13 12 11 +f 3 9 10 +f 9 8 5 +f 15 17 16 +f 18 15 16 +f 16 19 18 +f 20 16 22 +f 22 21 20 +f 13 14 20 +f 20 21 13 +f 23 20 14 +f 14 11 17 +f 17 23 14 +f 12 22 16 +f 16 11 12 +f 16 17 11 +f 22 12 13 +f 13 21 22 +f 20 23 25 +f 25 24 20 +f 26 19 16 +f 16 27 26 +f 28 18 29 +f 30 31 9 +f 9 5 30 +f 25 33 32 +f 32 24 25 +f 28 34 15 +f 15 18 28 +f 18 19 26 +f 26 29 18 +f 32 27 20 +f 20 24 32 +f 20 27 16 +f 26 27 10 +f 10 31 26 +f 28 29 30 +f 30 6 28 +f 33 1 2 +f 2 32 33 +f 6 7 34 +f 34 28 6 +f 26 31 30 +f 30 29 26 +f 2 10 27 +f 27 32 2 +f 31 10 9 +f 6 30 5 +f 35 38 37 +f 37 36 35 +f 35 36 39 +f 40 43 42 +f 42 41 40 +f 44 46 45 +f 47 50 49 +f 49 48 47 +f 51 52 46 +f 51 50 53 +f 53 52 51 +f 47 56 55 +f 55 54 47 +f 57 60 59 +f 59 58 57 +f 61 64 63 +f 63 62 61 +f 59 60 64 +f 64 61 59 +f 62 63 56 +f 56 65 62 +f 54 53 50 +f 50 47 54 +f 66 51 46 +f 46 44 66 +f 66 67 50 +f 50 51 66 +f 68 60 69 +f 48 65 56 +f 56 47 48 +f 60 57 69 +f 55 63 64 +f 64 70 55 +f 70 64 60 +f 60 68 70 +f 56 63 55 +f 71 74 73 +f 73 72 71 +f 72 75 71 +f 76 77 74 +f 74 71 76 +f 78 77 79 +f 49 81 80 +f 80 48 49 +f 65 48 80 +f 80 82 65 +f 83 85 84 +f 84 73 83 +f 86 89 88 +f 88 87 86 +f 90 91 89 +f 89 86 90 +f 89 93 92 +f 92 88 89 +f 81 49 95 +f 95 94 81 +f 91 90 94 +f 94 96 91 +f 94 95 98 +f 98 97 94 +f 97 96 94 +f 81 94 90 +f 86 80 81 +f 81 90 86 +f 87 82 80 +f 80 86 87 +f 99 84 82 +f 82 87 99 +f 84 85 65 +f 65 82 84 +f 99 87 88 +f 72 73 84 +f 100 101 88 +f 88 92 100 +f 102 103 101 +f 101 100 102 +f 104 105 103 +f 103 102 104 +f 106 107 105 +f 105 104 106 +f 108 109 107 +f 107 106 108 +f 72 84 75 +f 71 75 110 +f 110 76 71 +f 88 75 99 +f 101 75 88 +f 101 103 110 +f 110 75 101 +f 103 105 111 +f 111 110 103 +f 91 112 93 +f 93 89 91 +f 113 114 112 +f 112 91 113 +f 115 116 114 +f 114 113 115 +f 96 117 113 +f 113 91 96 +f 118 119 116 +f 116 115 118 +f 120 121 119 +f 119 118 120 +f 118 115 122 +f 122 120 118 +f 92 104 102 +f 102 100 92 +f 99 75 84 +f 92 106 104 +f 93 116 119 +f 119 106 92 +f 92 93 119 +f 108 106 119 +f 119 121 108 +f 116 93 112 +f 112 114 116 +f 98 124 123 +f 123 97 98 +f 123 124 126 +f 126 125 123 +f 123 96 97 +f 49 50 67 +f 67 127 49 +f 128 95 127 +f 127 67 128 +f 129 130 45 +f 45 46 129 +f 130 131 44 +f 44 45 130 +f 132 129 46 +f 46 52 132 +f 131 133 66 +f 66 44 131 +f 133 128 67 +f 67 66 133 +f 134 132 52 +f 52 53 134 +f 53 54 135 +f 135 134 53 +f 54 137 136 +f 136 135 54 +f 138 139 36 +f 36 37 138 +f 140 38 141 +f 142 141 38 +f 38 35 142 +f 139 143 39 +f 39 36 139 +f 143 142 35 +f 35 39 143 +f 140 42 144 +f 40 145 57 +f 57 43 40 +f 69 57 145 +f 146 148 147 +f 148 146 150 +f 150 149 148 +f 150 151 149 +f 146 153 152 +f 152 150 146 +f 153 146 154 +f 155 158 157 +f 157 156 155 +f 156 157 160 +f 160 159 156 +f 152 83 73 +f 73 150 152 +f 73 74 151 +f 151 150 73 +f 62 65 85 +f 83 62 85 +f 152 153 61 +f 61 83 152 +f 62 83 61 +f 61 153 154 +f 154 59 61 +f 148 155 156 +f 159 147 156 +f 147 148 156 +f 149 161 155 +f 155 148 149 +f 151 78 161 +f 161 149 151 +f 78 151 74 +f 74 77 78 +f 158 155 162 +f 162 155 163 +f 158 160 157 +f 163 161 164 +f 161 78 79 +f 79 164 161 +f 155 161 163 +f 165 146 147 +f 147 159 165 +f 154 146 165 +f 58 59 154 +f 166 58 154 +f 167 138 37 +f 37 144 167 +f 168 169 167 +f 167 144 168 +f 170 171 168 +f 170 172 171 +f 173 58 175 +f 175 174 173 +f 57 58 173 +f 176 177 174 +f 176 174 175 +f 174 177 172 +f 172 170 174 +f 43 57 173 +f 43 174 170 +f 170 42 43 +f 174 43 173 +f 168 144 42 +f 42 170 168 +f 169 168 171 +f 160 158 162 +f 162 178 160 +f 165 166 154 +f 179 180 175 +f 175 166 179 +f 175 180 181 +f 181 176 175 +f 176 181 182 +f 182 177 176 +f 183 184 177 +f 177 182 183 +f 185 186 171 +f 171 172 185 +f 186 187 169 +f 169 171 186 +f 188 189 169 +f 169 187 188 +f 190 191 189 +f 189 188 190 +f 192 193 191 +f 191 190 192 +f 194 195 193 +f 193 192 194 +f 196 197 195 +f 195 194 196 +f 190 194 192 +f 196 194 190 +f 190 188 196 +f 68 199 198 +f 198 70 68 +f 69 200 199 +f 199 68 69 +f 40 203 202 +f 202 201 40 +f 40 41 203 +f 204 203 41 +f 41 140 204 +f 197 204 140 +f 140 141 197 +f 145 205 200 +f 200 69 145 +f 70 198 206 +f 206 55 70 +f 55 206 137 +f 137 54 55 +f 40 201 205 +f 205 145 40 +f 196 204 197 +f 196 188 187 +f 187 204 196 +f 203 204 186 +f 186 185 203 +f 186 204 187 +f 144 37 38 +f 38 140 144 +f 195 191 193 +f 197 189 191 +f 191 195 197 +f 141 142 139 +f 139 138 141 +f 143 139 142 +f 197 169 189 +f 141 138 167 +f 167 169 197 +f 197 141 167 +f 177 184 185 +f 185 172 177 +f 127 95 49 +f 128 98 95 +f 207 124 128 +f 124 207 208 +f 208 126 124 +f 130 129 131 +f 132 131 129 +f 132 134 207 +f 207 133 132 +f 133 131 132 +f 58 166 175 +f 117 96 123 +f 113 117 115 +f 117 209 122 +f 122 115 117 +f 117 123 125 +f 125 209 117 +f 207 134 210 +f 210 208 207 +f 128 133 207 +f 98 128 124 +f 140 41 42 +f 210 134 135 +f 135 136 210 +f 178 211 159 +f 159 160 178 +f 211 212 165 +f 165 159 211 +f 212 179 166 +f 166 165 212 +f 183 202 203 +f 203 184 183 +f 213 216 215 +f 215 214 213 +f 217 214 215 +f 218 221 220 +f 220 219 218 +f 222 224 223 +f 225 228 227 +f 227 226 225 +f 224 230 229 +f 231 228 229 +f 229 230 231 +f 232 234 227 +f 227 233 232 +f 235 238 237 +f 237 236 235 +f 239 242 241 +f 241 240 239 +f 242 238 235 +f 235 241 242 +f 234 239 240 +f 240 243 234 +f 228 231 233 +f 233 227 228 +f 224 229 244 +f 244 223 224 +f 228 245 244 +f 244 229 228 +f 246 238 247 +f 234 243 226 +f 226 227 234 +f 246 237 238 +f 242 239 232 +f 232 248 242 +f 238 242 248 +f 248 247 238 +f 232 239 234 +f 249 252 251 +f 251 250 249 +f 251 253 250 +f 252 77 76 +f 76 251 252 +f 79 77 254 +f 255 256 225 +f 225 226 255 +f 255 226 243 +f 243 257 255 +f 258 260 259 +f 259 249 258 +f 261 264 263 +f 263 262 261 +f 264 266 265 +f 265 263 264 +f 267 268 264 +f 264 261 267 +f 269 225 256 +f 256 270 269 +f 270 265 266 +f 266 271 270 +f 272 269 270 +f 270 273 272 +f 270 271 273 +f 265 270 256 +f 256 255 263 +f 263 265 256 +f 255 257 262 +f 262 263 255 +f 257 258 274 +f 274 262 257 +f 243 260 258 +f 258 257 243 +f 261 262 274 +f 258 249 250 +f 261 276 275 +f 275 267 261 +f 276 278 277 +f 277 275 276 +f 278 280 279 +f 279 277 278 +f 280 282 281 +f 281 279 280 +f 282 109 108 +f 108 281 282 +f 253 258 250 +f 110 253 251 +f 251 76 110 +f 274 253 261 +f 261 253 276 +f 110 278 276 +f 276 253 110 +f 278 110 111 +f 111 280 278 +f 268 283 266 +f 266 264 268 +f 283 285 284 +f 284 266 283 +f 285 287 286 +f 286 284 285 +f 284 288 271 +f 271 266 284 +f 287 290 289 +f 289 286 287 +f 290 121 120 +f 120 289 290 +f 289 120 122 +f 122 286 289 +f 277 279 267 +f 267 275 277 +f 258 253 274 +f 279 281 267 +f 290 287 268 +f 267 281 290 +f 290 268 267 +f 290 281 108 +f 108 121 290 +f 283 268 287 +f 287 285 283 +f 291 292 272 +f 272 273 291 +f 126 292 291 +f 291 125 126 +f 273 271 291 +f 245 228 225 +f 225 293 245 +f 293 269 294 +f 294 245 293 +f 222 296 295 +f 295 224 222 +f 223 297 296 +f 296 222 223 +f 224 295 298 +f 298 230 224 +f 244 299 297 +f 297 223 244 +f 245 294 299 +f 299 244 245 +f 230 298 300 +f 300 231 230 +f 301 233 231 +f 231 300 301 +f 136 137 233 +f 233 301 136 +f 214 303 302 +f 302 213 214 +f 304 216 305 +f 216 304 306 +f 306 215 216 +f 217 307 303 +f 303 214 217 +f 215 306 307 +f 307 217 215 +f 308 218 305 +f 237 309 220 +f 220 221 237 +f 309 237 246 +f 310 312 311 +f 313 311 312 +f 312 314 313 +f 314 315 313 +f 316 317 311 +f 311 313 316 +f 318 311 317 +f 319 322 321 +f 321 320 319 +f 323 319 320 +f 320 324 323 +f 249 259 316 +f 316 313 249 +f 315 252 249 +f 249 313 315 +f 260 243 240 +f 260 240 259 +f 241 317 316 +f 316 259 241 +f 241 259 240 +f 318 317 241 +f 241 235 318 +f 320 321 312 +f 320 310 324 +f 320 312 310 +f 321 325 314 +f 314 312 321 +f 325 254 315 +f 315 314 325 +f 252 315 254 +f 254 77 252 +f 322 162 163 +f 163 321 322 +f 319 323 322 +f 164 325 163 +f 79 254 325 +f 325 164 79 +f 163 325 321 +f 310 311 326 +f 326 324 310 +f 326 311 318 +f 318 235 236 +f 318 236 327 +f 213 302 328 +f 328 308 213 +f 328 330 329 +f 329 308 328 +f 329 332 331 +f 332 333 331 +f 334 236 336 +f 336 335 334 +f 336 236 237 +f 335 338 337 +f 334 335 337 +f 333 338 335 +f 335 331 333 +f 336 237 221 +f 331 335 221 +f 221 218 331 +f 336 221 335 +f 218 308 329 +f 329 331 218 +f 332 329 330 +f 162 322 323 +f 323 178 162 +f 318 327 326 +f 334 180 179 +f 179 327 334 +f 181 180 334 +f 334 337 181 +f 182 181 337 +f 337 338 182 +f 183 182 338 +f 338 339 183 +f 332 341 340 +f 340 333 332 +f 330 342 341 +f 341 332 330 +f 330 344 343 +f 343 342 330 +f 344 346 345 +f 345 343 344 +f 346 348 347 +f 347 345 346 +f 348 350 349 +f 349 347 348 +f 350 352 351 +f 351 349 350 +f 347 349 345 +f 345 349 351 +f 351 343 345 +f 198 199 247 +f 247 248 198 +f 199 200 246 +f 246 247 199 +f 220 201 202 +f 202 353 220 +f 353 219 220 +f 219 353 354 +f 354 305 219 +f 305 354 352 +f 352 304 305 +f 200 205 309 +f 309 246 200 +f 206 198 248 +f 248 232 206 +f 137 206 232 +f 232 233 137 +f 205 201 220 +f 220 309 205 +f 352 354 351 +f 342 343 351 +f 351 354 342 +f 341 354 353 +f 353 340 341 +f 342 354 341 +f 216 213 308 +f 308 305 216 +f 348 346 350 +f 346 344 352 +f 352 350 346 +f 303 306 304 +f 304 302 303 +f 306 303 307 +f 344 330 352 +f 328 302 304 +f 352 330 328 +f 328 304 352 +f 340 339 338 +f 338 333 340 +f 225 269 293 +f 269 272 294 +f 294 292 355 +f 208 355 292 +f 292 126 208 +f 297 295 296 +f 295 297 298 +f 355 300 298 +f 298 299 355 +f 298 297 299 +f 334 327 236 +f 291 271 288 +f 286 288 284 +f 122 209 288 +f 288 286 122 +f 125 291 288 +f 288 209 125 +f 210 300 355 +f 355 208 210 +f 355 299 294 +f 292 294 272 +f 218 219 305 +f 301 300 210 +f 210 136 301 +f 324 211 178 +f 178 323 324 +f 326 212 211 +f 211 324 326 +f 327 179 212 +f 212 326 327 +f 340 353 339 +f 339 353 202 +f 202 183 339 +f 185 184 203 +f 111 109 282 +f 282 280 111 +f 111 105 107 +f 107 109 111 +f 356 359 358 +f 358 357 356 +f 360 363 362 +f 362 361 360 +f 364 363 359 +f 359 356 364 +f 365 356 357 +f 366 369 368 +f 368 367 366 +f 365 364 356 +f 362 363 364 +f 370 372 371 +f 370 371 374 +f 374 373 370 +f 375 370 377 +f 377 376 375 +f 377 369 366 +f 366 376 377 +f 369 377 378 +f 372 368 369 +f 369 378 372 +f 370 375 367 +f 367 368 370 +f 368 372 370 +f 366 367 375 +f 375 376 366 +f 379 378 377 +f 377 380 379 +f 370 373 382 +f 382 381 370 +f 383 374 384 +f 364 386 385 +f 385 362 364 +f 387 388 379 +f 379 380 387 +f 371 389 384 +f 384 374 371 +f 382 373 374 +f 374 383 382 +f 377 381 387 +f 387 380 377 +f 370 381 377 +f 365 381 382 +f 382 386 365 +f 385 383 384 +f 384 361 385 +f 357 358 388 +f 388 387 357 +f 389 360 361 +f 361 384 389 +f 385 386 382 +f 382 383 385 +f 381 365 357 +f 357 387 381 +f 364 365 386 +f 362 385 361 +f 390 393 392 +f 392 391 390 +f 393 395 394 +f 394 392 393 +f 395 397 396 +f 396 394 395 +f 397 399 398 +f 398 396 397 +f 399 401 400 +f 400 398 399 +f 401 390 391 +f 391 400 401 +f 402 403 391 +f 391 392 402 +f 404 402 392 +f 392 394 404 +f 405 404 394 +f 394 396 405 +f 406 405 396 +f 396 398 406 +f 407 406 398 +f 398 400 407 +f 403 407 400 +f 400 391 403 +f 408 411 410 +f 410 409 408 +f 409 410 413 +f 413 412 409 +f 412 413 415 +f 415 414 412 +f 414 415 417 +f 417 416 414 +f 418 419 411 +f 411 408 418 +f 420 421 419 +f 419 418 420 +f 422 425 424 +f 424 423 422 +f 423 424 421 +f 421 420 423 +f 416 417 427 +f 427 426 416 +f 426 427 425 +f 425 422 426 +f 413 410 415 +f 416 408 409 +f 409 414 416 +f 411 419 427 +f 427 417 411 +f 419 421 425 +f 425 427 419 +f 423 420 422 +f 412 414 409 +f 426 418 408 +f 408 416 426 +f 422 420 418 +f 418 426 422 +f 417 415 410 +f 410 411 417 +f 424 425 421 +f 428 431 430 +f 430 429 428 +f 432 428 429 +f 429 433 432 +f 434 432 433 +f 433 435 434 +f 436 434 435 +f 435 437 436 +f 431 439 438 +f 438 430 431 +f 439 441 440 +f 440 438 439 +f 442 445 444 +f 444 443 442 +f 441 442 443 +f 443 440 441 +f 446 436 437 +f 437 447 446 +f 445 446 447 +f 447 444 445 +f 434 428 432 +f 429 430 437 +f 437 435 429 +f 446 439 431 +f 431 436 446 +f 445 441 439 +f 439 446 445 +f 444 440 443 +f 429 435 433 +f 430 438 447 +f 447 437 430 +f 438 440 444 +f 444 447 438 +f 428 434 436 +f 436 431 428 +f 441 445 442 +f 448 451 450 +f 450 449 448 +f 451 453 452 +f 452 450 451 +f 453 455 454 +f 454 452 453 +f 455 457 456 +f 456 454 455 +f 458 461 460 +f 460 459 458 +f 461 463 462 +f 462 460 461 +f 463 465 464 +f 464 462 463 +f 465 467 466 +f 466 464 465 +f 449 466 467 +f 467 448 449 +f 457 458 459 +f 459 456 457 +f 451 448 457 +f 457 455 451 +f 464 460 462 +f 456 459 466 +f 466 449 456 +f 460 464 466 +f 466 459 460 +f 456 449 450 +f 450 454 456 +f 454 450 452 +f 458 457 448 +f 448 467 458 +f 451 455 453 +f 461 465 463 +f 465 461 458 +f 458 467 465 +f 468 471 470 +f 470 469 468 +f 472 473 471 +f 471 468 472 +f 474 475 473 +f 473 472 474 +f 476 477 475 +f 475 474 476 +f 478 481 480 +f 480 479 478 +f 482 483 481 +f 481 478 482 +f 484 485 483 +f 483 482 484 +f 486 487 485 +f 485 484 486 +f 487 486 469 +f 469 470 487 +f 479 480 477 +f 477 476 479 +f 477 470 471 +f 471 475 477 +f 482 478 484 +f 486 479 476 +f 476 469 486 +f 486 484 478 +f 478 479 486 +f 468 469 476 +f 476 474 468 +f 472 468 474 +f 470 477 480 +f 480 487 470 +f 473 475 471 +f 483 485 481 +f 480 481 485 +f 485 487 480 +f 488 491 490 +f 490 489 488 +f 489 490 493 +f 493 492 489 +f 492 493 495 +f 495 494 492 +f 496 499 498 +f 498 497 496 +f 500 501 499 +f 499 496 500 +f 502 503 501 +f 501 500 502 +f 494 495 503 +f 503 502 494 +f 497 498 505 +f 505 504 497 +f 504 505 507 +f 507 506 504 +f 506 507 509 +f 509 508 506 +f 510 511 491 +f 491 488 510 +f 512 513 511 +f 511 510 512 +f 514 515 513 +f 513 512 514 +f 508 509 515 +f 515 514 508 +f 516 519 518 +f 518 517 516 +f 520 521 519 +f 519 516 520 +f 522 523 521 +f 521 520 522 +f 524 525 523 +f 523 522 524 +f 526 527 525 +f 525 524 526 +f 517 518 527 +f 527 526 517 +f 500 496 519 +f 519 521 500 +f 496 497 519 +f 500 521 523 +f 523 502 500 +f 502 523 494 +f 519 497 504 +f 504 518 519 +f 494 523 525 +f 525 492 494 +f 512 510 525 +f 525 527 512 +f 527 518 514 +f 514 512 527 +f 506 508 514 +f 506 514 518 +f 518 504 506 +f 489 510 488 +f 489 492 525 +f 525 510 489 +f 490 491 511 +f 507 515 509 +f 507 505 517 +f 517 515 507 +f 490 511 524 +f 524 493 490 +f 513 526 524 +f 524 511 513 +f 515 517 526 +f 526 513 515 +f 516 517 505 +f 505 498 516 +f 499 516 498 +f 495 493 524 +f 524 522 495 +f 495 522 503 +f 501 503 522 +f 522 520 501 +f 501 520 516 +f 516 499 501 +f 528 531 530 +f 530 529 528 +f 532 528 529 +f 529 533 532 +f 534 532 533 +f 533 535 534 +f 536 539 538 +f 538 537 536 +f 539 541 540 +f 540 538 539 +f 541 543 542 +f 542 540 541 +f 543 534 535 +f 535 542 543 +f 544 536 537 +f 537 545 544 +f 546 544 545 +f 545 547 546 +f 548 546 547 +f 547 549 548 +f 531 551 550 +f 550 530 531 +f 551 553 552 +f 552 550 551 +f 553 555 554 +f 554 552 553 +f 555 548 549 +f 549 554 555 +f 556 559 558 +f 558 557 556 +f 559 561 560 +f 560 558 559 +f 561 563 562 +f 562 560 561 +f 563 565 564 +f 564 562 563 +f 565 567 566 +f 566 564 565 +f 567 556 557 +f 557 566 567 +f 559 538 540 +f 540 561 559 +f 559 537 538 +f 563 561 540 +f 540 542 563 +f 535 563 542 +f 545 537 559 +f 559 556 545 +f 565 563 535 +f 535 533 565 +f 565 550 552 +f 552 567 565 +f 554 556 567 +f 567 552 554 +f 554 549 547 +f 556 554 547 +f 547 545 556 +f 530 550 529 +f 565 533 529 +f 529 550 565 +f 551 531 528 +f 548 555 546 +f 557 544 546 +f 546 555 557 +f 564 551 528 +f 528 532 564 +f 564 566 553 +f 553 551 564 +f 566 557 555 +f 555 553 566 +f 544 557 558 +f 558 536 544 +f 536 558 539 +f 564 532 534 +f 534 562 564 +f 543 562 534 +f 562 543 541 +f 541 560 562 +f 558 560 541 +f 541 539 558 +f 568 571 570 +f 570 569 568 +f 572 570 571 +f 570 572 574 +f 574 573 570 +f 573 574 576 +f 576 575 573 +f 577 579 578 +f 578 571 577 +f 571 578 580 +f 580 572 571 +f 572 580 581 +f 581 574 572 +f 574 581 582 +f 582 576 574 +f 576 582 584 +f 584 583 576 +f 583 584 579 +f 579 577 583 +f 578 586 585 +f 585 580 578 +f 580 585 587 +f 587 581 580 +f 581 587 588 +f 588 582 581 +f 582 588 589 +f 589 584 582 +f 584 589 590 +f 590 579 584 +f 586 592 591 +f 591 585 586 +f 593 587 585 +f 585 591 593 +f 592 586 595 +f 595 594 592 +f 593 597 596 +f 596 587 593 +f 590 586 578 +f 578 579 590 +f 588 590 589 +f 595 590 588 +f 588 596 595 +f 591 592 593 +f 594 597 593 +f 593 592 594 +f 594 595 596 +f 596 597 594 +f 571 568 598 +f 598 577 571 +f 575 576 583 +f 583 599 575 +f 600 599 583 +f 577 598 600 +f 600 583 577 +f 601 602 569 +f 569 570 601 +f 569 602 568 +f 603 601 570 +f 570 573 603 +f 604 603 573 +f 573 575 604 +f 605 607 606 +f 606 602 605 +f 608 605 602 +f 602 601 608 +f 609 608 601 +f 601 603 609 +f 610 609 603 +f 603 604 610 +f 611 610 604 +f 604 612 611 +f 607 611 612 +f 612 606 607 +f 607 605 614 +f 614 613 607 +f 615 614 605 +f 605 608 615 +f 616 615 608 +f 608 609 616 +f 617 616 609 +f 609 610 617 +f 618 617 610 +f 610 611 618 +f 613 618 611 +f 611 607 613 +f 619 620 614 +f 614 615 619 +f 615 616 621 +f 621 619 615 +f 622 614 620 +f 620 623 622 +f 624 625 621 +f 621 616 624 +f 618 613 617 +f 617 613 622 +f 622 624 617 +f 621 620 619 +f 621 625 623 +f 623 620 621 +f 624 622 623 +f 623 625 624 +f 598 568 602 +f 602 606 598 +f 600 612 604 +f 604 599 600 +f 575 599 604 +f 600 598 606 +f 606 612 600 +f 586 590 595 +f 588 587 596 +f 613 614 622 +f 616 617 624 +f 626 629 628 +f 628 627 626 +f 630 628 629 +f 628 630 632 +f 632 631 628 +f 631 632 634 +f 634 633 631 +f 635 637 636 +f 636 629 635 +f 629 636 638 +f 638 630 629 +f 630 638 639 +f 639 632 630 +f 632 639 640 +f 640 634 632 +f 634 640 642 +f 642 641 634 +f 641 642 637 +f 637 635 641 +f 636 644 643 +f 643 638 636 +f 638 643 645 +f 645 639 638 +f 639 645 646 +f 646 640 639 +f 640 646 647 +f 647 642 640 +f 642 647 648 +f 648 637 642 +f 644 650 649 +f 649 643 644 +f 651 645 643 +f 643 649 651 +f 650 644 653 +f 653 652 650 +f 651 655 654 +f 654 645 651 +f 648 644 636 +f 636 637 648 +f 646 648 647 +f 653 648 646 +f 646 654 653 +f 649 650 651 +f 652 655 651 +f 651 650 652 +f 652 653 654 +f 654 655 652 +f 629 626 656 +f 656 635 629 +f 633 634 641 +f 641 657 633 +f 658 657 641 +f 635 656 658 +f 658 641 635 +f 644 648 653 +f 646 645 654 +f 659 660 627 +f 627 628 659 +f 627 660 626 +f 661 659 628 +f 628 631 661 +f 662 661 631 +f 631 633 662 +f 663 665 664 +f 664 660 663 +f 666 663 660 +f 660 659 666 +f 667 666 659 +f 659 661 667 +f 668 667 661 +f 661 662 668 +f 669 668 662 +f 662 670 669 +f 665 669 670 +f 670 664 665 +f 671 672 663 +f 663 666 671 +f 673 671 666 +f 666 667 673 +f 674 673 667 +f 667 668 674 +f 675 674 668 +f 668 669 675 +f 676 675 669 +f 669 665 676 +f 677 678 672 +f 672 671 677 +f 671 673 679 +f 679 677 671 +f 680 672 678 +f 678 681 680 +f 682 683 679 +f 679 673 682 +f 663 672 676 +f 676 665 663 +f 675 676 674 +f 674 676 680 +f 680 682 674 +f 679 678 677 +f 679 683 681 +f 681 678 679 +f 682 680 681 +f 681 683 682 +f 656 626 660 +f 660 664 656 +f 658 670 662 +f 662 657 658 +f 633 657 662 +f 658 656 664 +f 664 670 658 +f 680 676 672 +f 682 673 674 +f 684 687 686 +f 686 685 684 +f 687 689 688 +f 688 686 687 +f 689 691 690 +f 690 688 689 +f 691 693 692 +f 692 690 691 +f 693 695 694 +f 694 692 693 +f 695 684 685 +f 685 694 695 +f 696 697 685 +f 685 686 696 +f 698 696 686 +f 686 688 698 +f 699 698 688 +f 688 690 699 +f 700 699 690 +f 690 692 700 +f 701 700 692 +f 692 694 701 +f 697 701 694 +f 694 685 697 +f 702 705 704 +f 704 703 702 +f 706 707 705 +f 705 702 706 +f 708 709 707 +f 707 706 708 +f 710 711 709 +f 709 708 710 +f 712 713 711 +f 711 710 712 +f 703 704 713 +f 713 712 703 +f 703 715 714 +f 714 702 703 +f 702 714 716 +f 716 706 702 +f 706 716 717 +f 717 708 706 +f 708 717 718 +f 718 710 708 +f 710 718 719 +f 719 712 710 +f 712 719 715 +f 715 703 712 +f 720 723 722 +f 722 721 720 +f 724 725 723 +f 723 720 724 +f 726 727 725 +f 725 724 726 +f 728 729 727 +f 727 726 728 +f 730 731 729 +f 729 728 730 +f 721 722 731 +f 731 730 721 +f 723 733 732 +f 732 722 723 +f 725 734 733 +f 733 723 725 +f 727 735 734 +f 734 725 727 +f 736 735 727 +f 727 729 736 +f 737 736 729 +f 729 731 737 +f 732 737 731 +f 731 722 732 +f 738 741 740 +f 740 739 738 +f 741 743 742 +f 742 740 741 +f 743 745 744 +f 744 742 743 +f 745 747 746 +f 746 744 745 +f 747 749 748 +f 748 746 747 +f 749 738 739 +f 739 748 749 +f 732 733 741 +f 741 738 732 +f 733 734 743 +f 743 741 733 +f 734 735 745 +f 745 743 734 +f 745 735 736 +f 736 747 745 +f 747 736 737 +f 737 749 747 +f 749 737 732 +f 732 738 749 +f 750 753 752 +f 752 751 750 +f 754 755 753 +f 753 750 754 +f 756 757 755 +f 755 754 756 +f 758 759 757 +f 757 756 758 +f 760 761 759 +f 759 758 760 +f 751 752 761 +f 761 760 751 +f 753 763 762 +f 762 752 753 +f 755 764 763 +f 763 753 755 +f 757 765 764 +f 764 755 757 +f 766 765 757 +f 757 759 766 +f 767 766 759 +f 759 761 767 +f 762 767 761 +f 761 752 762 +f 768 771 770 +f 770 769 768 +f 771 773 772 +f 772 770 771 +f 773 775 774 +f 774 772 773 +f 775 777 776 +f 776 774 775 +f 777 779 778 +f 778 776 777 +f 779 768 769 +f 769 778 779 +f 762 763 771 +f 771 768 762 +f 763 764 773 +f 773 771 763 +f 764 765 775 +f 775 773 764 +f 775 765 766 +f 766 777 775 +f 777 766 767 +f 767 779 777 +f 779 767 762 +f 762 768 779 +f 780 783 782 +f 782 781 780 +f 784 785 783 +f 783 780 784 +f 786 787 785 +f 785 784 786 +f 788 789 787 +f 787 786 788 +f 790 791 789 +f 789 788 790 +f 781 782 791 +f 791 790 781 +f 783 793 792 +f 792 782 783 +f 785 794 793 +f 793 783 785 +f 787 795 794 +f 794 785 787 +f 796 795 787 +f 787 789 796 +f 797 796 789 +f 789 791 797 +f 792 797 791 +f 791 782 792 +f 798 801 800 +f 800 799 798 +f 801 803 802 +f 802 800 801 +f 803 805 804 +f 804 802 803 +f 805 807 806 +f 806 804 805 +f 807 809 808 +f 808 806 807 +f 809 798 799 +f 799 808 809 +f 792 793 801 +f 801 798 792 +f 793 794 803 +f 803 801 793 +f 794 795 805 +f 805 803 794 +f 805 795 796 +f 796 807 805 +f 807 796 797 +f 797 809 807 +f 809 797 792 +f 792 798 809 +# 1494 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_lleg_chull.obj b/examples/Atlas/urdf/mesh/r_lleg_chull.obj new file mode 100644 index 0000000..8f45b19 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_lleg_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_lleg_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.005717 0.057859 -0.032432 +v 0.071035 0.050665 -0.021669 +v 0.021705 -0.060052 -0.007531 +v 0.071030 -0.050931 -0.021748 +v -0.000814 0.047260 -0.310515 +v 0.043715 0.060881 0.014841 +v -0.038900 -0.050041 -0.139933 +v -0.041571 -0.038541 -0.333141 +v -0.038900 0.049773 -0.139933 +v -0.006041 -0.046179 -0.353100 +v 0.042349 -0.058126 -0.074754 +v 0.088630 0.029596 -0.032856 +v 0.060798 0.031625 -0.351242 +v 0.050900 0.044557 -0.353980 +v 0.050900 -0.044824 -0.353980 +v 0.060798 -0.031891 -0.351242 +v 0.088625 -0.029867 -0.032878 +v 0.094751 -0.000134 -0.109988 +v 0.069972 -0.000133 -0.350335 +v 0.038932 -0.051877 0.020755 +v 0.092434 -0.000115 -0.031037 +v -0.016805 0.051585 0.020840 +v -0.017081 -0.051836 0.019069 +v -0.038098 0.039358 -0.331344 +v -0.001230 -0.023728 -0.438277 +v -0.002300 0.024724 -0.439154 +v -0.041639 0.011187 -0.118129 +# 27 vertices, 0 vertices normals + +f 1 6 5 +f 8 10 7 +f 9 1 5 +f 1 9 22 +f 9 27 22 +f 21 17 18 +f 14 6 2 +f 14 2 12 +f 21 18 12 +f 6 1 22 +f 3 11 4 +f 3 23 7 +f 10 3 7 +f 11 3 10 +f 4 17 20 +f 21 20 17 +f 13 26 14 +f 24 5 26 +f 24 9 5 +f 21 12 6 +f 6 12 2 +f 3 4 20 +f 20 6 22 +f 15 17 4 +f 11 15 4 +f 5 6 14 +f 14 26 5 +f 7 23 27 +f 27 8 7 +f 26 8 24 +f 10 8 25 +f 19 25 26 +f 19 26 13 +f 20 23 3 +f 27 24 8 +f 9 24 27 +f 10 15 11 +f 25 15 10 +f 19 16 25 +f 16 15 25 +f 18 19 13 +f 12 18 13 +f 13 14 12 +f 15 16 17 +f 16 18 17 +f 16 19 18 +f 20 21 6 +f 27 23 22 +f 20 22 23 +f 25 8 26 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_scap.obj b/examples/Atlas/urdf/mesh/r_scap.obj new file mode 100644 index 0000000..ff67469 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_scap.obj @@ -0,0 +1,1067 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_scap.obj +# +# Vertices: 380 +# Faces: 671 +# +#### +v 0.049425 -0.000201 -0.027787 +v 0.049425 0.016688 -0.021211 +v 0.049425 0.025675 -0.004562 +v 0.049425 0.022554 0.014371 +v 0.049425 0.008786 0.026728 +v 0.049425 -0.009187 0.026728 +v 0.049425 -0.022956 0.014371 +v 0.049425 -0.026077 -0.004562 +v 0.049425 -0.017090 -0.021211 +v 0.061763 -0.000201 -0.027787 +v 0.061763 0.016688 -0.021211 +v 0.061763 0.025675 -0.004562 +v 0.061763 0.022554 0.014371 +v 0.061763 0.008786 0.026728 +v 0.061763 -0.009187 0.026728 +v 0.061763 -0.022956 0.014371 +v 0.061763 -0.026077 -0.004562 +v 0.061763 -0.017090 -0.021211 +v 0.061763 -0.000201 -0.019663 +v 0.061763 0.011806 -0.014988 +v 0.061763 0.018195 -0.003151 +v 0.061763 0.015977 0.010309 +v 0.061763 0.006188 0.019094 +v 0.061763 -0.006590 0.019094 +v 0.061763 -0.016378 0.010309 +v 0.061763 -0.018597 -0.003152 +v 0.061763 -0.012208 -0.014988 +v 0.054198 -0.000201 -0.022949 +v 0.054198 0.013781 -0.017506 +v 0.054198 0.021221 -0.003722 +v 0.054198 0.018637 0.011952 +v 0.054198 0.007239 0.022182 +v 0.054198 -0.007641 0.022182 +v 0.054198 -0.019039 0.011952 +v 0.054198 -0.021623 -0.003722 +v 0.054198 -0.014183 -0.017506 +v -0.077499 -0.017943 0.012666 +v -0.077499 -0.001376 0.023031 +v -0.077499 0.029056 0.058354 +v -0.077499 0.023476 -0.001917 +v -0.077499 0.013047 -0.018444 +v -0.077499 -0.006377 -0.020594 +v -0.077499 -0.020168 -0.006749 +v -0.077499 0.052433 0.044074 +v -0.077499 0.004232 0.020477 +v -0.070905 -0.017943 0.012666 +v -0.070905 -0.001376 0.023031 +v -0.070905 0.029056 0.058354 +v -0.070905 0.023476 -0.001917 +v -0.070905 0.013047 -0.018444 +v -0.070905 -0.006377 -0.020594 +v -0.070905 -0.020168 -0.006749 +v -0.070905 0.052433 0.044074 +v -0.070905 0.004232 0.020477 +v -0.087576 -0.017943 0.012666 +v -0.087576 -0.001376 0.023031 +v -0.087576 0.029056 0.058354 +v -0.087576 0.023476 -0.001917 +v -0.087576 0.013047 -0.018444 +v -0.087576 -0.006377 -0.020594 +v -0.087576 -0.020168 -0.006749 +v -0.087576 0.052433 0.044074 +v -0.087576 0.004232 0.020477 +v -0.082600 -0.017943 0.012666 +v -0.082600 -0.001376 0.023031 +v -0.082600 0.029056 0.058354 +v -0.082600 0.023476 -0.001917 +v -0.082600 0.013047 -0.018444 +v -0.082600 -0.006377 -0.020594 +v -0.082600 -0.020168 -0.006749 +v -0.082600 0.052433 0.044074 +v -0.082600 0.004232 0.020477 +v -0.062411 0.000450 0.015816 +v -0.062411 0.013276 0.009639 +v -0.062411 0.016444 -0.004240 +v -0.062411 0.007568 -0.015371 +v -0.062411 -0.006668 -0.015371 +v -0.062411 -0.015545 -0.004240 +v -0.062411 -0.012377 0.009639 +v -0.071203 0.000450 0.015816 +v -0.071203 0.013276 0.009639 +v -0.071203 0.016444 -0.004240 +v -0.071203 0.007568 -0.015371 +v -0.071203 -0.006668 -0.015371 +v -0.071203 -0.015545 -0.004240 +v -0.071203 -0.012377 0.009639 +v -0.082943 0.029056 0.058354 +v -0.082943 0.023476 -0.001917 +v -0.082943 0.052433 0.044074 +v -0.082943 0.004232 0.020477 +v -0.071154 0.004232 0.020477 +v -0.071154 0.029056 0.058354 +v -0.071154 0.052433 0.044073 +v -0.071154 0.023476 -0.001917 +v -0.076349 0.029056 0.058354 +v -0.076349 0.023476 -0.001917 +v -0.076349 0.052433 0.044074 +v -0.076349 0.004232 0.020477 +v -0.064560 0.004232 0.020477 +v -0.064560 0.029056 0.058354 +v -0.064560 0.052433 0.044074 +v -0.064560 0.023476 -0.001917 +v 0.084164 -0.061024 0.022426 +v 0.084164 -0.065817 0.024884 +v 0.084164 -0.070944 0.023233 +v 0.084164 -0.073401 0.018440 +v 0.084164 -0.071750 0.013313 +v 0.084164 -0.062500 0.002089 +v 0.084164 -0.057707 -0.000369 +v 0.084164 -0.052580 0.001283 +v 0.084164 -0.050122 0.006076 +v 0.084164 -0.051774 0.011203 +v 0.084164 -0.062500 0.002089 +v 0.071899 -0.061024 0.022426 +v 0.071899 -0.065817 0.024884 +v 0.071899 -0.070944 0.023233 +v 0.071899 -0.073401 0.018440 +v 0.071899 -0.071750 0.013313 +v 0.071899 -0.062500 0.002089 +v 0.071899 -0.057707 -0.000369 +v 0.071899 -0.052580 0.001283 +v 0.071899 -0.050122 0.006076 +v 0.071899 -0.051774 0.011203 +v 0.071899 -0.062500 0.002089 +v -0.077127 0.025872 -0.006258 +v -0.077127 0.025881 0.006476 +v -0.061876 0.025881 0.006476 +v -0.061876 0.025872 -0.006258 +v -0.077127 0.020616 -0.016777 +v -0.077127 0.020625 0.016995 +v -0.061876 0.020625 0.016995 +v -0.061876 0.020616 -0.016777 +v -0.077127 0.009512 -0.024906 +v -0.077127 0.009522 0.025124 +v -0.061876 0.009522 0.025124 +v -0.061876 0.009512 -0.024906 +v -0.077127 -0.000080 -0.028050 +v -0.077127 -0.000071 0.026848 +v -0.061876 -0.000071 0.026848 +v -0.061876 -0.000080 -0.028050 +v -0.077127 -0.011200 -0.033256 +v -0.077127 -0.011190 0.024417 +v -0.061876 -0.011190 0.024417 +v -0.061876 -0.011200 -0.033256 +v -0.077127 -0.023856 -0.039694 +v -0.077127 -0.023846 0.010915 +v -0.061876 -0.023846 0.010915 +v -0.061876 -0.023856 -0.039694 +v -0.076784 -0.032029 -0.045581 +v -0.076784 -0.032020 0.000781 +v -0.062155 -0.032020 0.000781 +v -0.062155 -0.032029 -0.045581 +v -0.076784 -0.053631 -0.045581 +v -0.076784 -0.053622 0.000781 +v -0.062155 -0.053622 0.000781 +v -0.062155 -0.053631 -0.045581 +v -0.076784 -0.067229 -0.045581 +v -0.076784 -0.067220 0.014357 +v -0.062155 -0.067220 0.014357 +v -0.062155 -0.067229 -0.045581 +v -0.076784 -0.092889 -0.045581 +v -0.076784 -0.090253 0.014357 +v -0.062155 -0.090253 0.014357 +v -0.062155 -0.092889 -0.045581 +v -0.081892 -0.090340 -0.043657 +v -0.081892 -0.090331 0.012433 +v -0.058294 -0.090331 0.012433 +v -0.058294 -0.090340 -0.043657 +v -0.058294 -0.146978 -0.043657 +v -0.081892 -0.146978 -0.043657 +v -0.058294 -0.146968 0.012433 +v -0.081892 -0.146968 0.012433 +v -0.058294 -0.153265 -0.036057 +v -0.081892 -0.153265 -0.036057 +v -0.058294 -0.153256 0.004833 +v -0.081892 -0.153256 0.004833 +v -0.046757 -0.138288 -0.052159 +v -0.052272 -0.146634 -0.043757 +v -0.081892 -0.146634 -0.043757 +v -0.081892 -0.141767 -0.048678 +v -0.078537 -0.137041 -0.053386 +v -0.071867 -0.132860 -0.057565 +v -0.066103 -0.132860 -0.057565 +v -0.060976 -0.134506 -0.055914 +v -0.055857 -0.138288 -0.052159 +v -0.046757 -0.115146 -0.052159 +v -0.052272 -0.115191 -0.043757 +v -0.081892 -0.088348 -0.043757 +v -0.081892 -0.088579 -0.048678 +v -0.078537 -0.092165 -0.053386 +v -0.071867 -0.096518 -0.057565 +v -0.066103 -0.096518 -0.057565 +v -0.060976 -0.098164 -0.055914 +v -0.055857 -0.093413 -0.052159 +v -0.034962 -0.115031 -0.043716 +v -0.034960 -0.114985 -0.052117 +v -0.034960 -0.056851 -0.052117 +v -0.034962 -0.058683 -0.044339 +v -0.053101 -0.058843 -0.044380 +v -0.081892 -0.036796 -0.043757 +v -0.081892 -0.042046 -0.048678 +v -0.078537 -0.048495 -0.053386 +v -0.055857 -0.057297 -0.052159 +v -0.046757 -0.057012 -0.052159 +v 0.034650 -0.114363 -0.045705 +v 0.009606 -0.114363 -0.063900 +v 0.009606 -0.062710 -0.063900 +v 0.034650 -0.062710 -0.045705 +v -0.021350 -0.114363 -0.063900 +v -0.021350 -0.062710 -0.063900 +v -0.046395 -0.114363 -0.045705 +v -0.046395 -0.062710 -0.045705 +v -0.046395 -0.114363 0.013178 +v -0.021350 -0.114363 0.031374 +v -0.021350 -0.062710 0.031374 +v -0.046395 -0.062710 0.013178 +v 0.009606 -0.114363 0.031374 +v 0.009606 -0.062710 0.031374 +v 0.034650 -0.114363 0.013178 +v 0.034650 -0.062710 0.013178 +v 0.044216 -0.114363 -0.016263 +v 0.050125 -0.121191 -0.016263 +v 0.039431 -0.121191 -0.049178 +v 0.011432 -0.121191 -0.069520 +v -0.023176 -0.121191 -0.069520 +v -0.051175 -0.121191 -0.049178 +v -0.055961 -0.114363 -0.016263 +v -0.061870 -0.121191 -0.016263 +v -0.051175 -0.121191 0.016651 +v -0.023176 -0.121191 0.036994 +v 0.011432 -0.121191 0.036994 +v 0.039431 -0.121191 0.016651 +v 0.050125 -0.171223 -0.016263 +v 0.039431 -0.171223 -0.049178 +v 0.011432 -0.171223 -0.069520 +v -0.023176 -0.171223 -0.069520 +v -0.051175 -0.171223 -0.049178 +v -0.061870 -0.171223 -0.016263 +v -0.051175 -0.171223 0.016651 +v -0.023176 -0.171223 0.036994 +v 0.011432 -0.171223 0.036994 +v 0.039431 -0.171223 0.016651 +v 0.044216 -0.062710 -0.016263 +v 0.028467 -0.062710 -0.041212 +v 0.036573 -0.062710 -0.016263 +v 0.007244 -0.062710 -0.056631 +v -0.018989 -0.062710 -0.056631 +v -0.040211 -0.062710 -0.041212 +v -0.055961 -0.062710 -0.016263 +v -0.048318 -0.062710 -0.016263 +v -0.040211 -0.062710 0.008685 +v -0.018989 -0.062710 0.024105 +v 0.007244 -0.062710 0.024105 +v 0.028467 -0.062710 0.008685 +v 0.028467 -0.115585 -0.041212 +v 0.036573 -0.115585 -0.016263 +v 0.007244 -0.115585 -0.056631 +v -0.018989 -0.115585 -0.056631 +v -0.040211 -0.115585 -0.041212 +v -0.048318 -0.115585 -0.016263 +v -0.040211 -0.115585 0.008685 +v -0.018989 -0.115585 0.024105 +v 0.007244 -0.115585 0.024105 +v 0.028467 -0.115585 0.008685 +v 0.045612 -0.171223 -0.016263 +v 0.035779 -0.171223 -0.046525 +v 0.010037 -0.171223 -0.065228 +v -0.021782 -0.171223 -0.065228 +v -0.047524 -0.171223 -0.046525 +v -0.057356 -0.171223 -0.016263 +v -0.047524 -0.171223 0.013998 +v -0.021782 -0.171223 0.032701 +v 0.010037 -0.171223 0.032701 +v 0.035779 -0.171223 0.013998 +v 0.045612 -0.148358 -0.016263 +v 0.035779 -0.148358 -0.046525 +v 0.010037 -0.148358 -0.065228 +v -0.021782 -0.148358 -0.065228 +v -0.047524 -0.148358 -0.046525 +v -0.057356 -0.148358 -0.016263 +v -0.047524 -0.148358 0.013998 +v -0.021782 -0.148358 0.032701 +v 0.010037 -0.148358 0.032701 +v 0.035779 -0.148358 0.013998 +v 0.044216 -0.157043 -0.016263 +v 0.034650 -0.177516 -0.036677 +v 0.050103 -0.177516 -0.036677 +v 0.050108 -0.157043 -0.016263 +v 0.050103 -0.062710 -0.045705 +v 0.050103 -0.114363 -0.045705 +v 0.050108 -0.062710 -0.016263 +v -0.061847 -0.114363 -0.045705 +v -0.061847 -0.062710 -0.045705 +v -0.046395 -0.128799 -0.045705 +v -0.055961 -0.128799 -0.016263 +v -0.061855 -0.128799 -0.016263 +v -0.061847 -0.128799 -0.045705 +v -0.061855 -0.062710 -0.016263 +v -0.046395 -0.128799 0.013178 +v -0.061847 -0.128799 0.013178 +v -0.061847 -0.062710 0.013178 +v -0.061847 -0.114363 0.013178 +v 0.050103 -0.114363 0.013178 +v 0.050103 -0.062710 0.013178 +v 0.034650 -0.136569 0.004151 +v 0.050103 -0.136569 0.004151 +v 0.050108 -0.114363 -0.016263 +v -0.061855 -0.114363 -0.016263 +v 0.034650 -0.128799 -0.045705 +v 0.044216 -0.128799 -0.016263 +v 0.050103 -0.128799 -0.045705 +v 0.050108 -0.128799 -0.016263 +v 0.050103 -0.128799 0.013178 +v 0.034650 -0.128799 0.013178 +v 0.034650 -0.129879 -0.036586 +v 0.044216 -0.129879 -0.016263 +v 0.050103 -0.129879 -0.036586 +v 0.050108 -0.129879 -0.016263 +v 0.050103 -0.129879 0.004060 +v 0.034650 -0.129879 0.004060 +v 0.032110 -0.148311 -0.009163 +v 0.018967 -0.148311 0.013655 +v 0.018967 -0.223215 0.013655 +v 0.032110 -0.223215 -0.009163 +v -0.005769 -0.148311 0.022687 +v -0.005769 -0.223215 0.022687 +v -0.030523 -0.148311 0.013706 +v -0.030523 -0.223215 0.013706 +v -0.043713 -0.148311 -0.009086 +v -0.043713 -0.223215 -0.009086 +v -0.039167 -0.148311 -0.035024 +v -0.039167 -0.223215 -0.035024 +v -0.019012 -0.148311 -0.051971 +v -0.019012 -0.223215 -0.051971 +v 0.007321 -0.148311 -0.051998 +v 0.007321 -0.223215 -0.051998 +v 0.027511 -0.148311 -0.035092 +v 0.027511 -0.223215 -0.035092 +v -0.084650 -0.025737 -0.003523 +v -0.084650 -0.025742 -0.027701 +v -0.084650 -0.058385 -0.027701 +v -0.084650 -0.058380 -0.003523 +v -0.075935 -0.025737 -0.003523 +v -0.075935 -0.025742 -0.027701 +v -0.075935 -0.058385 -0.027701 +v -0.075935 -0.058380 -0.003523 +v 0.054353 0.033209 -0.006258 +v 0.054353 0.033219 0.006476 +v 0.069604 0.033219 0.006476 +v 0.069604 0.033209 -0.006258 +v 0.054353 0.027077 -0.021341 +v 0.054353 0.027087 0.021559 +v 0.069604 0.027087 0.021559 +v 0.069604 0.027077 -0.021341 +v 0.054353 0.009931 -0.045631 +v 0.054353 0.009941 0.032754 +v 0.069604 0.009941 0.032754 +v 0.069604 0.009931 -0.045631 +v 0.054353 -0.010623 -0.045631 +v 0.054353 -0.010614 0.032754 +v 0.069604 -0.010614 0.032754 +v 0.069604 -0.010623 -0.045631 +v 0.054353 -0.025120 -0.045631 +v 0.054353 -0.025111 0.024367 +v 0.069604 -0.025111 0.024367 +v 0.069604 -0.025120 -0.045631 +v 0.054353 -0.132848 -0.045631 +v 0.054353 -0.132839 0.024367 +v 0.069604 -0.132839 0.024367 +v 0.069604 -0.132848 -0.045631 +v 0.054353 -0.155779 -0.029458 +v 0.054353 -0.155769 0.008194 +v 0.069604 -0.155769 0.008194 +v 0.069604 -0.155779 -0.029458 +v 0.072767 -0.025120 -0.045631 +v 0.072767 -0.025111 0.024367 +v 0.072767 -0.132839 0.024367 +v 0.072767 -0.155769 0.008194 +v 0.072767 -0.155779 -0.029458 +v 0.072767 -0.132848 -0.045631 +# 380 vertices, 0 vertices normals + +f 1 2 11 +f 11 10 1 +f 2 3 12 +f 12 11 2 +f 3 4 13 +f 13 12 3 +f 4 5 14 +f 14 13 4 +f 5 6 15 +f 15 14 5 +f 6 7 16 +f 16 15 6 +f 7 8 17 +f 17 16 7 +f 8 9 18 +f 18 17 8 +f 9 1 10 +f 10 18 9 +f 8 7 6 +f 6 2 8 +f 6 5 4 +f 4 2 6 +f 4 3 2 +f 8 2 1 +f 1 9 8 +f 29 30 31 +f 31 35 29 +f 31 32 33 +f 33 35 31 +f 33 34 35 +f 29 35 36 +f 36 28 29 +f 10 11 20 +f 20 19 10 +f 11 12 21 +f 21 20 11 +f 12 13 22 +f 22 21 12 +f 13 14 23 +f 23 22 13 +f 14 15 24 +f 24 23 14 +f 15 16 25 +f 25 24 15 +f 16 17 26 +f 26 25 16 +f 17 18 27 +f 27 26 17 +f 18 10 19 +f 19 27 18 +f 19 20 29 +f 29 28 19 +f 20 21 30 +f 30 29 20 +f 21 22 31 +f 31 30 21 +f 22 23 32 +f 32 31 22 +f 23 24 33 +f 33 32 23 +f 24 25 34 +f 34 33 24 +f 25 26 35 +f 35 34 25 +f 26 27 36 +f 36 35 26 +f 27 19 28 +f 28 36 27 +f 40 41 42 +f 42 43 40 +f 43 37 38 +f 38 40 43 +f 40 38 45 +f 44 40 45 +f 45 39 44 +f 51 50 49 +f 49 52 51 +f 49 54 47 +f 47 52 49 +f 47 46 52 +f 54 49 53 +f 53 48 54 +f 47 54 45 +f 45 38 47 +f 49 50 41 +f 41 40 49 +f 50 51 42 +f 42 41 50 +f 51 52 43 +f 43 42 51 +f 46 47 38 +f 38 37 46 +f 52 46 37 +f 37 43 52 +f 54 48 39 +f 39 45 54 +f 48 53 44 +f 44 39 48 +f 53 49 40 +f 40 44 53 +f 58 59 60 +f 60 61 58 +f 61 55 56 +f 56 58 61 +f 58 56 63 +f 62 58 63 +f 63 57 62 +f 69 68 67 +f 67 70 69 +f 67 72 65 +f 65 70 67 +f 65 64 70 +f 72 67 71 +f 71 66 72 +f 65 72 63 +f 63 56 65 +f 67 68 59 +f 59 58 67 +f 68 69 60 +f 60 59 68 +f 69 70 61 +f 61 60 69 +f 64 65 56 +f 56 55 64 +f 70 64 55 +f 55 61 70 +f 72 66 57 +f 57 63 72 +f 66 71 62 +f 62 57 66 +f 71 67 58 +f 58 62 71 +f 73 74 81 +f 81 80 73 +f 74 75 82 +f 82 81 74 +f 75 76 83 +f 83 82 75 +f 76 77 84 +f 84 83 76 +f 77 78 85 +f 85 84 77 +f 78 79 86 +f 86 85 78 +f 79 73 80 +f 80 86 79 +f 78 77 76 +f 76 73 78 +f 76 75 74 +f 74 73 76 +f 79 78 73 +f 81 82 83 +f 83 86 81 +f 83 84 85 +f 85 86 83 +f 80 81 86 +f 89 88 90 +f 90 87 89 +f 93 94 91 +f 91 92 93 +f 98 96 97 +f 97 95 98 +f 99 102 101 +f 101 100 99 +f 98 95 87 +f 87 90 98 +f 95 97 89 +f 89 87 95 +f 97 96 88 +f 88 89 97 +f 96 98 90 +f 90 88 96 +f 99 100 92 +f 92 91 99 +f 100 101 93 +f 93 92 100 +f 101 102 94 +f 94 93 101 +f 102 99 91 +f 91 94 102 +f 107 104 105 +f 105 106 107 +f 103 104 107 +f 111 112 109 +f 109 110 111 +f 112 113 108 +f 108 109 112 +f 107 113 112 +f 112 103 107 +f 114 115 104 +f 104 103 114 +f 115 116 105 +f 105 104 115 +f 116 117 106 +f 106 105 116 +f 117 118 107 +f 107 106 117 +f 119 120 109 +f 109 108 119 +f 120 121 110 +f 110 109 120 +f 121 122 111 +f 111 110 121 +f 122 123 112 +f 112 111 122 +f 124 119 108 +f 108 113 124 +f 123 114 103 +f 103 112 123 +f 118 124 113 +f 113 107 118 +f 128 125 126 +f 126 127 128 +f 129 130 126 +f 126 125 129 +f 130 131 127 +f 127 126 130 +f 131 132 128 +f 128 127 131 +f 132 129 125 +f 125 128 132 +f 133 134 130 +f 130 129 133 +f 134 135 131 +f 131 130 134 +f 135 136 132 +f 132 131 135 +f 136 133 129 +f 129 132 136 +f 137 138 134 +f 134 133 137 +f 138 139 135 +f 135 134 138 +f 139 140 136 +f 136 135 139 +f 140 137 133 +f 133 136 140 +f 141 142 138 +f 138 137 141 +f 142 143 139 +f 139 138 142 +f 143 144 140 +f 140 139 143 +f 144 141 137 +f 137 140 144 +f 145 146 142 +f 142 141 145 +f 146 147 143 +f 143 142 146 +f 147 148 144 +f 144 143 147 +f 148 145 141 +f 141 144 148 +f 149 150 146 +f 146 145 149 +f 150 151 147 +f 147 146 150 +f 151 152 148 +f 148 147 151 +f 152 149 145 +f 145 148 152 +f 153 154 150 +f 150 149 153 +f 154 155 151 +f 151 150 154 +f 155 156 152 +f 152 151 155 +f 156 153 149 +f 149 152 156 +f 157 158 154 +f 154 153 157 +f 158 159 155 +f 155 154 158 +f 159 160 156 +f 156 155 159 +f 160 157 153 +f 153 156 160 +f 161 162 158 +f 158 157 161 +f 162 163 159 +f 159 158 162 +f 163 164 160 +f 160 159 163 +f 164 161 157 +f 157 160 164 +f 162 161 164 +f 164 163 162 +f 166 167 168 +f 168 165 166 +f 169 170 165 +f 165 168 169 +f 171 169 168 +f 168 167 171 +f 172 171 167 +f 167 166 172 +f 170 172 166 +f 166 165 170 +f 173 174 170 +f 170 169 173 +f 175 173 169 +f 169 171 175 +f 176 175 171 +f 171 172 176 +f 174 176 172 +f 172 170 174 +f 174 173 175 +f 175 176 174 +f 180 181 178 +f 178 179 180 +f 182 183 178 +f 178 181 182 +f 184 185 178 +f 178 183 184 +f 177 178 185 +f 186 187 178 +f 178 177 186 +f 187 188 179 +f 179 178 187 +f 188 189 180 +f 180 179 188 +f 189 190 181 +f 181 180 189 +f 191 192 183 +f 183 182 191 +f 192 193 184 +f 184 183 192 +f 194 186 177 +f 177 185 194 +f 190 191 182 +f 182 181 190 +f 193 194 185 +f 185 184 193 +f 197 198 195 +f 195 196 197 +f 199 200 188 +f 188 187 199 +f 200 201 189 +f 189 188 200 +f 201 202 190 +f 190 189 201 +f 203 204 186 +f 186 194 203 +f 203 194 190 +f 190 202 203 +f 192 190 194 +f 194 193 192 +f 191 190 192 +f 196 195 187 +f 187 186 196 +f 197 196 186 +f 186 204 197 +f 198 197 204 +f 204 199 198 +f 195 198 199 +f 199 187 195 +f 201 199 203 +f 203 202 201 +f 201 200 199 +f 204 203 199 +f 205 206 207 +f 207 208 205 +f 206 209 210 +f 210 207 206 +f 209 211 212 +f 212 210 209 +f 213 214 215 +f 215 216 213 +f 214 217 218 +f 218 215 214 +f 217 219 220 +f 220 218 217 +f 205 221 222 +f 222 223 205 +f 206 205 223 +f 223 224 206 +f 209 206 224 +f 224 225 209 +f 211 209 225 +f 225 226 211 +f 227 211 226 +f 226 228 227 +f 213 227 228 +f 228 229 213 +f 214 213 229 +f 229 230 214 +f 217 214 230 +f 230 231 217 +f 219 217 231 +f 231 232 219 +f 221 219 232 +f 232 222 221 +f 223 222 233 +f 233 234 223 +f 224 223 234 +f 234 235 224 +f 225 224 235 +f 235 236 225 +f 226 225 236 +f 236 237 226 +f 228 226 237 +f 237 238 228 +f 229 228 238 +f 238 239 229 +f 230 229 239 +f 239 240 230 +f 231 230 240 +f 240 241 231 +f 232 231 241 +f 241 242 232 +f 222 232 242 +f 242 233 222 +f 244 245 243 +f 243 208 244 +f 246 244 208 +f 208 207 246 +f 247 246 207 +f 207 210 247 +f 248 247 210 +f 210 212 248 +f 250 248 212 +f 212 249 250 +f 251 250 249 +f 249 216 251 +f 252 251 216 +f 216 215 252 +f 253 252 215 +f 215 218 253 +f 254 253 218 +f 218 220 254 +f 245 254 220 +f 220 243 245 +f 255 256 245 +f 245 244 255 +f 257 255 244 +f 244 246 257 +f 258 257 246 +f 246 247 258 +f 259 258 247 +f 247 248 259 +f 260 259 248 +f 248 250 260 +f 261 260 250 +f 250 251 261 +f 262 261 251 +f 251 252 262 +f 263 262 252 +f 252 253 263 +f 264 263 253 +f 253 254 264 +f 256 264 254 +f 254 245 256 +f 259 256 257 +f 257 258 259 +f 261 256 259 +f 259 260 261 +f 263 256 261 +f 261 262 263 +f 263 264 256 +f 255 257 256 +f 265 266 234 +f 234 233 265 +f 266 267 235 +f 235 234 266 +f 267 268 236 +f 236 235 267 +f 268 269 237 +f 237 236 268 +f 269 270 238 +f 238 237 269 +f 270 271 239 +f 239 238 270 +f 271 272 240 +f 240 239 271 +f 272 273 241 +f 241 240 272 +f 273 274 242 +f 242 241 273 +f 274 265 233 +f 233 242 274 +f 275 276 266 +f 266 265 275 +f 276 277 267 +f 267 266 276 +f 277 278 268 +f 268 267 277 +f 278 279 269 +f 269 268 278 +f 279 280 270 +f 270 269 279 +f 280 281 271 +f 271 270 280 +f 281 282 272 +f 272 271 281 +f 282 283 273 +f 273 272 282 +f 283 284 274 +f 274 273 283 +f 284 275 265 +f 265 274 284 +f 287 288 285 +f 285 286 287 +f 289 290 205 +f 205 208 289 +f 291 289 208 +f 208 243 291 +f 292 293 212 +f 212 211 292 +f 296 297 294 +f 294 295 296 +f 293 298 249 +f 249 212 293 +f 300 296 295 +f 295 299 300 +f 301 302 213 +f 213 216 301 +f 298 301 216 +f 216 249 298 +f 303 304 220 +f 220 219 303 +f 288 306 305 +f 305 285 288 +f 304 291 243 +f 243 220 304 +f 304 307 289 +f 289 291 304 +f 304 303 307 +f 290 289 307 +f 301 292 308 +f 308 302 301 +f 298 293 292 +f 292 301 298 +f 309 310 221 +f 221 205 309 +f 311 309 205 +f 205 290 311 +f 312 311 290 +f 290 307 312 +f 313 312 307 +f 307 303 313 +f 314 313 303 +f 303 219 314 +f 310 314 219 +f 219 221 310 +f 295 294 211 +f 211 227 295 +f 299 295 227 +f 227 213 299 +f 300 299 213 +f 213 302 300 +f 296 300 302 +f 302 308 296 +f 297 296 308 +f 308 292 297 +f 294 297 292 +f 292 211 294 +f 315 316 310 +f 310 309 315 +f 317 315 309 +f 309 311 317 +f 318 317 311 +f 311 312 318 +f 319 318 312 +f 312 313 319 +f 320 319 313 +f 313 314 320 +f 316 320 314 +f 314 310 316 +f 286 285 316 +f 316 315 286 +f 287 286 315 +f 315 317 287 +f 288 287 317 +f 317 318 288 +f 306 288 318 +f 318 319 306 +f 305 306 319 +f 319 320 305 +f 285 305 320 +f 320 316 285 +f 323 324 321 +f 321 322 323 +f 326 323 322 +f 322 325 326 +f 328 326 325 +f 325 327 328 +f 330 328 327 +f 327 329 330 +f 332 330 329 +f 329 331 332 +f 334 332 331 +f 331 333 334 +f 336 334 333 +f 333 335 336 +f 338 336 335 +f 335 337 338 +f 324 338 337 +f 337 321 324 +f 341 342 339 +f 339 340 341 +f 343 344 340 +f 340 339 343 +f 344 345 341 +f 341 340 344 +f 345 346 342 +f 342 341 345 +f 346 343 339 +f 339 342 346 +f 350 347 348 +f 348 349 350 +f 351 352 348 +f 348 347 351 +f 352 353 349 +f 349 348 352 +f 353 354 350 +f 350 349 353 +f 354 351 347 +f 347 350 354 +f 355 356 352 +f 352 351 355 +f 356 357 353 +f 353 352 356 +f 357 358 354 +f 354 353 357 +f 358 355 351 +f 351 354 358 +f 359 360 356 +f 356 355 359 +f 360 361 357 +f 357 356 360 +f 361 362 358 +f 358 357 361 +f 362 359 355 +f 355 358 362 +f 363 364 360 +f 360 359 363 +f 364 365 361 +f 361 360 364 +f 365 366 362 +f 362 361 365 +f 366 363 359 +f 359 362 366 +f 367 368 364 +f 364 363 367 +f 368 369 365 +f 365 364 368 +f 377 380 375 +f 375 376 377 +f 370 367 363 +f 363 366 370 +f 371 372 368 +f 368 367 371 +f 372 373 369 +f 369 368 372 +f 378 379 380 +f 380 377 378 +f 374 371 367 +f 367 370 374 +f 372 371 374 +f 374 373 372 +f 376 375 366 +f 366 365 376 +f 377 376 365 +f 365 369 377 +f 378 377 369 +f 369 373 378 +f 379 378 373 +f 373 374 379 +f 380 379 374 +f 374 370 380 +f 375 380 370 +f 370 366 375 +# 671 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_scap_chull.obj b/examples/Atlas/urdf/mesh/r_scap_chull.obj new file mode 100644 index 0000000..2894e66 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_scap_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_scap_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.072767 -0.155769 0.008194 +v 0.072767 -0.155779 -0.029458 +v 0.072767 -0.132839 0.024367 +v 0.071123 0.008312 0.033228 +v 0.069735 0.032030 0.016006 +v -0.087833 0.019014 -0.018184 +v 0.071172 0.011995 -0.046262 +v 0.072767 -0.132848 -0.045631 +v 0.007800 -0.167106 -0.071695 +v -0.023176 -0.171223 0.036994 +v -0.064560 0.029056 0.058354 +v -0.087576 0.029056 0.058354 +v 0.011432 -0.171223 0.036994 +v -0.064561 0.052433 0.044074 +v -0.087576 0.052433 0.044074 +v -0.080849 -0.048098 -0.052932 +v -0.082157 -0.151593 -0.042784 +v 0.087512 -0.060454 0.019807 +v -0.005239 -0.064393 -0.065714 +v 0.069390 0.026546 -0.024023 +v -0.082331 -0.150240 0.011210 +v 0.016816 -0.224838 -0.046365 +v 0.030165 -0.223115 0.006748 +v -0.043713 -0.223215 -0.009086 +v -0.032759 -0.223457 -0.044123 +v -0.020119 -0.224449 0.020600 +v -0.033510 -0.158027 -0.069712 +# 27 vertices, 0 vertices normals + +f 7 8 18 +f 13 3 23 +f 3 1 23 +f 4 3 13 +f 11 4 13 +f 4 5 18 +f 25 27 17 +f 22 2 8 +f 2 22 23 +f 2 23 1 +f 10 21 12 +f 26 21 10 +f 1 3 18 +f 4 14 5 +f 14 4 11 +f 16 6 17 +f 20 15 6 +f 22 27 25 +f 22 9 27 +f 8 9 22 +f 2 18 8 +f 26 24 21 +f 24 17 21 +f 26 10 13 +f 26 13 23 +f 18 20 7 +f 18 5 20 +f 18 2 1 +f 18 3 4 +f 17 6 21 +f 27 19 16 +f 19 9 7 +f 7 16 19 +f 7 20 6 +f 5 14 20 +f 20 14 15 +f 17 24 25 +f 16 7 6 +f 7 9 8 +f 12 11 10 +f 10 11 13 +f 14 11 12 +f 12 15 14 +f 17 27 16 +f 19 27 9 +f 6 12 21 +f 6 15 12 +f 25 23 22 +f 25 24 26 +f 25 26 23 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_talus.obj b/examples/Atlas/urdf/mesh/r_talus.obj new file mode 100644 index 0000000..c826f21 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_talus.obj @@ -0,0 +1,92 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_talus.obj +# +# Vertices: 28 +# Faces: 48 +# +#### +v 0.006590 0.015904 -0.008474 +v 0.006590 -0.016747 -0.008474 +v 0.010622 -0.016747 -0.000100 +v 0.010622 0.015904 -0.000100 +v -0.002471 0.015904 -0.010542 +v -0.002471 -0.016747 -0.010542 +v -0.009737 0.015904 -0.004747 +v -0.009737 -0.016747 -0.004747 +v -0.009737 0.015904 0.004546 +v -0.009737 -0.016747 0.004546 +v -0.002471 0.015904 0.010341 +v -0.002471 -0.016747 0.010341 +v 0.006590 0.015904 0.008273 +v 0.006590 -0.016747 0.008273 +v -0.016413 0.006858 -0.009229 +v 0.016238 0.006858 -0.009229 +v 0.016238 0.011254 -0.000100 +v -0.016413 0.011254 -0.000100 +v -0.016413 -0.003020 -0.011484 +v 0.016238 -0.003020 -0.011484 +v -0.016413 -0.010941 -0.005166 +v 0.016238 -0.010941 -0.005166 +v -0.016413 -0.010941 0.004966 +v 0.016238 -0.010941 0.004966 +v -0.016413 -0.003020 0.011283 +v 0.016238 -0.003020 0.011283 +v -0.016413 0.006858 0.009028 +v 0.016238 0.006858 0.009028 +# 28 vertices, 0 vertices normals + +f 1 4 3 +f 3 2 1 +f 5 1 2 +f 2 6 5 +f 7 5 6 +f 6 8 7 +f 9 7 8 +f 8 10 9 +f 11 9 10 +f 10 12 11 +f 13 11 12 +f 12 14 13 +f 4 13 14 +f 14 3 4 +f 4 1 5 +f 5 7 4 +f 9 11 4 +f 4 7 9 +f 11 13 4 +f 14 12 10 +f 10 8 14 +f 6 2 14 +f 14 8 6 +f 2 3 14 +f 15 18 17 +f 17 16 15 +f 19 15 16 +f 16 20 19 +f 21 19 20 +f 20 22 21 +f 23 21 22 +f 22 24 23 +f 25 23 24 +f 24 26 25 +f 27 25 26 +f 26 28 27 +f 18 27 28 +f 28 17 18 +f 18 15 19 +f 19 21 18 +f 23 25 18 +f 18 21 23 +f 25 27 18 +f 28 26 24 +f 24 22 28 +f 20 16 28 +f 28 22 20 +f 16 17 28 +# 48 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_uarm.obj b/examples/Atlas/urdf/mesh/r_uarm.obj new file mode 100644 index 0000000..92738e2 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_uarm.obj @@ -0,0 +1,850 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_uarm.obj +# +# Vertices: 288 +# Faces: 546 +# +#### +v -0.084211 -0.052625 -0.011234 +v -0.084211 -0.052625 0.015262 +v -0.061012 -0.052625 0.015262 +v -0.061012 -0.052625 -0.011234 +v -0.084211 -0.078062 -0.011234 +v -0.084211 -0.078062 0.015262 +v -0.061012 -0.078062 0.015262 +v -0.061012 -0.078062 -0.011234 +v -0.084211 -0.081802 -0.017792 +v -0.084211 -0.081802 0.015262 +v -0.061012 -0.081802 0.015262 +v -0.061012 -0.081802 -0.017792 +v -0.084211 -0.099434 -0.017792 +v -0.084211 -0.099434 0.015262 +v -0.061012 -0.099434 0.015262 +v -0.061012 -0.099434 -0.017792 +v -0.084211 -0.101791 -0.011309 +v -0.084211 -0.101791 0.021746 +v -0.061012 -0.101791 0.021746 +v -0.061012 -0.101791 -0.011309 +v -0.084211 -0.113765 -0.011309 +v -0.084211 -0.113765 0.029808 +v -0.061012 -0.113765 0.029808 +v -0.061012 -0.113765 -0.011309 +v -0.084211 -0.125340 -0.011309 +v -0.084211 -0.125340 0.029808 +v -0.061012 -0.125340 0.029808 +v -0.061012 -0.125340 -0.011309 +v -0.084211 -0.134949 -0.003750 +v -0.084211 -0.134949 0.022249 +v -0.061012 -0.134949 0.022249 +v -0.061011 -0.134949 -0.003750 +v -0.084211 -0.138958 0.004781 +v -0.084211 -0.138958 0.013718 +v -0.061012 -0.138958 0.013718 +v -0.061011 -0.138958 0.004781 +v 0.049445 -0.134926 -0.027504 +v 0.049445 -0.062304 -0.027504 +v 0.008088 -0.062304 -0.027504 +v 0.008088 -0.134926 -0.027504 +v 0.049445 -0.134926 -0.051026 +v 0.008088 -0.134926 -0.051026 +v 0.008088 -0.062304 -0.051026 +v 0.049445 -0.062304 -0.051026 +v 0.063266 -0.073239 0.026412 +v 0.063266 -0.050493 0.026412 +v -0.051266 -0.050493 0.026412 +v -0.051266 -0.073239 0.026412 +v 0.063266 -0.073239 -0.022065 +v -0.051266 -0.073239 -0.022065 +v -0.051266 -0.050493 -0.022065 +v 0.063266 -0.050493 -0.022065 +v 0.063266 -0.018069 0.026412 +v 0.063266 -0.018069 -0.022065 +v -0.072454 -0.018296 0.026412 +v -0.049131 -0.018069 0.026412 +v -0.049131 -0.018069 0.010307 +v -0.072454 -0.018296 0.010307 +v -0.049131 -0.018069 -0.022065 +v -0.049131 -0.018069 -0.008934 +v 0.063266 -0.018069 -0.008934 +v -0.072454 -0.018296 -0.022065 +v -0.072454 -0.018296 -0.008934 +v 0.063266 -0.018069 0.010308 +v -0.049131 -0.008178 0.010307 +v -0.069071 -0.009001 0.010307 +v -0.049131 -0.008178 -0.008934 +v 0.063266 -0.008178 -0.008934 +v -0.069071 -0.009001 -0.008934 +v 0.063266 -0.008178 0.010308 +v -0.083544 -0.048764 -0.022065 +v -0.083544 -0.048764 0.026412 +v 0.002234 -0.118950 0.056556 +v 0.002234 -0.088708 0.045549 +v -0.053266 -0.088708 0.045549 +v -0.053266 -0.118950 0.056556 +v 0.002234 -0.072616 0.017678 +v -0.053266 -0.072616 0.017678 +v 0.002234 -0.078205 -0.014016 +v -0.053266 -0.078205 -0.014016 +v 0.002234 -0.102858 -0.034703 +v -0.053266 -0.102858 -0.034703 +v 0.002234 -0.135041 -0.034703 +v -0.053266 -0.135041 -0.034703 +v 0.002234 -0.159694 -0.014016 +v -0.053266 -0.159694 -0.014016 +v 0.002234 -0.165283 0.017678 +v -0.053266 -0.165283 0.017678 +v 0.002234 -0.149191 0.045549 +v -0.053266 -0.149191 0.045549 +v -0.053266 -0.093840 0.039432 +v -0.053266 -0.118950 0.048571 +v -0.053266 -0.080480 0.016291 +v -0.053266 -0.085120 -0.010023 +v -0.053266 -0.105589 -0.027199 +v -0.053266 -0.132310 -0.027199 +v -0.053266 -0.152779 -0.010023 +v -0.053266 -0.157419 0.016291 +v -0.053266 -0.144059 0.039432 +v -0.007677 -0.093840 0.039432 +v -0.007677 -0.118950 0.048571 +v -0.007677 -0.080480 0.016291 +v -0.007677 -0.085120 -0.010023 +v -0.007677 -0.105589 -0.027199 +v -0.007677 -0.132310 -0.027199 +v -0.007677 -0.152779 -0.010023 +v -0.007677 -0.157419 0.016291 +v -0.007677 -0.144059 0.039432 +v 0.002234 -0.118950 0.047169 +v 0.002234 -0.094742 0.038358 +v 0.002234 -0.081861 0.016048 +v 0.002234 -0.086334 -0.009322 +v 0.002234 -0.106069 -0.025882 +v 0.002234 -0.131830 -0.025882 +v 0.002234 -0.151565 -0.009322 +v 0.002234 -0.156038 0.016048 +v 0.002234 -0.143157 0.038358 +v 0.050732 -0.118950 0.047169 +v 0.050732 -0.094742 0.038358 +v 0.050732 -0.081861 0.016048 +v 0.050732 -0.086334 -0.009322 +v 0.050732 -0.106069 -0.025882 +v 0.050732 -0.131830 -0.025882 +v 0.050732 -0.151565 -0.009322 +v 0.050732 -0.156038 0.016048 +v 0.050732 -0.143157 0.038358 +v 0.050732 -0.118950 0.038497 +v 0.050732 -0.100316 0.031715 +v 0.050732 -0.090401 0.014542 +v 0.050732 -0.093844 -0.004987 +v 0.050732 -0.109035 -0.017733 +v 0.050732 -0.128865 -0.017733 +v 0.050732 -0.144055 -0.004987 +v 0.050732 -0.147499 0.014542 +v 0.050732 -0.137584 0.031715 +v 0.002283 -0.118950 0.038497 +v 0.002283 -0.100316 0.031715 +v 0.002283 -0.090401 0.014542 +v 0.002283 -0.093844 -0.004987 +v 0.002283 -0.109035 -0.017733 +v 0.002283 -0.128865 -0.017733 +v 0.002283 -0.144055 -0.004987 +v 0.002283 -0.147499 0.014542 +v 0.002283 -0.137584 0.031715 +v 0.002283 -0.118950 0.023459 +v 0.002283 -0.109982 0.020195 +v 0.002283 -0.105211 0.011930 +v 0.002283 -0.106868 0.002533 +v 0.002283 -0.114178 -0.003601 +v 0.002283 -0.123721 -0.003601 +v 0.002283 -0.131031 0.002533 +v 0.002283 -0.132688 0.011930 +v 0.002283 -0.127917 0.020195 +v 0.041843 -0.118950 0.022574 +v 0.041843 -0.110551 0.019517 +v 0.041843 -0.106082 0.011777 +v 0.041843 -0.107634 0.002975 +v 0.041843 -0.114481 -0.002770 +v 0.041843 -0.123418 -0.002770 +v 0.041843 -0.130265 0.002975 +v 0.041843 -0.131817 0.011777 +v 0.041843 -0.127348 0.019517 +v -0.060175 -0.005632 0.000808 +v -0.052743 -0.005632 0.028543 +v -0.052743 0.011585 0.028543 +v -0.060175 0.011585 0.000808 +v -0.032439 -0.005632 0.048847 +v -0.032439 0.011585 0.048847 +v -0.004704 -0.005632 0.056278 +v -0.004704 0.011585 0.056278 +v 0.023031 -0.005632 0.048847 +v 0.023031 0.011585 0.048847 +v 0.043335 -0.005632 0.028543 +v 0.043335 0.011585 0.028543 +v 0.050767 -0.005632 0.000808 +v 0.050767 0.011585 0.000808 +v 0.043335 -0.005632 -0.026928 +v 0.043335 0.011585 -0.026928 +v 0.023031 -0.005632 -0.047231 +v 0.023031 0.011585 -0.047231 +v -0.004704 -0.005632 -0.054663 +v -0.004704 0.011585 -0.054663 +v -0.032439 -0.005632 -0.047231 +v -0.032439 0.011585 -0.047231 +v -0.052743 -0.005632 -0.026928 +v -0.052743 0.011585 -0.026928 +v -0.047746 0.011585 0.025658 +v -0.054404 0.011585 0.000808 +v -0.029554 0.011585 0.043849 +v -0.004704 0.011585 0.050508 +v 0.020146 0.011585 0.043849 +v 0.038338 0.011585 0.025658 +v 0.044996 0.011585 0.000808 +v 0.038338 0.011585 -0.024043 +v 0.020146 0.011585 -0.042234 +v -0.004704 0.011585 -0.048893 +v -0.029554 0.011585 -0.042234 +v -0.047746 0.011585 -0.024043 +v -0.047746 -0.005868 0.025658 +v -0.054404 -0.005868 0.000808 +v -0.029554 -0.005868 0.043849 +v -0.004704 -0.005868 0.050508 +v 0.020146 -0.005868 0.043849 +v 0.038338 -0.005868 0.025658 +v 0.044996 -0.005868 0.000808 +v 0.038338 -0.005868 -0.024043 +v 0.020146 -0.005868 -0.042234 +v -0.004704 -0.005868 -0.048893 +v -0.029554 -0.005868 -0.042234 +v -0.047746 -0.005868 -0.024043 +v -0.075039 -0.030906 0.000808 +v -0.054035 -0.030906 0.029029 +v -0.033185 -0.032063 0.050839 +v -0.004704 -0.019912 0.055462 +v 0.044627 -0.030906 0.029029 +v 0.061367 -0.030906 0.000808 +v 0.056208 -0.030906 -0.034360 +v 0.030463 -0.030906 -0.060104 +v -0.004704 -0.030906 -0.069527 +v -0.039871 -0.030906 -0.060104 +v -0.065616 -0.030906 -0.034360 +v -0.075039 -0.062737 0.000808 +v -0.054035 -0.062737 0.029029 +v -0.046131 -0.063778 0.038717 +v -0.004704 -0.063720 0.038747 +v 0.023777 -0.032063 0.050839 +v 0.036723 -0.063778 0.038717 +v 0.044627 -0.062737 0.029029 +v 0.061367 -0.062737 0.000808 +v 0.061168 -0.062737 -0.022662 +v 0.030463 -0.062737 -0.060104 +v -0.004704 -0.062737 -0.069527 +v -0.039871 -0.062737 -0.060104 +v -0.070576 -0.062737 -0.022662 +v -0.054035 -0.087588 0.029029 +v -0.051722 -0.087588 0.030624 +v -0.004704 -0.087588 0.030632 +v 0.042314 -0.087588 0.030624 +v 0.044627 -0.087588 0.029029 +v 0.061168 -0.086174 -0.022662 +v 0.030463 -0.096181 -0.060104 +v -0.004704 -0.063690 -0.069527 +v 0.011307 -0.079734 -0.063583 +v 0.020408 -0.103173 -0.056323 +v -0.004712 -0.109612 -0.052667 +v -0.020715 -0.079734 -0.063583 +v -0.029816 -0.112506 -0.052948 +v -0.044991 -0.112933 -0.056086 +v -0.070576 -0.088599 -0.022662 +v -0.071014 -0.062737 -0.000118 +v -0.071054 -0.031803 0.000195 +v -0.050889 -0.031024 0.026356 +v -0.050833 -0.062791 0.026421 +v -0.031602 -0.031568 0.047057 +v -0.044282 -0.063127 0.035082 +v -0.004830 -0.031853 0.046863 +v -0.004704 -0.062319 0.034862 +v 0.022238 -0.031602 0.047035 +v 0.034897 -0.063027 0.035089 +v 0.041344 -0.031244 0.026547 +v 0.041404 -0.062698 0.026447 +v 0.061689 -0.031911 0.000092 +v 0.061589 -0.062825 -0.000037 +v 0.052770 -0.031786 -0.016339 +v 0.057536 -0.062800 -0.016339 +v 0.037078 -0.031893 -0.042712 +v 0.037074 -0.062616 -0.042712 +v -0.016409 -0.031948 -0.036415 +v -0.016457 -0.062686 -0.036415 +v -0.037873 -0.031948 -0.036415 +v -0.037741 -0.062626 -0.036415 +v -0.062171 -0.031901 -0.016340 +v -0.066938 -0.062688 -0.016339 +v -0.051420 -0.087166 0.025860 +v -0.050291 -0.086646 0.026866 +v -0.004704 -0.086259 0.026722 +v 0.040685 -0.086983 0.026878 +v 0.042283 -0.087588 0.025629 +v 0.057974 -0.086174 -0.016339 +v 0.037148 -0.096181 -0.042712 +v 0.028757 -0.102266 -0.050013 +v 0.018648 -0.078953 -0.050013 +v -0.016548 -0.063285 -0.036415 +v -0.016409 -0.108229 -0.036415 +v -0.020249 -0.078884 -0.036415 +v -0.030388 -0.111101 -0.036415 +v -0.043510 -0.112311 -0.036415 +v -0.067296 -0.088599 -0.016339 +# 288 vertices, 0 vertices normals + +f 1 2 3 +f 3 4 1 +f 5 6 2 +f 2 1 5 +f 6 7 3 +f 3 2 6 +f 7 8 4 +f 4 3 7 +f 8 5 1 +f 1 4 8 +f 9 10 6 +f 6 5 9 +f 10 11 7 +f 7 6 10 +f 11 12 8 +f 8 7 11 +f 12 9 5 +f 5 8 12 +f 13 14 10 +f 10 9 13 +f 14 15 11 +f 11 10 14 +f 15 16 12 +f 12 11 15 +f 16 13 9 +f 9 12 16 +f 17 18 14 +f 14 13 17 +f 18 19 15 +f 15 14 18 +f 19 20 16 +f 16 15 19 +f 20 17 13 +f 13 16 20 +f 21 22 18 +f 18 17 21 +f 22 23 19 +f 19 18 22 +f 23 24 20 +f 20 19 23 +f 24 21 17 +f 17 20 24 +f 25 26 22 +f 22 21 25 +f 26 27 23 +f 23 22 26 +f 27 28 24 +f 24 23 27 +f 28 25 21 +f 21 24 28 +f 29 30 26 +f 26 25 29 +f 30 31 27 +f 27 26 30 +f 31 32 28 +f 28 27 31 +f 32 29 25 +f 25 28 32 +f 33 34 30 +f 30 29 33 +f 34 35 31 +f 31 30 34 +f 35 36 32 +f 32 31 35 +f 36 33 29 +f 29 32 36 +f 34 33 36 +f 36 35 34 +f 39 40 37 +f 37 38 39 +f 43 44 41 +f 41 42 43 +f 43 42 40 +f 40 39 43 +f 41 44 38 +f 38 37 41 +f 39 38 44 +f 44 43 39 +f 37 40 42 +f 42 41 37 +f 48 45 46 +f 46 47 48 +f 52 49 50 +f 50 51 52 +f 54 53 46 +f 46 52 54 +f 58 55 56 +f 56 57 58 +f 61 54 59 +f 59 60 61 +f 58 63 62 +f 62 55 58 +f 61 64 53 +f 53 54 61 +f 66 58 57 +f 57 65 66 +f 68 61 60 +f 60 67 68 +f 66 69 63 +f 63 58 66 +f 68 70 64 +f 64 61 68 +f 65 70 68 +f 68 67 65 +f 47 46 53 +f 53 56 47 +f 51 71 62 +f 62 59 51 +f 71 72 55 +f 55 62 71 +f 52 46 45 +f 45 49 52 +f 48 50 49 +f 49 45 48 +f 57 56 53 +f 53 64 57 +f 60 59 62 +f 62 63 60 +f 65 57 64 +f 64 70 65 +f 67 60 63 +f 63 69 67 +f 65 67 69 +f 69 66 65 +f 47 56 55 +f 55 72 47 +f 51 59 54 +f 54 52 51 +f 72 71 51 +f 51 47 72 +f 48 47 51 +f 51 50 48 +f 75 76 73 +f 73 74 75 +f 78 75 74 +f 74 77 78 +f 80 78 77 +f 77 79 80 +f 82 80 79 +f 79 81 82 +f 84 82 81 +f 81 83 84 +f 86 84 83 +f 83 85 86 +f 88 86 85 +f 85 87 88 +f 90 88 87 +f 87 89 90 +f 76 90 89 +f 89 73 76 +f 91 92 76 +f 76 75 91 +f 93 91 75 +f 75 78 93 +f 94 93 78 +f 78 80 94 +f 95 94 80 +f 80 82 95 +f 96 95 82 +f 82 84 96 +f 97 96 84 +f 84 86 97 +f 98 97 86 +f 86 88 98 +f 99 98 88 +f 88 90 99 +f 92 99 90 +f 90 76 92 +f 100 101 92 +f 92 91 100 +f 102 100 91 +f 91 93 102 +f 103 102 93 +f 93 94 103 +f 104 103 94 +f 94 95 104 +f 105 104 95 +f 95 96 105 +f 106 105 96 +f 96 97 106 +f 107 106 97 +f 97 98 107 +f 108 107 98 +f 98 99 108 +f 101 108 99 +f 99 92 101 +f 104 108 102 +f 102 103 104 +f 106 108 104 +f 104 105 106 +f 106 107 108 +f 101 100 102 +f 102 108 101 +f 109 110 74 +f 74 73 109 +f 110 111 77 +f 77 74 110 +f 111 112 79 +f 79 77 111 +f 112 113 81 +f 81 79 112 +f 113 114 83 +f 83 81 113 +f 114 115 85 +f 85 83 114 +f 115 116 87 +f 87 85 115 +f 116 117 89 +f 89 87 116 +f 117 109 73 +f 73 89 117 +f 118 119 110 +f 110 109 118 +f 119 120 111 +f 111 110 119 +f 120 121 112 +f 112 111 120 +f 121 122 113 +f 113 112 121 +f 122 123 114 +f 114 113 122 +f 123 124 115 +f 115 114 123 +f 124 125 116 +f 116 115 124 +f 125 126 117 +f 117 116 125 +f 126 118 109 +f 109 117 126 +f 127 128 119 +f 119 118 127 +f 128 129 120 +f 120 119 128 +f 129 130 121 +f 121 120 129 +f 130 131 122 +f 122 121 130 +f 131 132 123 +f 123 122 131 +f 132 133 124 +f 124 123 132 +f 133 134 125 +f 125 124 133 +f 134 135 126 +f 126 125 134 +f 135 127 118 +f 118 126 135 +f 136 137 128 +f 128 127 136 +f 137 138 129 +f 129 128 137 +f 138 139 130 +f 130 129 138 +f 139 140 131 +f 131 130 139 +f 140 141 132 +f 132 131 140 +f 141 142 133 +f 133 132 141 +f 142 143 134 +f 134 133 142 +f 143 144 135 +f 135 134 143 +f 144 136 127 +f 127 135 144 +f 145 146 137 +f 137 136 145 +f 146 147 138 +f 138 137 146 +f 147 148 139 +f 139 138 147 +f 148 149 140 +f 140 139 148 +f 149 150 141 +f 141 140 149 +f 150 151 142 +f 142 141 150 +f 151 152 143 +f 143 142 151 +f 152 153 144 +f 144 143 152 +f 153 145 136 +f 136 144 153 +f 154 155 146 +f 146 145 154 +f 155 156 147 +f 147 146 155 +f 156 157 148 +f 148 147 156 +f 157 158 149 +f 149 148 157 +f 158 159 150 +f 150 149 158 +f 159 160 151 +f 151 150 159 +f 160 161 152 +f 152 151 160 +f 161 162 153 +f 153 152 161 +f 162 154 145 +f 145 153 162 +f 160 156 162 +f 162 161 160 +f 158 156 160 +f 160 159 158 +f 158 157 156 +f 155 154 162 +f 162 156 155 +f 163 164 165 +f 165 166 163 +f 164 167 168 +f 168 165 164 +f 167 169 170 +f 170 168 167 +f 169 171 172 +f 172 170 169 +f 171 173 174 +f 174 172 171 +f 173 175 176 +f 176 174 173 +f 175 177 178 +f 178 176 175 +f 177 179 180 +f 180 178 177 +f 179 181 182 +f 182 180 179 +f 181 183 184 +f 184 182 181 +f 183 185 186 +f 186 184 183 +f 185 163 166 +f 166 186 185 +f 166 165 187 +f 187 188 166 +f 165 168 189 +f 189 187 165 +f 168 170 190 +f 190 189 168 +f 170 172 191 +f 191 190 170 +f 172 174 192 +f 192 191 172 +f 174 176 193 +f 193 192 174 +f 176 178 194 +f 194 193 176 +f 178 180 195 +f 195 194 178 +f 180 182 196 +f 196 195 180 +f 182 184 197 +f 197 196 182 +f 184 186 198 +f 198 197 184 +f 186 166 188 +f 188 198 186 +f 188 187 199 +f 199 200 188 +f 187 189 201 +f 201 199 187 +f 189 190 202 +f 202 201 189 +f 190 191 203 +f 203 202 190 +f 191 192 204 +f 204 203 191 +f 192 193 205 +f 205 204 192 +f 193 194 206 +f 206 205 193 +f 194 195 207 +f 207 206 194 +f 195 196 208 +f 208 207 195 +f 196 197 209 +f 209 208 196 +f 197 198 210 +f 210 209 197 +f 198 188 200 +f 200 210 198 +f 200 207 209 +f 209 210 200 +f 201 203 200 +f 200 199 201 +f 201 202 203 +f 205 207 203 +f 203 204 205 +f 205 206 207 +f 200 203 207 +f 209 207 208 +f 164 163 211 +f 211 212 164 +f 167 164 212 +f 212 213 167 +f 169 167 213 +f 213 214 169 +f 175 173 215 +f 215 216 175 +f 177 175 216 +f 216 217 177 +f 179 177 217 +f 217 218 179 +f 181 179 218 +f 218 219 181 +f 183 181 219 +f 219 220 183 +f 185 183 220 +f 220 221 185 +f 163 185 221 +f 221 211 163 +f 212 211 222 +f 222 223 212 +f 213 212 223 +f 223 224 213 +f 214 213 224 +f 224 225 214 +f 226 214 225 +f 225 227 226 +f 215 226 227 +f 227 228 215 +f 216 215 228 +f 228 229 216 +f 217 216 229 +f 229 230 217 +f 218 217 230 +f 230 231 218 +f 219 218 231 +f 231 232 219 +f 220 219 232 +f 232 233 220 +f 221 220 233 +f 233 234 221 +f 211 221 234 +f 234 222 211 +f 224 223 235 +f 235 236 224 +f 225 224 236 +f 236 237 225 +f 227 225 237 +f 237 238 227 +f 228 227 238 +f 238 239 228 +f 231 230 240 +f 240 241 231 +f 242 243 244 +f 244 245 242 +f 246 242 245 +f 245 247 246 +f 234 233 248 +f 248 249 234 +f 232 231 243 +f 243 242 232 +f 231 241 244 +f 244 243 231 +f 248 233 246 +f 246 247 248 +f 233 232 242 +f 242 246 233 +f 250 251 252 +f 252 253 250 +f 253 252 254 +f 254 255 253 +f 255 254 256 +f 256 257 255 +f 257 256 258 +f 258 259 257 +f 259 258 260 +f 260 261 259 +f 261 260 262 +f 262 263 261 +f 263 262 264 +f 264 265 263 +f 265 264 266 +f 266 267 265 +f 267 266 268 +f 268 269 267 +f 269 268 270 +f 270 271 269 +f 271 270 272 +f 272 273 271 +f 273 272 251 +f 251 250 273 +f 274 253 255 +f 255 275 274 +f 275 255 257 +f 257 276 275 +f 276 257 259 +f 259 277 276 +f 277 259 261 +f 261 278 277 +f 279 265 267 +f 267 280 279 +f 281 282 283 +f 283 284 281 +f 284 283 285 +f 285 286 284 +f 287 271 273 +f 273 288 287 +f 282 267 269 +f 269 283 282 +f 281 280 267 +f 267 282 281 +f 285 271 287 +f 287 286 285 +f 283 269 271 +f 271 285 283 +f 223 222 250 +f 250 253 223 +f 229 228 261 +f 261 263 229 +f 230 229 263 +f 263 265 230 +f 222 234 273 +f 273 250 222 +f 235 223 253 +f 253 274 235 +f 236 235 274 +f 274 275 236 +f 237 236 275 +f 275 276 237 +f 238 237 276 +f 276 277 238 +f 239 238 277 +f 277 278 239 +f 228 239 278 +f 278 261 228 +f 240 230 265 +f 265 279 240 +f 241 240 279 +f 279 280 241 +f 245 244 281 +f 281 284 245 +f 247 245 284 +f 284 286 247 +f 249 248 287 +f 287 288 249 +f 234 249 288 +f 288 273 234 +f 244 241 280 +f 280 281 244 +f 248 247 286 +f 286 287 248 +f 171 169 214 +f 214 226 171 +f 171 226 215 +f 215 173 171 +# 546 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_uarm_chull.obj b/examples/Atlas/urdf/mesh/r_uarm_chull.obj new file mode 100644 index 0000000..4b722f9 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_uarm_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_uarm_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.050910 -0.158251 0.019838 +v -0.044991 -0.112933 -0.056086 +v 0.050700 -0.118881 0.047195 +v 0.002234 -0.118950 0.056556 +v -0.044478 -0.150136 0.048190 +v -0.053266 -0.118950 0.056556 +v -0.004704 -0.063690 -0.069527 +v -0.030124 -0.028808 -0.066731 +v -0.081017 -0.040777 -0.024375 +v -0.084071 -0.050041 0.026256 +v -0.054472 -0.159363 -0.014194 +v 0.008088 -0.134926 -0.051026 +v 0.049445 -0.134926 -0.051026 +v 0.044113 -0.046211 -0.056269 +v 0.030722 0.011613 0.044149 +v -0.004704 0.011585 0.056278 +v -0.032439 0.011585 0.048847 +v 0.014686 0.011926 -0.054366 +v -0.041171 0.011638 -0.040941 +v -0.058643 0.011538 0.023250 +v 0.063713 -0.003727 -0.015023 +v 0.063234 -0.073957 -0.022204 +v 0.064925 -0.049557 0.029374 +v -0.053266 -0.165283 0.017678 +v 0.000087 -0.167352 0.007759 +v -0.084203 -0.114878 -0.015979 +v -0.084287 -0.129736 0.030169 +# 27 vertices, 0 vertices normals + +f 11 26 2 +f 19 18 8 +f 9 19 8 +f 16 17 6 +f 10 6 17 +f 4 5 3 +f 4 16 6 +f 3 16 4 +f 1 22 23 +f 3 5 1 +f 1 23 3 +f 1 5 25 +f 9 8 2 +f 9 2 26 +f 27 5 6 +f 12 2 7 +f 12 7 13 +f 14 13 7 +f 8 7 2 +f 20 19 9 +f 1 25 13 +f 27 6 10 +f 11 2 12 +f 14 18 21 +f 14 8 18 +f 22 1 13 +f 3 15 16 +f 20 10 17 +f 15 23 21 +f 23 15 3 +f 5 27 24 +f 24 27 11 +f 10 20 9 +f 6 5 4 +f 10 9 26 +f 11 12 13 +f 11 13 25 +f 14 7 8 +f 17 16 15 +f 18 19 15 +f 21 18 15 +f 20 15 19 +f 15 20 17 +f 14 21 22 +f 13 14 22 +f 22 21 23 +f 24 11 25 +f 25 5 24 +f 27 10 26 +f 26 11 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_uglut.obj b/examples/Atlas/urdf/mesh/r_uglut.obj new file mode 100644 index 0000000..93246c2 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_uglut.obj @@ -0,0 +1,742 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_uglut.obj +# +# Vertices: 238 +# Faces: 488 +# +#### +v 0.033190 -0.017124 0.011995 +v 0.049145 -0.017124 0.011995 +v 0.049145 -0.020551 -0.003462 +v 0.039190 -0.020551 -0.003462 +v 0.049145 -0.012044 -0.016815 +v 0.039190 -0.012044 -0.016815 +v 0.049145 0.003414 -0.020242 +v 0.039190 0.003414 -0.020242 +v 0.049145 0.016767 -0.011735 +v 0.039190 0.016767 -0.011735 +v 0.049145 0.020194 0.003722 +v 0.039190 0.020194 0.003722 +v 0.040715 -0.005326 0.003734 +v 0.040715 -0.001270 0.006319 +v 0.039190 -0.003771 0.020502 +v 0.040715 0.006010 0.001221 +v 0.040715 0.004969 -0.003475 +v 0.040715 0.003426 0.005278 +v 0.039190 0.011687 0.017075 +v 0.047621 -0.001373 0.006907 +v 0.047621 -0.005815 0.004077 +v 0.049145 -0.003771 0.020502 +v 0.047621 -0.006955 -0.001065 +v 0.047621 -0.004125 -0.005507 +v 0.047621 0.001016 -0.006647 +v 0.047621 0.005459 -0.003817 +v 0.047621 0.006598 0.001325 +v 0.047621 0.003768 0.005767 +v 0.049145 0.011687 0.017075 +v 0.040715 0.000913 -0.006059 +v 0.040715 -0.003783 -0.005018 +v 0.040715 -0.006367 -0.000961 +v 0.036381 -0.002676 0.127511 +v 0.049145 -0.002676 0.127511 +v 0.049145 -0.012201 0.121443 +v 0.036381 -0.012201 0.121443 +v 0.049145 -0.014646 0.110416 +v 0.036381 -0.014646 0.110416 +v 0.036381 0.014176 0.104141 +v 0.049145 0.014176 0.104141 +v 0.049145 0.014420 0.115541 +v 0.036381 0.014420 0.115541 +v 0.049145 0.008351 0.125067 +v 0.036381 0.008351 0.125067 +v 0.037906 -0.006519 0.117464 +v 0.037906 -0.001471 0.120680 +v 0.037906 -0.007814 0.111621 +v 0.037906 -0.004598 0.106573 +v 0.036381 -0.008577 0.100890 +v 0.037906 0.001245 0.105278 +v 0.036381 0.002449 0.098446 +v 0.037906 0.006293 0.108493 +v 0.037906 0.007588 0.114337 +v 0.037906 0.004372 0.119384 +v 0.047621 -0.001600 0.121411 +v 0.047621 -0.007127 0.117890 +v 0.047621 -0.008546 0.111492 +v 0.047621 -0.005024 0.105965 +v 0.049145 -0.008577 0.100890 +v 0.047621 0.001374 0.104546 +v 0.049145 0.002449 0.098446 +v 0.047621 0.006901 0.108067 +v 0.047621 0.008320 0.114466 +v 0.047621 0.004798 0.119993 +v 0.030808 -0.018546 0.071550 +v 0.049145 -0.018545 0.071550 +v 0.049145 -0.006583 0.067529 +v 0.049145 0.006283 0.064677 +v 0.049145 0.016673 0.062467 +v 0.030808 0.016673 0.062467 +v 0.030808 0.006283 0.064677 +v 0.030808 -0.006583 0.067529 +v 0.011414 -0.017415 -0.019670 +v 0.020040 -0.003875 -0.019670 +v 0.020040 -0.003875 -0.040319 +v 0.011414 -0.017415 -0.040319 +v -0.004260 -0.020890 -0.019670 +v -0.004260 -0.020890 -0.040319 +v -0.017800 -0.012264 -0.019670 +v -0.017800 -0.012264 -0.040319 +v -0.021275 0.003410 -0.019670 +v -0.021275 0.003410 -0.040319 +v -0.012649 0.016950 -0.019670 +v -0.012649 0.016950 -0.040319 +v 0.003025 0.020425 -0.019670 +v 0.003025 0.020425 -0.040319 +v 0.016565 0.011799 -0.019670 +v 0.016565 0.011799 -0.040319 +v 0.020040 -0.003875 -0.012050 +v 0.011414 -0.017415 -0.012050 +v -0.004260 -0.020890 -0.012050 +v -0.017800 -0.012264 -0.012050 +v -0.021275 0.003410 -0.012050 +v -0.012649 0.016950 -0.012050 +v 0.003025 0.020425 -0.012050 +v 0.016565 0.011799 -0.012050 +v 0.010271 -0.002152 -0.040319 +v 0.005724 -0.009289 -0.040319 +v 0.005724 -0.009289 -0.012050 +v 0.010271 -0.002152 -0.012050 +v -0.002537 -0.011120 -0.040319 +v -0.002537 -0.011120 -0.012050 +v -0.009674 -0.006574 -0.040319 +v -0.009674 -0.006574 -0.012050 +v -0.011505 0.001687 -0.040319 +v -0.011505 0.001687 -0.012050 +v -0.006959 0.008824 -0.040319 +v -0.006959 0.008824 -0.012050 +v 0.001303 0.010656 -0.040319 +v 0.001303 0.010656 -0.012050 +v 0.008439 0.006109 -0.040319 +v 0.008439 0.006109 -0.012050 +v -0.033234 -0.020551 -0.003462 +v -0.033234 -0.017124 0.011995 +v -0.014469 -0.017124 0.011995 +v -0.020469 -0.020551 -0.003462 +v -0.033234 -0.012044 -0.016815 +v -0.020469 -0.012044 -0.016815 +v -0.033234 0.003414 -0.020242 +v -0.020469 0.003414 -0.020242 +v -0.033234 0.016767 -0.011735 +v -0.020469 0.016767 -0.011735 +v -0.033234 0.020194 0.003722 +v -0.020469 0.020194 0.003722 +v -0.020469 -0.003771 0.020502 +v -0.021994 -0.001270 0.006319 +v -0.021994 -0.005326 0.003734 +v -0.021994 0.004969 -0.003475 +v -0.021994 0.006010 0.001221 +v -0.021994 0.003426 0.005278 +v -0.020469 0.011687 0.017075 +v -0.031709 -0.005815 0.004077 +v -0.031709 -0.001373 0.006907 +v -0.033234 -0.003771 0.020502 +v -0.031709 -0.006955 -0.001065 +v -0.031709 -0.004125 -0.005507 +v -0.031709 0.001016 -0.006647 +v -0.031709 0.005459 -0.003817 +v -0.031709 0.006598 0.001325 +v -0.033234 0.011687 0.017075 +v -0.031709 0.003768 0.005767 +v -0.021994 0.000913 -0.006059 +v -0.021994 -0.003783 -0.005018 +v -0.021994 -0.006367 -0.000961 +v -0.033234 -0.012201 0.121443 +v -0.033234 -0.002676 0.127511 +v -0.020469 -0.002676 0.127511 +v -0.020469 -0.012201 0.121443 +v -0.033234 -0.014646 0.110416 +v -0.020469 -0.014646 0.110416 +v -0.033234 0.014420 0.115541 +v -0.033234 0.014176 0.104141 +v -0.020469 0.014176 0.104141 +v -0.020469 0.014420 0.115541 +v -0.033234 0.008351 0.125067 +v -0.020469 0.008351 0.125067 +v -0.021994 -0.001471 0.120680 +v -0.021994 -0.006519 0.117464 +v -0.021994 -0.007814 0.111621 +v -0.021994 -0.004598 0.106573 +v -0.020469 -0.008577 0.100890 +v -0.021994 0.001245 0.105278 +v -0.020469 0.002449 0.098446 +v -0.021994 0.006293 0.108493 +v -0.021994 0.007588 0.114337 +v -0.021994 0.004372 0.119384 +v -0.031709 -0.007127 0.117890 +v -0.031709 -0.001600 0.121411 +v -0.031709 -0.008546 0.111492 +v -0.033234 -0.008577 0.100890 +v -0.031709 -0.005024 0.105965 +v -0.033234 0.002449 0.098446 +v -0.031709 0.001374 0.104546 +v -0.031709 0.006901 0.108067 +v -0.031709 0.008320 0.114466 +v -0.031709 0.004798 0.119993 +v -0.011116 -0.071646 -0.018766 +v -0.011116 -0.069722 -0.009324 +v 0.029909 -0.068421 -0.009304 +v 0.029909 -0.071822 -0.016749 +v -0.011564 -0.066870 -0.026261 +v 0.029909 -0.068421 -0.024960 +v -0.011954 -0.058194 -0.028184 +v 0.030746 -0.060211 -0.028361 +v 0.033903 -0.060211 -0.005138 +v 0.033903 -0.060211 -0.011239 +v 0.031685 -0.064107 -0.012853 +v -0.012893 -0.064724 -0.013589 +v -0.015110 -0.061167 -0.011323 +v -0.015110 -0.062227 -0.005314 +v 0.030804 -0.065721 -0.016749 +v -0.011564 -0.065637 -0.017706 +v 0.031685 -0.064107 -0.020646 +v -0.012893 -0.063371 -0.021263 +v 0.033903 -0.060211 -0.022259 +v -0.015110 -0.059254 -0.022176 +v 0.033903 -0.056314 -0.020646 +v 0.033903 -0.052000 -0.024960 +v -0.015110 -0.050699 -0.023410 +v -0.015110 -0.055697 -0.019910 +v 0.033903 -0.054700 -0.016749 +v 0.033903 -0.048599 -0.016749 +v -0.015110 -0.048775 -0.014733 +v -0.015110 -0.054784 -0.015793 +v 0.033903 -0.056314 -0.012853 +v 0.033903 -0.052000 -0.008539 +v -0.015110 -0.053550 -0.007238 +v -0.015110 -0.057050 -0.012236 +v -0.033234 -0.018545 0.071550 +v -0.014896 -0.018546 0.071550 +v -0.033234 -0.006583 0.067529 +v -0.033234 0.006283 0.064677 +v -0.033234 0.016673 0.062467 +v -0.014896 0.016673 0.062467 +v -0.014896 0.006283 0.064677 +v -0.014896 -0.006583 0.067529 +v 0.040267 -0.017741 0.072430 +v 0.035253 -0.017738 0.041350 +v -0.016460 -0.017779 0.040815 +v -0.021475 -0.017767 0.072429 +v 0.030746 -0.017794 -0.040884 +v -0.011954 -0.017794 -0.040897 +v 0.033903 -0.017745 -0.040918 +v -0.015110 -0.017744 -0.040809 +v 0.033903 -0.017720 -0.009967 +v -0.015110 -0.017720 -0.009762 +v 0.033903 -0.017708 0.007381 +v -0.015110 -0.017740 0.011325 +v -0.004782 -0.065842 -0.003319 +v 0.023493 -0.064642 -0.003312 +v 0.034488 -0.017739 0.072430 +v -0.015789 -0.021473 0.072427 +v -0.009782 -0.028915 0.008095 +v 0.028493 -0.027715 0.008100 +v 0.034298 -0.018149 0.072431 +v -0.015587 -0.019349 0.072431 +v 0.029407 -0.023690 -0.011774 +v -0.010665 -0.024394 -0.011822 +# 238 vertices, 0 vertices normals + +f 1 4 3 +f 3 2 1 +f 4 6 5 +f 5 3 4 +f 6 8 7 +f 7 5 6 +f 8 10 9 +f 9 7 8 +f 10 12 11 +f 11 9 10 +f 13 1 15 +f 15 14 13 +f 16 12 10 +f 10 17 16 +f 18 19 12 +f 12 16 18 +f 14 15 19 +f 19 18 14 +f 20 22 2 +f 2 21 20 +f 21 2 3 +f 3 23 21 +f 23 3 5 +f 5 24 23 +f 24 5 7 +f 7 25 24 +f 25 7 9 +f 9 26 25 +f 26 9 11 +f 11 27 26 +f 27 11 29 +f 29 28 27 +f 28 29 22 +f 22 20 28 +f 27 16 17 +f 17 26 27 +f 26 17 30 +f 30 25 26 +f 25 30 31 +f 31 24 25 +f 24 31 32 +f 32 23 24 +f 23 32 13 +f 13 21 23 +f 21 13 14 +f 14 20 21 +f 20 14 18 +f 18 28 20 +f 28 18 16 +f 16 27 28 +f 33 36 35 +f 35 34 33 +f 36 38 37 +f 37 35 36 +f 39 42 41 +f 41 40 39 +f 42 44 43 +f 43 41 42 +f 44 33 34 +f 34 43 44 +f 45 36 33 +f 33 46 45 +f 47 38 36 +f 36 45 47 +f 48 49 38 +f 38 47 48 +f 50 51 49 +f 49 48 50 +f 52 39 51 +f 51 50 52 +f 53 42 39 +f 39 52 53 +f 54 44 42 +f 42 53 54 +f 46 33 44 +f 44 54 46 +f 55 34 35 +f 35 56 55 +f 56 35 37 +f 37 57 56 +f 57 37 59 +f 59 58 57 +f 58 59 61 +f 61 60 58 +f 60 61 40 +f 40 62 60 +f 62 40 41 +f 41 63 62 +f 63 41 43 +f 43 64 63 +f 64 43 34 +f 34 55 64 +f 63 53 52 +f 52 62 63 +f 62 52 50 +f 50 60 62 +f 60 50 48 +f 48 58 60 +f 58 48 47 +f 47 57 58 +f 57 47 45 +f 45 56 57 +f 56 45 46 +f 46 55 56 +f 55 46 54 +f 54 64 55 +f 64 54 53 +f 53 63 64 +f 1 2 66 +f 66 65 1 +f 2 22 67 +f 67 66 2 +f 67 22 29 +f 29 68 67 +f 68 29 11 +f 11 69 68 +f 11 12 70 +f 70 69 11 +f 12 19 71 +f 71 70 12 +f 19 15 72 +f 72 71 19 +f 72 15 1 +f 1 65 72 +f 66 37 38 +f 38 65 66 +f 67 59 37 +f 37 66 67 +f 68 61 59 +f 59 67 68 +f 68 69 40 +f 40 61 68 +f 70 39 40 +f 40 69 70 +f 71 51 39 +f 39 70 71 +f 71 72 49 +f 49 51 71 +f 72 65 38 +f 38 49 72 +f 73 76 75 +f 75 74 73 +f 77 78 76 +f 76 73 77 +f 79 80 78 +f 78 77 79 +f 81 82 80 +f 80 79 81 +f 83 84 82 +f 82 81 83 +f 85 86 84 +f 84 83 85 +f 87 88 86 +f 86 85 87 +f 74 75 88 +f 88 87 74 +f 89 90 73 +f 73 74 89 +f 90 91 77 +f 77 73 90 +f 91 92 79 +f 79 77 91 +f 92 93 81 +f 81 79 92 +f 93 94 83 +f 83 81 93 +f 94 95 85 +f 85 83 94 +f 95 96 87 +f 87 85 95 +f 96 89 74 +f 74 87 96 +f 75 76 98 +f 98 97 75 +f 90 89 100 +f 100 99 90 +f 76 78 101 +f 101 98 76 +f 91 90 99 +f 99 102 91 +f 78 80 103 +f 103 101 78 +f 92 91 102 +f 102 104 92 +f 80 82 105 +f 105 103 80 +f 93 92 104 +f 104 106 93 +f 82 84 107 +f 107 105 82 +f 94 93 106 +f 106 108 94 +f 84 86 109 +f 109 107 84 +f 95 94 108 +f 108 110 95 +f 86 88 111 +f 111 109 86 +f 96 95 110 +f 110 112 96 +f 88 75 97 +f 97 111 88 +f 89 96 112 +f 112 100 89 +f 97 98 99 +f 99 100 97 +f 111 97 100 +f 100 112 111 +f 109 111 112 +f 112 110 109 +f 107 109 110 +f 110 108 107 +f 105 107 108 +f 108 106 105 +f 103 105 106 +f 106 104 103 +f 101 103 104 +f 104 102 101 +f 98 101 102 +f 102 99 98 +f 113 116 115 +f 115 114 113 +f 117 118 116 +f 116 113 117 +f 119 120 118 +f 118 117 119 +f 121 122 120 +f 120 119 121 +f 123 124 122 +f 122 121 123 +f 125 115 127 +f 127 126 125 +f 122 124 129 +f 129 128 122 +f 124 131 130 +f 130 129 124 +f 131 125 126 +f 126 130 131 +f 114 134 133 +f 133 132 114 +f 113 114 132 +f 132 135 113 +f 117 113 135 +f 135 136 117 +f 119 117 136 +f 136 137 119 +f 121 119 137 +f 137 138 121 +f 123 121 138 +f 138 139 123 +f 140 123 139 +f 139 141 140 +f 134 140 141 +f 141 133 134 +f 128 129 139 +f 139 138 128 +f 142 128 138 +f 138 137 142 +f 143 142 137 +f 137 136 143 +f 144 143 136 +f 136 135 144 +f 127 144 135 +f 135 132 127 +f 126 127 132 +f 132 133 126 +f 130 126 133 +f 133 141 130 +f 129 130 141 +f 141 139 129 +f 145 148 147 +f 147 146 145 +f 149 150 148 +f 148 145 149 +f 151 154 153 +f 153 152 151 +f 155 156 154 +f 154 151 155 +f 146 147 156 +f 156 155 146 +f 147 148 158 +f 158 157 147 +f 148 150 159 +f 159 158 148 +f 150 161 160 +f 160 159 150 +f 161 163 162 +f 162 160 161 +f 163 153 164 +f 164 162 163 +f 153 154 165 +f 165 164 153 +f 154 156 166 +f 166 165 154 +f 156 147 157 +f 157 166 156 +f 145 146 168 +f 168 167 145 +f 149 145 167 +f 167 169 149 +f 170 149 169 +f 169 171 170 +f 172 170 171 +f 171 173 172 +f 152 172 173 +f 173 174 152 +f 151 152 174 +f 174 175 151 +f 155 151 175 +f 175 176 155 +f 146 155 176 +f 176 168 146 +f 164 165 175 +f 175 174 164 +f 162 164 174 +f 174 173 162 +f 160 162 173 +f 173 171 160 +f 159 160 171 +f 171 169 159 +f 158 159 169 +f 169 167 158 +f 157 158 167 +f 167 168 157 +f 166 157 168 +f 168 176 166 +f 165 166 176 +f 176 175 165 +f 177 180 179 +f 179 178 177 +f 181 182 180 +f 180 177 181 +f 183 184 182 +f 182 181 183 +f 185 179 187 +f 187 186 185 +f 178 190 189 +f 189 188 178 +f 179 180 191 +f 191 187 179 +f 177 178 188 +f 188 192 177 +f 180 182 193 +f 193 191 180 +f 181 177 192 +f 192 194 181 +f 182 184 195 +f 195 193 182 +f 183 181 194 +f 194 196 183 +f 184 198 197 +f 197 195 184 +f 199 183 196 +f 196 200 199 +f 198 202 201 +f 201 197 198 +f 203 199 200 +f 200 204 203 +f 202 206 205 +f 205 201 202 +f 207 203 204 +f 204 208 207 +f 206 185 186 +f 186 205 206 +f 190 207 208 +f 208 189 190 +f 201 205 208 +f 208 204 201 +f 197 201 204 +f 204 200 197 +f 195 197 200 +f 200 196 195 +f 193 195 196 +f 196 194 193 +f 191 193 194 +f 194 192 191 +f 187 191 192 +f 192 188 187 +f 186 187 188 +f 188 189 186 +f 205 186 189 +f 189 208 205 +f 209 114 115 +f 115 210 209 +f 211 134 114 +f 114 209 211 +f 140 134 211 +f 211 212 140 +f 123 140 212 +f 212 213 123 +f 214 124 123 +f 123 213 214 +f 215 131 124 +f 124 214 215 +f 216 125 131 +f 131 215 216 +f 115 125 216 +f 216 210 115 +f 150 149 209 +f 209 210 150 +f 149 170 211 +f 211 209 149 +f 170 172 212 +f 212 211 170 +f 152 213 212 +f 212 172 152 +f 152 153 214 +f 214 213 152 +f 153 163 215 +f 215 214 153 +f 161 216 215 +f 215 163 161 +f 150 210 216 +f 216 161 150 +f 116 4 1 +f 1 115 116 +f 115 1 13 +f 13 127 115 +f 127 13 32 +f 32 144 127 +f 144 32 31 +f 31 143 144 +f 143 31 30 +f 30 142 143 +f 142 30 17 +f 17 128 142 +f 128 17 10 +f 10 122 128 +f 122 10 8 +f 8 120 122 +f 120 8 6 +f 6 118 120 +f 118 6 4 +f 4 116 118 +f 217 179 185 +f 185 218 217 +f 219 190 178 +f 178 220 219 +f 221 184 183 +f 183 222 221 +f 223 198 184 +f 184 221 223 +f 222 183 199 +f 199 224 222 +f 225 202 198 +f 198 223 225 +f 224 199 203 +f 203 226 224 +f 227 206 202 +f 202 225 227 +f 226 203 207 +f 207 228 226 +f 218 185 206 +f 206 227 218 +f 228 207 190 +f 190 219 228 +f 229 178 179 +f 179 230 229 +f 230 179 217 +f 217 231 230 +f 232 220 178 +f 178 229 232 +f 233 229 230 +f 230 234 233 +f 231 235 234 +f 234 230 231 +f 236 232 229 +f 229 233 236 +f 233 228 219 +f 237 221 222 +f 222 238 237 +f 218 235 231 +f 231 217 218 +f 234 235 218 +f 237 225 223 +f 223 221 237 +f 226 238 222 +f 222 224 226 +f 238 226 228 +f 228 233 238 +f 237 233 234 +f 237 238 233 +f 227 225 237 +f 237 234 227 +f 219 220 232 +f 232 236 219 +f 233 219 236 +f 234 218 227 +# 488 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_uglut_chull.obj b/examples/Atlas/urdf/mesh/r_uglut_chull.obj new file mode 100644 index 0000000..230077a --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_uglut_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_uglut_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.010540 -0.072584 -0.015884 +v 0.008667 0.020443 -0.040398 +v -0.011564 -0.066870 -0.026261 +v 0.029909 -0.071822 -0.016749 +v 0.030404 -0.068123 -0.025919 +v -0.015552 -0.018892 -0.040910 +v 0.033903 -0.017745 -0.040918 +v -0.012649 0.016950 -0.040319 +v -0.021275 0.003410 -0.040319 +v -0.033234 -0.002676 0.127511 +v 0.049145 -0.002676 0.127511 +v 0.049145 0.008351 0.125067 +v -0.033234 0.008351 0.125067 +v -0.033234 0.016767 -0.011735 +v -0.033234 0.014420 0.115541 +v -0.034605 -0.005460 -0.017709 +v -0.033234 -0.018545 0.071550 +v -0.033234 -0.020554 -0.003451 +v -0.033234 0.020194 0.003722 +v -0.033418 -0.012460 0.120867 +v 0.049145 0.014420 0.115541 +v 0.049145 -0.018545 0.071550 +v 0.049138 -0.020622 -0.012668 +v 0.049503 -0.012252 0.121327 +v 0.049145 0.003414 -0.020242 +v 0.049145 0.020194 0.003722 +v 0.049145 0.016767 -0.011735 +# 27 vertices, 0 vertices normals + +f 1 24 20 +f 24 1 4 +f 16 3 18 +f 24 4 22 +f 1 5 4 +f 3 5 1 +f 1 18 3 +f 23 5 7 +f 26 27 2 +f 18 1 17 +f 20 17 1 +f 25 7 2 +f 25 2 27 +f 25 23 7 +f 23 22 4 +f 6 7 5 +f 6 5 3 +f 9 6 16 +f 3 16 6 +f 14 9 16 +f 2 19 26 +f 5 23 4 +f 2 7 6 +f 8 14 19 +f 8 19 2 +f 14 8 9 +f 2 6 8 +f 8 6 9 +f 10 24 11 +f 10 20 24 +f 11 12 10 +f 10 12 13 +f 14 10 13 +f 14 13 15 +f 18 17 14 +f 14 16 18 +f 15 19 14 +f 20 14 17 +f 20 10 14 +f 23 21 22 +f 21 11 24 +f 21 24 22 +f 23 25 21 +f 21 12 11 +f 27 26 21 +f 21 25 27 +f 21 15 13 +f 12 21 13 +f 21 19 15 +f 21 26 19 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_uleg.obj b/examples/Atlas/urdf/mesh/r_uleg.obj new file mode 100644 index 0000000..ba4c168 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_uleg.obj @@ -0,0 +1,3726 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_uleg.obj +# +# Vertices: 1246 +# Faces: 2464 +# +#### +v -0.051197 -0.012924 -0.061447 +v -0.053869 -0.013386 -0.062289 +v -0.053523 -0.000258 -0.061604 +v -0.052277 -0.000258 -0.060385 +v -0.056009 -0.025629 -0.065658 +v -0.051081 -0.025783 -0.064644 +v -0.062193 -0.038587 -0.072882 +v -0.050952 -0.041471 -0.071773 +v -0.068221 -0.049687 -0.078694 +v -0.050893 -0.052293 -0.079492 +v -0.074112 -0.059783 -0.086318 +v -0.051295 -0.059860 -0.086896 +v -0.058806 -0.064420 -0.091399 +v -0.070524 -0.063277 -0.090561 +v -0.091589 -0.045258 -0.090589 +v -0.081116 -0.051490 -0.086567 +v -0.092010 -0.054892 -0.093867 +v -0.072426 -0.046407 -0.081524 +v -0.083531 -0.037447 -0.087634 +v -0.067736 -0.037117 -0.078015 +v -0.075572 -0.031713 -0.083426 +v -0.065413 -0.023452 -0.076014 +v -0.093507 -0.013433 -0.091059 +v -0.109342 -0.016306 -0.094825 +v -0.109939 -0.000258 -0.094752 +v -0.094009 -0.000258 -0.091158 +v -0.064488 -0.012006 -0.075089 +v -0.063777 -0.000258 -0.074354 +v -0.078702 -0.012855 -0.085273 +v -0.078792 -0.000258 -0.085356 +v -0.101816 -0.029781 -0.092876 +v -0.090005 -0.026374 -0.090065 +v -0.076961 -0.024270 -0.084033 +v -0.106569 -0.036275 -0.096463 +v -0.115328 -0.019401 -0.100672 +v -0.117667 -0.000258 -0.101490 +v -0.120738 -0.000258 -0.110085 +v -0.117031 -0.023168 -0.108534 +v -0.105552 -0.044647 -0.105575 +v -0.085972 -0.062474 -0.101808 +v -0.060860 -0.069420 -0.099940 +v -0.051265 -0.069191 -0.099502 +v -0.061901 -0.072533 -0.112494 +v -0.051525 -0.073867 -0.113498 +v -0.086224 -0.063887 -0.115244 +v -0.105663 -0.046639 -0.117205 +v -0.118758 -0.023574 -0.119546 +v -0.122704 -0.000258 -0.121204 +v -0.125285 -0.000258 -0.139711 +v -0.121061 -0.024254 -0.137744 +v -0.107642 -0.047121 -0.133799 +v -0.087362 -0.064053 -0.132521 +v -0.063073 -0.073049 -0.132773 +v -0.050562 -0.073988 -0.133170 +v -0.063504 -0.073055 -0.164836 +v -0.051023 -0.074267 -0.164841 +v -0.087476 -0.064844 -0.162812 +v -0.108671 -0.048428 -0.160118 +v -0.122347 -0.025920 -0.160064 +v -0.126781 -0.000258 -0.158457 +v -0.127756 -0.000258 -0.184270 +v -0.123377 -0.025396 -0.183655 +v -0.109617 -0.048197 -0.184420 +v -0.088284 -0.064576 -0.187759 +v -0.095422 -0.060197 -0.209259 +v -0.110649 -0.046802 -0.199318 +v -0.067714 -0.071726 -0.189989 +v -0.051254 -0.074258 -0.190996 +v -0.064912 -0.072865 -0.208364 +v -0.050825 -0.074239 -0.208502 +v -0.075506 -0.070050 -0.208934 +v -0.083843 -0.066469 -0.224522 +v -0.068850 -0.071266 -0.233928 +v -0.050862 -0.073833 -0.228241 +v -0.063342 -0.069308 -0.257286 +v -0.051135 -0.071451 -0.253097 +v -0.060669 -0.061239 -0.288781 +v -0.051079 -0.063646 -0.284915 +v -0.050628 -0.056429 -0.303569 +v -0.055637 -0.056462 -0.302933 +v -0.070700 -0.065682 -0.266290 +v -0.051051 -0.068488 -0.267879 +v -0.061096 -0.044083 -0.287938 +v -0.070259 -0.044281 -0.268612 +v -0.081772 -0.065346 -0.247192 +v -0.080877 -0.044165 -0.251290 +v -0.093618 -0.059921 -0.232955 +v -0.089176 -0.039671 -0.239523 +v -0.107492 -0.048563 -0.217962 +v -0.099493 -0.028445 -0.228028 +v -0.123276 -0.023812 -0.202756 +v -0.103974 -0.013178 -0.222541 +v -0.127144 -0.000258 -0.199854 +v -0.105319 -0.000258 -0.221239 +v -0.054376 -0.051196 -0.316434 +v -0.050364 -0.051026 -0.315899 +v -0.056045 -0.044167 -0.302012 +v -0.054571 -0.044953 -0.316470 +v -0.051197 0.012408 -0.061447 +v -0.053869 0.012870 -0.062289 +v -0.056009 0.025113 -0.065658 +v -0.051081 0.025267 -0.064644 +v -0.062193 0.038071 -0.072882 +v -0.050952 0.040955 -0.071773 +v -0.068221 0.049171 -0.078694 +v -0.050893 0.051777 -0.079491 +v -0.074112 0.059267 -0.086318 +v -0.070524 0.062761 -0.090561 +v -0.058806 0.063904 -0.091399 +v -0.051295 0.059344 -0.086896 +v -0.091589 0.044742 -0.090589 +v -0.092010 0.054376 -0.093867 +v -0.081116 0.050974 -0.086567 +v -0.072426 0.045891 -0.081524 +v -0.083531 0.036931 -0.087634 +v -0.067736 0.036601 -0.078015 +v -0.075572 0.031197 -0.083426 +v -0.065413 0.022936 -0.076014 +v -0.093507 0.012917 -0.091059 +v -0.109342 0.015790 -0.094825 +v -0.064488 0.011490 -0.075089 +v -0.078702 0.012339 -0.085273 +v -0.101816 0.029265 -0.092876 +v -0.090005 0.025859 -0.090065 +v -0.076961 0.023754 -0.084033 +v -0.106569 0.035759 -0.096463 +v -0.115328 0.018885 -0.100672 +v -0.117031 0.022652 -0.108534 +v -0.105552 0.044131 -0.105575 +v -0.085972 0.061958 -0.101808 +v -0.060860 0.068904 -0.099940 +v -0.051265 0.068675 -0.099502 +v -0.061901 0.072017 -0.112494 +v -0.051525 0.073351 -0.113498 +v -0.086224 0.063371 -0.115244 +v -0.105663 0.046123 -0.117205 +v -0.118758 0.023058 -0.119546 +v -0.121061 0.023738 -0.137744 +v -0.107643 0.046605 -0.133799 +v -0.087362 0.063537 -0.132521 +v -0.063073 0.072533 -0.132772 +v -0.050562 0.073472 -0.133170 +v -0.063504 0.072539 -0.164836 +v -0.051023 0.073751 -0.164841 +v -0.087476 0.064328 -0.162812 +v -0.108671 0.047912 -0.160118 +v -0.122347 0.025404 -0.160064 +v -0.123377 0.024880 -0.183655 +v -0.109617 0.047681 -0.184420 +v -0.088284 0.064060 -0.187759 +v -0.095422 0.059681 -0.209259 +v -0.110649 0.046286 -0.199318 +v -0.067714 0.071210 -0.189989 +v -0.051254 0.073742 -0.190996 +v -0.064912 0.072349 -0.208364 +v -0.050825 0.073723 -0.208502 +v -0.075506 0.069534 -0.208934 +v -0.083843 0.065953 -0.224522 +v -0.068850 0.070750 -0.233928 +v -0.050862 0.073317 -0.228241 +v -0.063342 0.068792 -0.257286 +v -0.051135 0.070935 -0.253097 +v -0.060669 0.060723 -0.288781 +v -0.055637 0.055946 -0.302933 +v -0.050628 0.055913 -0.303569 +v -0.051079 0.063130 -0.284915 +v -0.070700 0.065166 -0.266290 +v -0.051051 0.067972 -0.267879 +v -0.070259 0.043765 -0.268612 +v -0.061096 0.043567 -0.287938 +v -0.081772 0.064830 -0.247192 +v -0.080877 0.043649 -0.251290 +v -0.093618 0.059405 -0.232955 +v -0.089176 0.039155 -0.239523 +v -0.107492 0.048047 -0.217962 +v -0.099493 0.027929 -0.228028 +v -0.123276 0.023296 -0.202756 +v -0.103974 0.012662 -0.222541 +v -0.054376 0.050680 -0.316434 +v -0.050364 0.050510 -0.315899 +v -0.056045 0.043651 -0.302012 +v -0.054571 0.044436 -0.316470 +v -0.050078 -0.012251 -0.065365 +v -0.049581 -0.000258 -0.063514 +v -0.050471 -0.000258 -0.064386 +v -0.051684 -0.012945 -0.065766 +v -0.054072 -0.024759 -0.069201 +v -0.050237 -0.024473 -0.068469 +v -0.060403 -0.037459 -0.076429 +v -0.050081 -0.039415 -0.075248 +v -0.066978 -0.048164 -0.082326 +v -0.050507 -0.049758 -0.082729 +v -0.072938 -0.057016 -0.089150 +v -0.069798 -0.059767 -0.092614 +v -0.058872 -0.061165 -0.093941 +v -0.051365 -0.056899 -0.089774 +v -0.089872 -0.044663 -0.094297 +v -0.089321 -0.052474 -0.095861 +v -0.079222 -0.050652 -0.090140 +v -0.070165 -0.046424 -0.084980 +v -0.081827 -0.037399 -0.091395 +v -0.065089 -0.037125 -0.081186 +v -0.073441 -0.031611 -0.086962 +v -0.062659 -0.023420 -0.079092 +v -0.092272 -0.013438 -0.095000 +v -0.092811 -0.000258 -0.095110 +v -0.108053 -0.000258 -0.098426 +v -0.107338 -0.015979 -0.098421 +v -0.061672 -0.012004 -0.078109 +v -0.060916 -0.000258 -0.077333 +v -0.076756 -0.012911 -0.088915 +v -0.076824 -0.000258 -0.088987 +v -0.100241 -0.029502 -0.096684 +v -0.088639 -0.026306 -0.093962 +v -0.074927 -0.024234 -0.087627 +v -0.103640 -0.034908 -0.099033 +v -0.111906 -0.018613 -0.102846 +v -0.114185 -0.000258 -0.103712 +v -0.116738 -0.000258 -0.111113 +v -0.113228 -0.021902 -0.109530 +v -0.102374 -0.042243 -0.106663 +v -0.083924 -0.059036 -0.102830 +v -0.060366 -0.065612 -0.101459 +v -0.051396 -0.065480 -0.101310 +v -0.061028 -0.068535 -0.113048 +v -0.051130 -0.069790 -0.114027 +v -0.084107 -0.060354 -0.115549 +v -0.102476 -0.044052 -0.117660 +v -0.114892 -0.022249 -0.120142 +v -0.118623 -0.000258 -0.121838 +v -0.121178 -0.000258 -0.140143 +v -0.117188 -0.022880 -0.138163 +v -0.104481 -0.044485 -0.134139 +v -0.085268 -0.060496 -0.132667 +v -0.062188 -0.069016 -0.132858 +v -0.050222 -0.069873 -0.133232 +v -0.062621 -0.069020 -0.164847 +v -0.050634 -0.070156 -0.164850 +v -0.085512 -0.061212 -0.162897 +v -0.105598 -0.045674 -0.160307 +v -0.118494 -0.024452 -0.160300 +v -0.122659 -0.000258 -0.158704 +v -0.123626 -0.000258 -0.184282 +v -0.119503 -0.023963 -0.183676 +v -0.106552 -0.045429 -0.184444 +v -0.086309 -0.060948 -0.187792 +v -0.093031 -0.056830 -0.209210 +v -0.107445 -0.044199 -0.199178 +v -0.066702 -0.067722 -0.189992 +v -0.050655 -0.070172 -0.190949 +v -0.064162 -0.068804 -0.208414 +v -0.050371 -0.070134 -0.208506 +v -0.074148 -0.066150 -0.209018 +v -0.082065 -0.062745 -0.224347 +v -0.067897 -0.067261 -0.233595 +v -0.050385 -0.069738 -0.228000 +v -0.062560 -0.065318 -0.256564 +v -0.050653 -0.067391 -0.252514 +v -0.058014 -0.058644 -0.286972 +v -0.053007 -0.053765 -0.301240 +v -0.050452 -0.052619 -0.301985 +v -0.050614 -0.059735 -0.283674 +v -0.068033 -0.063028 -0.264586 +v -0.050477 -0.064522 -0.266877 +v -0.066610 -0.044170 -0.266682 +v -0.057285 -0.044066 -0.286347 +v -0.078977 -0.062738 -0.245629 +v -0.077393 -0.043913 -0.249087 +v -0.090506 -0.057744 -0.231334 +v -0.085942 -0.039472 -0.236963 +v -0.104099 -0.046812 -0.216388 +v -0.096315 -0.028371 -0.225391 +v -0.119537 -0.022874 -0.201275 +v -0.100979 -0.013141 -0.219697 +v -0.123305 -0.000258 -0.198332 +v -0.102393 -0.000258 -0.218324 +v -0.051352 -0.048677 -0.315180 +v -0.050612 -0.047189 -0.314391 +v -0.052025 -0.044101 -0.301064 +v -0.050464 -0.044822 -0.316059 +v -0.050078 0.011735 -0.065365 +v -0.051684 0.012429 -0.065766 +v -0.054072 0.024243 -0.069201 +v -0.050237 0.023957 -0.068469 +v -0.060403 0.036943 -0.076429 +v -0.050081 0.038899 -0.075248 +v -0.066978 0.047648 -0.082326 +v -0.050507 0.049242 -0.082729 +v -0.072938 0.056500 -0.089150 +v -0.051365 0.056383 -0.089774 +v -0.058872 0.060650 -0.093940 +v -0.069798 0.059251 -0.092614 +v -0.089872 0.044147 -0.094297 +v -0.079222 0.050136 -0.090140 +v -0.089321 0.051958 -0.095861 +v -0.070165 0.045908 -0.084980 +v -0.081827 0.036883 -0.091395 +v -0.065089 0.036609 -0.081186 +v -0.073441 0.031096 -0.086962 +v -0.062659 0.022904 -0.079092 +v -0.092272 0.012922 -0.095000 +v -0.107338 0.015463 -0.098421 +v -0.061672 0.011488 -0.078109 +v -0.076756 0.012395 -0.088915 +v -0.100241 0.028986 -0.096684 +v -0.088639 0.025791 -0.093962 +v -0.074927 0.023718 -0.087627 +v -0.103640 0.034392 -0.099033 +v -0.111906 0.018097 -0.102846 +v -0.113228 0.021386 -0.109530 +v -0.102374 0.041727 -0.106663 +v -0.083924 0.058520 -0.102830 +v -0.060366 0.065096 -0.101459 +v -0.051396 0.064964 -0.101310 +v -0.061028 0.068019 -0.113048 +v -0.051130 0.069275 -0.114027 +v -0.084107 0.059838 -0.115549 +v -0.102476 0.043536 -0.117660 +v -0.114892 0.021733 -0.120142 +v -0.117188 0.022364 -0.138163 +v -0.104481 0.043969 -0.134139 +v -0.085268 0.059981 -0.132667 +v -0.062188 0.068500 -0.132858 +v -0.050222 0.069357 -0.133232 +v -0.062621 0.068504 -0.164847 +v -0.050634 0.069640 -0.164849 +v -0.085512 0.060696 -0.162897 +v -0.105598 0.045158 -0.160306 +v -0.118494 0.023936 -0.160300 +v -0.119503 0.023447 -0.183676 +v -0.106552 0.044913 -0.184444 +v -0.086310 0.060432 -0.187792 +v -0.093031 0.056314 -0.209210 +v -0.107445 0.043683 -0.199178 +v -0.066702 0.067206 -0.189992 +v -0.050655 0.069656 -0.190949 +v -0.064162 0.068288 -0.208414 +v -0.050371 0.069618 -0.208506 +v -0.074148 0.065634 -0.209018 +v -0.082065 0.062229 -0.224347 +v -0.067897 0.066745 -0.233595 +v -0.050385 0.069222 -0.228000 +v -0.062560 0.064802 -0.256564 +v -0.050653 0.066875 -0.252514 +v -0.058014 0.058128 -0.286972 +v -0.050614 0.059219 -0.283674 +v -0.050452 0.052103 -0.301985 +v -0.053007 0.053249 -0.301240 +v -0.068033 0.062512 -0.264586 +v -0.050478 0.064006 -0.266877 +v -0.057285 0.043550 -0.286347 +v -0.066610 0.043654 -0.266682 +v -0.078977 0.062222 -0.245629 +v -0.077393 0.043397 -0.249087 +v -0.090506 0.057228 -0.231334 +v -0.085942 0.038956 -0.236963 +v -0.104099 0.046296 -0.216388 +v -0.096315 0.027855 -0.225391 +v -0.119537 0.022358 -0.201275 +v -0.100979 0.012625 -0.219697 +v -0.051352 0.048161 -0.315180 +v -0.050612 0.046673 -0.314391 +v -0.052026 0.043585 -0.301064 +v -0.050464 0.044306 -0.316059 +v -0.026482 0.045983 -0.344329 +v -0.024778 0.047494 -0.332917 +v -0.036297 0.046875 -0.334804 +v -0.033785 0.046008 -0.343062 +v -0.018607 0.043295 -0.343112 +v -0.013129 0.047138 -0.332893 +v -0.019521 0.050786 -0.320706 +v -0.036179 0.050224 -0.320841 +v -0.002343 0.047454 -0.324966 +v -0.007498 0.073461 -0.026448 +v -0.012557 0.073731 -0.030529 +v -0.005394 0.073743 -0.035325 +v -0.001038 0.073765 -0.028646 +v -0.006144 0.073747 -0.040857 +v 0.004655 0.073779 -0.036666 +v -0.017100 0.073735 -0.037081 +v -0.006520 0.073742 -0.047133 +v 0.006194 0.073766 -0.047888 +v -0.022975 0.073780 -0.047387 +v -0.028292 0.073768 -0.060834 +v -0.009151 0.073733 -0.063017 +v -0.012724 0.073748 -0.081529 +v -0.032368 0.073818 -0.078053 +v 0.007401 0.073748 -0.063457 +v -0.032971 0.073831 -0.100557 +v -0.015746 0.073735 -0.102862 +v 0.011751 0.073585 -0.084866 +v 0.003018 0.073754 -0.104400 +v 0.009828 0.073376 -0.119367 +v 0.025417 0.071268 -0.108499 +v -0.012727 0.073734 -0.126503 +v -0.031815 0.073824 -0.125250 +v -0.017438 0.056672 -0.305981 +v -0.035946 0.056726 -0.304456 +v -0.000678 0.053711 -0.308629 +v -0.015357 0.061951 -0.292895 +v -0.032911 0.062616 -0.289159 +v -0.010985 0.068903 -0.268344 +v -0.027699 0.069191 -0.266850 +v -0.006121 0.073070 -0.234175 +v -0.027897 0.073227 -0.233083 +v -0.003074 0.073505 -0.195833 +v -0.027337 0.073809 -0.194085 +v -0.003005 0.073631 -0.178827 +v -0.025988 0.073797 -0.159282 +v 0.000190 0.073712 -0.149768 +v 0.020896 0.071343 -0.138861 +v 0.041083 0.064367 -0.126756 +v 0.001622 0.058896 -0.294810 +v 0.007126 0.064991 -0.270682 +v 0.011079 0.069601 -0.236075 +v 0.016534 0.070115 -0.197317 +v 0.017331 0.070944 -0.175606 +v 0.035818 0.064729 -0.157951 +v 0.055245 0.053450 -0.139368 +v 0.013200 0.043858 -0.319266 +v 0.012151 0.049457 -0.307685 +v 0.015601 0.052598 -0.295856 +v 0.020908 0.057921 -0.271812 +v 0.026395 0.062365 -0.237513 +v 0.032224 0.063063 -0.200921 +v 0.040015 0.059821 -0.184365 +v 0.053521 0.051356 -0.166617 +v 0.067639 0.038127 -0.144914 +v 0.054382 0.042551 -0.203113 +v 0.057541 0.042646 -0.186220 +v 0.047065 0.042677 -0.237736 +v 0.041192 0.038142 -0.270257 +v 0.036378 0.034254 -0.292275 +v 0.043917 -0.000240 -0.301755 +v 0.046915 -0.000240 -0.290175 +v 0.044489 0.016648 -0.291638 +v 0.041476 0.014588 -0.303257 +v 0.048696 0.022649 -0.270488 +v 0.052415 -0.000240 -0.270233 +v 0.056979 0.022631 -0.238310 +v 0.061057 -0.000240 -0.236365 +v 0.064279 0.022948 -0.204108 +v 0.067920 -0.000240 -0.204760 +v 0.071335 0.020656 -0.171431 +v 0.076173 0.018318 -0.147289 +v 0.074078 -0.000240 -0.174084 +v 0.078473 -0.000240 -0.147253 +v 0.030134 0.030181 -0.315501 +v 0.032636 0.033858 -0.303101 +v 0.037765 0.013437 -0.316072 +v 0.039734 -0.000240 -0.315749 +v 0.032655 0.013531 -0.332137 +v 0.034559 -0.000240 -0.332508 +v 0.026412 0.026459 -0.331645 +v 0.016086 0.037379 -0.331409 +v 0.002700 0.042924 -0.335802 +v -0.007140 0.044523 -0.341178 +v -0.014454 0.044187 -0.351029 +v -0.027460 0.045043 -0.352599 +v -0.043331 0.045494 -0.349105 +v -0.032542 0.041582 -0.359314 +v -0.021024 0.040876 -0.361982 +v -0.048082 0.041580 -0.354495 +v -0.047888 0.039998 -0.358945 +v -0.038361 0.041613 -0.363451 +v -0.034877 0.040778 -0.373714 +v -0.038673 0.041605 -0.385635 +v -0.037155 0.040209 -0.389136 +v -0.053707 0.041609 -0.389529 +v -0.054058 0.040948 -0.392931 +v -0.063232 0.041610 -0.382770 +v -0.066886 0.040856 -0.383422 +v -0.065643 0.041613 -0.371715 +v -0.069312 0.040200 -0.370601 +v -0.058067 0.041356 -0.349718 +v -0.061056 0.041616 -0.363164 +v -0.049847 0.045030 -0.334517 +v -0.054131 0.035613 -0.340375 +v -0.049963 0.037206 -0.327553 +v -0.051365 0.029986 -0.335159 +v -0.055335 0.029353 -0.342538 +v 0.034632 0.033700 -0.239048 +v 0.041399 0.026223 -0.237163 +v 0.044360 0.019552 -0.235693 +v 0.035051 0.023638 -0.238951 +v 0.045120 0.013496 -0.235428 +v 0.034897 0.015367 -0.238981 +v 0.043624 0.007360 -0.236635 +v 0.034677 0.007528 -0.239655 +v 0.000444 0.006936 -0.257011 +v -0.000674 0.006939 -0.262409 +v -0.009703 0.007847 -0.257933 +v -0.004223 0.007951 -0.249446 +v 0.008742 0.007596 -0.245304 +v 0.010403 0.006940 -0.256950 +v 0.020630 0.007157 -0.243324 +v 0.023101 0.006943 -0.255919 +v 0.032594 0.006943 -0.253629 +v 0.004266 0.006943 -0.271427 +v -0.007651 0.007603 -0.272212 +v 0.024541 0.006956 -0.268099 +v 0.032268 0.006955 -0.263581 +v 0.038760 0.006751 -0.252324 +v 0.038217 0.006244 -0.262272 +v 0.048142 0.005182 -0.233465 +v 0.043985 0.004282 -0.249683 +v 0.050392 0.001787 -0.231303 +v 0.045603 0.001431 -0.248730 +v 0.050491 -0.000240 -0.231208 +v 0.045972 -0.000240 -0.248327 +v 0.029271 0.006812 -0.279130 +v 0.041326 0.003762 -0.261404 +v 0.042751 -0.000240 -0.261042 +v 0.042420 0.001440 -0.261150 +v 0.009891 0.006953 -0.286800 +v 0.033104 0.004972 -0.280658 +v 0.034889 -0.000240 -0.281583 +v 0.034599 0.002955 -0.281344 +v -0.002861 0.008014 -0.289819 +v 0.017543 0.004991 -0.292977 +v 0.018997 -0.000240 -0.294719 +v 0.018717 0.002344 -0.294471 +v 0.001628 -0.000240 -0.300459 +v 0.001262 0.003435 -0.299610 +v 0.000594 0.005991 -0.297036 +v -0.000450 0.012469 -0.300901 +v -0.002590 0.014568 -0.297952 +v -0.043490 0.034755 -0.321689 +v -0.042738 0.024370 -0.321924 +v -0.048169 0.023779 -0.330650 +v -0.036629 0.022950 -0.330850 +v -0.039896 0.022958 -0.336991 +v -0.029157 0.024546 -0.315904 +v -0.028746 0.022939 -0.325710 +v -0.020071 0.024440 -0.315856 +v -0.018715 0.022942 -0.324272 +v -0.010386 0.023382 -0.311785 +v -0.006357 0.022904 -0.319539 +v -0.004782 0.020354 -0.305182 +v 0.001369 0.021112 -0.314421 +v 0.003350 0.008097 -0.311800 +v 0.005117 0.020513 -0.324683 +v 0.003693 -0.000240 -0.312979 +v -0.016744 0.025126 -0.355892 +v -0.010195 0.024164 -0.347146 +v -0.026003 0.022945 -0.346549 +v -0.019882 0.022952 -0.341102 +v -0.005554 0.024270 -0.343262 +v -0.016023 0.022960 -0.337601 +v 0.001077 0.021955 -0.338941 +v -0.011432 0.022624 -0.334321 +v 0.007000 0.015899 -0.336256 +v -0.002072 0.020939 -0.329712 +v 0.011340 0.006730 -0.334839 +v 0.004024 0.013538 -0.329592 +v 0.011787 -0.000240 -0.334661 +v 0.006107 -0.000240 -0.321265 +v 0.018573 0.015873 -0.242592 +v 0.019490 0.026834 -0.242373 +v 0.019803 0.042025 -0.242311 +v 0.006094 0.015801 -0.245537 +v -0.004297 0.016024 -0.249813 +v -0.009923 0.015575 -0.258314 +v -0.008152 0.015459 -0.272368 +v -0.000774 0.016959 -0.256411 +v 0.006405 0.016963 -0.253574 +v 0.015910 0.017144 -0.248710 +v -0.005749 0.015462 -0.280903 +v 0.000368 0.016978 -0.270383 +v 0.002047 0.017115 -0.279571 +v -0.002090 0.021615 -0.294671 +v 0.002388 0.022251 -0.294000 +v -0.005140 0.036812 -0.306113 +v 0.003386 0.036503 -0.306826 +v -0.009902 0.036153 -0.310996 +v -0.021056 0.035565 -0.315927 +v -0.030105 0.035420 -0.315775 +v 0.017500 0.027389 -0.247323 +v 0.020416 0.017002 -0.266871 +v 0.011821 0.017409 -0.280944 +v 0.016989 0.042129 -0.250159 +v 0.013460 0.032576 -0.277487 +v 0.013648 0.044296 -0.275110 +v 0.012827 0.022166 -0.295171 +v 0.012947 0.031646 -0.280896 +v 0.011257 0.037219 -0.307049 +v 0.012696 0.044332 -0.282175 +v -0.048571 0.049356 -0.321794 +v -0.048924 0.055509 -0.304440 +v -0.047244 0.043379 -0.314313 +v -0.048608 0.062409 -0.287580 +v -0.048659 0.068219 -0.267107 +v -0.048761 0.073123 -0.233050 +v -0.048312 0.073720 -0.194406 +v -0.047811 0.073801 -0.158103 +v -0.048552 0.073695 -0.126465 +v -0.048407 0.073711 -0.100305 +v -0.047499 0.073400 -0.073757 +v -0.050049 0.064496 -0.089819 +v -0.050038 0.057629 -0.093509 +v -0.049897 0.058421 -0.108801 +v -0.049311 0.062938 -0.079322 +v -0.050034 0.052461 -0.085066 +v -0.049976 0.029658 -0.067550 +v -0.049595 0.045566 -0.074176 +v -0.045155 0.037089 -0.061616 +v -0.049982 0.006538 -0.063003 +v -0.023718 0.006706 -0.064428 +v -0.024097 -0.000240 -0.064409 +v -0.049960 -0.000240 -0.062979 +v -0.049828 0.016840 -0.064320 +v -0.022935 0.016944 -0.066259 +v -0.020474 0.028794 -0.069225 +v -0.013228 0.036522 -0.063079 +v 0.009193 0.035414 -0.069586 +v 0.008851 0.025436 -0.072742 +v 0.008917 0.014195 -0.069799 +v 0.008406 0.004716 -0.068566 +v 0.008138 -0.000240 -0.068260 +v 0.082972 -0.000240 -0.117475 +v 0.080370 0.018373 -0.116812 +v 0.072017 0.038169 -0.115979 +v 0.060422 0.052539 -0.111950 +v 0.046994 0.062936 -0.103241 +v 0.034707 0.069218 -0.092242 +v 0.024514 0.072488 -0.077073 +v 0.019402 0.073403 -0.060890 +v 0.016311 0.073585 -0.046332 +v 0.013789 0.073506 -0.032151 +v 0.016902 0.069852 -0.040795 +v 0.015622 0.068071 -0.033490 +v 0.006506 0.073389 -0.020886 +v -0.005275 0.073239 -0.017005 +v -0.015787 0.073409 -0.020928 +v -0.022850 0.073631 -0.029336 +v -0.040562 0.060267 -0.051358 +v -0.030039 0.073651 -0.039049 +v -0.038600 0.073708 -0.051648 +v -0.035090 0.069759 -0.042554 +v -0.037081 0.071485 -0.045559 +v 0.017218 0.066303 -0.042835 +v 0.016337 0.065483 -0.034782 +v 0.010847 0.065982 -0.022453 +v -0.002254 0.066252 -0.015532 +v -0.016708 0.064963 -0.018987 +v -0.022435 0.065429 -0.024706 +v -0.027019 0.065922 -0.030910 +v -0.037072 0.064012 -0.045548 +v -0.032229 0.066062 -0.037782 +v -0.038235 0.038146 -0.047819 +v -0.031475 0.049721 -0.036224 +v -0.024448 0.057732 -0.020768 +v -0.014467 0.058260 -0.013560 +v 0.002728 0.056623 -0.014942 +v 0.003581 0.049861 -0.014707 +v -0.011283 0.052481 -0.010453 +v -0.023109 0.053931 -0.015299 +v -0.018768 0.049576 0.001933 +v -0.025460 0.045339 -0.022495 +v -0.020290 0.043562 -0.000815 +v -0.016685 0.049009 0.009712 +v -0.017023 0.043877 0.010329 +v 0.001109 0.048791 0.019433 +v -0.008427 0.048191 0.017761 +v -0.008907 0.043345 0.017732 +v 0.012620 0.048870 0.014818 +v 0.013580 0.042838 0.014564 +v 0.001612 0.042771 0.019801 +v 0.019159 0.049345 -0.001200 +v 0.016911 0.049570 0.007878 +v 0.017372 0.052486 -0.014247 +v 0.016488 0.057998 -0.023305 +v 0.018947 0.062694 -0.050702 +v 0.016969 0.057785 -0.040873 +v 0.016312 0.050303 -0.030172 +v 0.021427 0.064904 -0.062003 +v -0.011592 0.036452 -0.051761 +v 0.011643 0.036563 -0.053404 +v 0.012433 0.048647 -0.058073 +v 0.010008 0.048678 -0.076199 +v 0.026560 0.064937 -0.077276 +v 0.014352 0.056124 -0.060519 +v 0.013909 0.058875 -0.080333 +v 0.035257 0.063071 -0.090741 +v 0.014671 0.061496 -0.100203 +v 0.044748 0.057766 -0.100437 +v 0.020061 0.063318 -0.114016 +v 0.057666 0.047667 -0.108832 +v 0.067226 0.034813 -0.112889 +v 0.075454 0.016940 -0.114897 +v 0.077249 -0.000240 -0.115310 +v 0.051605 0.048044 -0.122165 +v 0.042554 0.055058 -0.117378 +v 0.031463 0.059968 -0.126207 +v 0.062896 0.034633 -0.127302 +v 0.070632 0.017264 -0.130163 +v 0.072797 -0.000240 -0.132994 +v 0.042569 0.053796 -0.132095 +v 0.057088 0.038528 -0.149044 +v 0.033899 0.057438 -0.150673 +v 0.034633 0.057780 -0.139827 +v 0.066844 0.018790 -0.152124 +v 0.068809 -0.000240 -0.157413 +v 0.044571 0.030164 -0.235268 +v 0.049648 0.021031 -0.231929 +v 0.052727 0.012598 -0.228476 +v 0.054525 0.006615 -0.225480 +v 0.055918 -0.000240 -0.222577 +v 0.054433 0.015646 -0.221489 +v 0.056237 0.009547 -0.218595 +v 0.052068 0.021934 -0.223415 +v 0.060447 0.018175 -0.188680 +v 0.051707 0.037163 -0.185117 +v 0.062517 -0.000240 -0.191120 +v 0.058990 -0.000240 -0.208651 +v 0.056640 0.017055 -0.209527 +v 0.048825 0.031272 -0.218611 +v 0.033360 0.044602 -0.238111 +v 0.035164 0.053426 -0.183740 +v 0.035233 0.049345 -0.213514 +v 0.016915 0.057905 -0.239959 +v -0.049987 -0.000240 -0.074095 +v -0.050002 0.004786 -0.075510 +v 0.008750 0.005298 -0.082837 +v 0.008311 -0.000240 -0.082899 +v -0.004001 0.006578 -0.084437 +v -0.049270 0.007267 -0.082138 +v -0.050032 0.019995 -0.078169 +v 0.008411 0.021511 -0.086118 +v -0.049928 0.024644 -0.079050 +v 0.007618 0.036799 -0.093094 +v -0.049850 0.035807 -0.085169 +v -0.049991 0.043139 -0.090420 +v 0.007022 0.058579 -0.119752 +v -0.049875 0.065331 -0.127254 +v 0.018481 0.063690 -0.135138 +v -0.049562 0.066632 -0.157743 +v 0.018132 0.063279 -0.152513 +v -0.049610 0.066708 -0.194135 +v 0.019649 0.061299 -0.187044 +v -0.049663 0.066334 -0.232044 +v 0.018748 0.059753 -0.214026 +v 0.013345 0.057597 -0.251320 +v -0.049451 0.061512 -0.264309 +v 0.008428 0.054317 -0.274922 +v -0.049834 0.056362 -0.284994 +v -0.049674 0.049619 -0.301524 +v -0.034328 0.044472 -0.311729 +v -0.025952 0.045515 -0.310719 +v -0.014959 0.047451 -0.307356 +v -0.008392 0.049463 -0.301149 +v -0.004395 0.050184 -0.298388 +v 0.001363 0.050008 -0.295027 +v 0.004997 0.052489 -0.284512 +v -0.006459 0.051547 -0.295982 +v -0.031675 0.049656 -0.301023 +v -0.010384 0.051098 -0.298594 +v -0.035197 0.022943 -0.362323 +v -0.046059 0.022945 -0.355836 +v -0.021383 0.025135 -0.363879 +v -0.035746 0.022937 -0.375410 +v -0.039232 0.023577 -0.366437 +v -0.037749 0.025366 -0.389772 +v -0.041708 0.022937 -0.385697 +v -0.058841 0.024695 -0.391829 +v -0.056711 0.022936 -0.387430 +v -0.067070 0.024612 -0.384014 +v -0.062647 0.022936 -0.381225 +v -0.069692 0.024562 -0.371977 +v -0.063772 0.022940 -0.371415 +v -0.048883 0.024435 -0.360798 +v -0.058924 0.023782 -0.349888 +v -0.056390 0.022943 -0.361987 +v -0.049812 0.016269 -0.083017 +v -0.048832 0.007455 -0.100897 +v -0.042507 0.007424 -0.109758 +v -0.041899 0.016401 -0.110110 +v -0.047770 0.016566 -0.103410 +v -0.022263 0.007266 -0.104138 +v -0.032304 0.007228 -0.111353 +v -0.030785 0.015854 -0.111746 +v -0.007517 0.018248 -0.086631 +v -0.023064 0.016249 -0.105888 +v -0.016255 0.037782 0.011158 +v -0.020063 0.037725 -0.000854 +v 0.002900 0.038473 0.019685 +v -0.007368 0.037836 0.018215 +v 0.017434 0.038086 -0.020092 +v 0.019784 0.038029 -0.002576 +v -0.025830 0.037387 -0.024984 +v -0.004320 0.036448 -0.019682 +v 0.002772 0.036438 -0.010565 +v 0.010044 0.036471 -0.004601 +v -0.006552 0.036483 -0.008660 +v -0.010807 0.036476 -0.000106 +v -0.006775 0.036473 0.008465 +v 0.013947 0.037687 0.013991 +v 0.002431 0.036468 0.010722 +v 0.009885 0.036471 0.004853 +v 0.002772 0.030533 -0.010565 +v 0.010044 0.030566 -0.004601 +v -0.006552 0.030578 -0.008660 +v -0.010807 0.030571 -0.000106 +v -0.006775 0.030568 0.008465 +v 0.009885 0.030566 0.004853 +v 0.002431 0.030563 0.010722 +v 0.001288 0.030550 -0.004592 +v 0.004455 0.030565 -0.001995 +v -0.002772 0.030570 -0.003762 +v -0.004625 0.030567 -0.000038 +v -0.002869 0.030566 0.003695 +v 0.004385 0.030565 0.002122 +v 0.001139 0.030563 0.004678 +v 0.001288 0.018873 -0.004592 +v 0.004455 0.018888 -0.001995 +v -0.002772 0.018893 -0.003762 +v -0.004625 0.018890 -0.000038 +v -0.002869 0.018889 0.003695 +v 0.004385 0.018888 0.002122 +v 0.001139 0.018887 0.004678 +v -0.036297 -0.047356 -0.334804 +v -0.024778 -0.047975 -0.332917 +v -0.026482 -0.046463 -0.344329 +v -0.033785 -0.046489 -0.343062 +v -0.013129 -0.047619 -0.332893 +v -0.018607 -0.043776 -0.343112 +v -0.036179 -0.050704 -0.320841 +v -0.019521 -0.051266 -0.320706 +v -0.002343 -0.047934 -0.324966 +v -0.005394 -0.074223 -0.035325 +v -0.012557 -0.074211 -0.030529 +v -0.007498 -0.073942 -0.026447 +v -0.001038 -0.074246 -0.028646 +v 0.004655 -0.074259 -0.036666 +v -0.006144 -0.074227 -0.040857 +v -0.017100 -0.074215 -0.037081 +v 0.006194 -0.074246 -0.047888 +v -0.006520 -0.074222 -0.047133 +v -0.022975 -0.074261 -0.047387 +v -0.009151 -0.074214 -0.063017 +v -0.028292 -0.074249 -0.060834 +v -0.012724 -0.074229 -0.081529 +v -0.032368 -0.074298 -0.078053 +v 0.007401 -0.074228 -0.063457 +v -0.015746 -0.074215 -0.102862 +v -0.032971 -0.074311 -0.100557 +v 0.011751 -0.074065 -0.084866 +v 0.003018 -0.074234 -0.104400 +v 0.025417 -0.071749 -0.108499 +v 0.009828 -0.073856 -0.119367 +v -0.012727 -0.074214 -0.126503 +v -0.031815 -0.074304 -0.125250 +v -0.035946 -0.057206 -0.304456 +v -0.017438 -0.057152 -0.305981 +v -0.000678 -0.054191 -0.308629 +v -0.032911 -0.063097 -0.289159 +v -0.015357 -0.062431 -0.292895 +v -0.010985 -0.069383 -0.268344 +v -0.027699 -0.069671 -0.266850 +v -0.006121 -0.073551 -0.234175 +v -0.027897 -0.073708 -0.233083 +v -0.003074 -0.073985 -0.195833 +v -0.027337 -0.074289 -0.194085 +v -0.003005 -0.074111 -0.178827 +v -0.025988 -0.074277 -0.159282 +v 0.000190 -0.074192 -0.149768 +v 0.020896 -0.071823 -0.138862 +v 0.041083 -0.064847 -0.126756 +v 0.001622 -0.059376 -0.294810 +v 0.007126 -0.065472 -0.270682 +v 0.011079 -0.070082 -0.236075 +v 0.016534 -0.070595 -0.197317 +v 0.017331 -0.071425 -0.175606 +v 0.035818 -0.065209 -0.157951 +v 0.055245 -0.053930 -0.139368 +v 0.012151 -0.049937 -0.307685 +v 0.013200 -0.044338 -0.319266 +v 0.015601 -0.053078 -0.295856 +v 0.020908 -0.058401 -0.271812 +v 0.026395 -0.062846 -0.237513 +v 0.032224 -0.063544 -0.200921 +v 0.040015 -0.060302 -0.184365 +v 0.053521 -0.051836 -0.166617 +v 0.067639 -0.038607 -0.144914 +v 0.057541 -0.043127 -0.186221 +v 0.054382 -0.043032 -0.203113 +v 0.047065 -0.043157 -0.237736 +v 0.041192 -0.038622 -0.270257 +v 0.036378 -0.034735 -0.292275 +v 0.044489 -0.017128 -0.291638 +v 0.041476 -0.015068 -0.303257 +v 0.048696 -0.023130 -0.270488 +v 0.056979 -0.023112 -0.238310 +v 0.064279 -0.023428 -0.204108 +v 0.071335 -0.021136 -0.171431 +v 0.076173 -0.018798 -0.147289 +v 0.032636 -0.034338 -0.303101 +v 0.030134 -0.030661 -0.315501 +v 0.037765 -0.013917 -0.316072 +v 0.032655 -0.014011 -0.332137 +v 0.026412 -0.026939 -0.331645 +v 0.016086 -0.037859 -0.331409 +v 0.002700 -0.043404 -0.335802 +v -0.007140 -0.045003 -0.341178 +v -0.014454 -0.044668 -0.351029 +v -0.027460 -0.045523 -0.352599 +v -0.043331 -0.045975 -0.349104 +v -0.032542 -0.042063 -0.359314 +v -0.021024 -0.041356 -0.361982 +v -0.048082 -0.042060 -0.354495 +v -0.047888 -0.040478 -0.358945 +v -0.038361 -0.042094 -0.363451 +v -0.034877 -0.041259 -0.373714 +v -0.037155 -0.040689 -0.389136 +v -0.038673 -0.042085 -0.385635 +v -0.054058 -0.041429 -0.392931 +v -0.053707 -0.042090 -0.389529 +v -0.066886 -0.041337 -0.383422 +v -0.063232 -0.042090 -0.382770 +v -0.069312 -0.040680 -0.370601 +v -0.065643 -0.042093 -0.371714 +v -0.061056 -0.042096 -0.363164 +v -0.058067 -0.041837 -0.349718 +v -0.049847 -0.045510 -0.334517 +v -0.051365 -0.030466 -0.335159 +v -0.049963 -0.037686 -0.327553 +v -0.054131 -0.036093 -0.340375 +v -0.055335 -0.029834 -0.342538 +v 0.044360 -0.020032 -0.235693 +v 0.041399 -0.026704 -0.237163 +v 0.034632 -0.034180 -0.239048 +v 0.035051 -0.024118 -0.238951 +v 0.045120 -0.013977 -0.235428 +v 0.034897 -0.015847 -0.238981 +v 0.034677 -0.008009 -0.239655 +v 0.043624 -0.007840 -0.236635 +v -0.009703 -0.008328 -0.257933 +v -0.000674 -0.007420 -0.262409 +v 0.000444 -0.007417 -0.257011 +v -0.004223 -0.008431 -0.249446 +v 0.010403 -0.007421 -0.256950 +v 0.008742 -0.008077 -0.245304 +v 0.023101 -0.007423 -0.255919 +v 0.020630 -0.007637 -0.243324 +v 0.032594 -0.007423 -0.253629 +v 0.004266 -0.007423 -0.271427 +v -0.007651 -0.008083 -0.272212 +v 0.024541 -0.007436 -0.268099 +v 0.032268 -0.007435 -0.263581 +v 0.038760 -0.007231 -0.252324 +v 0.038217 -0.006725 -0.262272 +v 0.043985 -0.004763 -0.249683 +v 0.048142 -0.005663 -0.233465 +v 0.045603 -0.001911 -0.248730 +v 0.050392 -0.002267 -0.231303 +v 0.029271 -0.007292 -0.279130 +v 0.041326 -0.004242 -0.261404 +v 0.042420 -0.001920 -0.261150 +v 0.009891 -0.007433 -0.286800 +v 0.033104 -0.005452 -0.280658 +v 0.034599 -0.003435 -0.281344 +v -0.002861 -0.008494 -0.289819 +v 0.017543 -0.005471 -0.292977 +v 0.018717 -0.002824 -0.294471 +v 0.001262 -0.003916 -0.299610 +v 0.000594 -0.006471 -0.297036 +v -0.000450 -0.012950 -0.300901 +v -0.002590 -0.015049 -0.297952 +v -0.048169 -0.024260 -0.330649 +v -0.042738 -0.024851 -0.321924 +v -0.043490 -0.035236 -0.321689 +v -0.039896 -0.023438 -0.336990 +v -0.036629 -0.023431 -0.330850 +v -0.028746 -0.023420 -0.325710 +v -0.029157 -0.025027 -0.315904 +v -0.018715 -0.023422 -0.324272 +v -0.020071 -0.024921 -0.315856 +v -0.006357 -0.023384 -0.319539 +v -0.010386 -0.023862 -0.311785 +v 0.001369 -0.021592 -0.314421 +v -0.004782 -0.020835 -0.305182 +v 0.003350 -0.008578 -0.311800 +v 0.005117 -0.020993 -0.324683 +v -0.010195 -0.024644 -0.347146 +v -0.016744 -0.025607 -0.355892 +v -0.019882 -0.023433 -0.341102 +v -0.026003 -0.023426 -0.346549 +v -0.005554 -0.024751 -0.343262 +v -0.016023 -0.023440 -0.337601 +v 0.001077 -0.022436 -0.338941 +v -0.011432 -0.023105 -0.334320 +v 0.007000 -0.016379 -0.336256 +v -0.002072 -0.021420 -0.329712 +v 0.011340 -0.007210 -0.334839 +v 0.004024 -0.014019 -0.329592 +v 0.018573 -0.016354 -0.242592 +v 0.019490 -0.027314 -0.242373 +v 0.019803 -0.042505 -0.242311 +v 0.006094 -0.016281 -0.245537 +v -0.004297 -0.016504 -0.249813 +v -0.009923 -0.016055 -0.258313 +v -0.008152 -0.015939 -0.272368 +v -0.000774 -0.017440 -0.256411 +v 0.006405 -0.017444 -0.253574 +v 0.015910 -0.017624 -0.248710 +v -0.005749 -0.015942 -0.280903 +v 0.000368 -0.017459 -0.270382 +v 0.002047 -0.017595 -0.279571 +v -0.002090 -0.022096 -0.294670 +v 0.002388 -0.022732 -0.294000 +v 0.003386 -0.036983 -0.306826 +v -0.005140 -0.037293 -0.306113 +v -0.009902 -0.036633 -0.310996 +v -0.021056 -0.036046 -0.315927 +v -0.030105 -0.035900 -0.315775 +v 0.017500 -0.027869 -0.247323 +v 0.020416 -0.017482 -0.266871 +v 0.011821 -0.017889 -0.280944 +v 0.016989 -0.042609 -0.250159 +v 0.013460 -0.033057 -0.277487 +v 0.013648 -0.044777 -0.275110 +v 0.012827 -0.022647 -0.295171 +v 0.012947 -0.032126 -0.280896 +v 0.011257 -0.037699 -0.307049 +v 0.012696 -0.044813 -0.282175 +v -0.048571 -0.049837 -0.321794 +v -0.048924 -0.055989 -0.304440 +v -0.047244 -0.043859 -0.314313 +v -0.048608 -0.062889 -0.287579 +v -0.048659 -0.068700 -0.267107 +v -0.048761 -0.073603 -0.233050 +v -0.048312 -0.074201 -0.194406 +v -0.047811 -0.074281 -0.158103 +v -0.048552 -0.074176 -0.126465 +v -0.048407 -0.074191 -0.100305 +v -0.047499 -0.073880 -0.073757 +v -0.049897 -0.058901 -0.108801 +v -0.050038 -0.058109 -0.093509 +v -0.050049 -0.064977 -0.089819 +v -0.049311 -0.063418 -0.079322 +v -0.050034 -0.052941 -0.085066 +v -0.049595 -0.046046 -0.074176 +v -0.049976 -0.030138 -0.067550 +v -0.045155 -0.037570 -0.061616 +v -0.023718 -0.007187 -0.064428 +v -0.049982 -0.007019 -0.063003 +v -0.022935 -0.017425 -0.066259 +v -0.049828 -0.017320 -0.064320 +v -0.020474 -0.029275 -0.069225 +v -0.013228 -0.037003 -0.063079 +v 0.008851 -0.025917 -0.072742 +v 0.009193 -0.035894 -0.069586 +v 0.008917 -0.014675 -0.069799 +v 0.008406 -0.005197 -0.068566 +v 0.080370 -0.018853 -0.116812 +v 0.072017 -0.038650 -0.115979 +v 0.060422 -0.053019 -0.111950 +v 0.046994 -0.063416 -0.103241 +v 0.034707 -0.069698 -0.092242 +v 0.024514 -0.072968 -0.077073 +v 0.019402 -0.073884 -0.060890 +v 0.016312 -0.074065 -0.046332 +v 0.013789 -0.073987 -0.032151 +v 0.015622 -0.068552 -0.033490 +v 0.016902 -0.070332 -0.040795 +v 0.006506 -0.073870 -0.020886 +v -0.005275 -0.073720 -0.017005 +v -0.015787 -0.073889 -0.020928 +v -0.022850 -0.074112 -0.029336 +v -0.040562 -0.060748 -0.051358 +v -0.030039 -0.074131 -0.039049 +v -0.038600 -0.074189 -0.051648 +v -0.037081 -0.071965 -0.045559 +v -0.035090 -0.070239 -0.042554 +v 0.016337 -0.065963 -0.034782 +v 0.017218 -0.066783 -0.042835 +v 0.010847 -0.066463 -0.022453 +v -0.002254 -0.066732 -0.015532 +v -0.016708 -0.065444 -0.018987 +v -0.022435 -0.065910 -0.024706 +v -0.027019 -0.066402 -0.030910 +v -0.037072 -0.064493 -0.045548 +v -0.032229 -0.066542 -0.037781 +v -0.038235 -0.038626 -0.047819 +v -0.031475 -0.050202 -0.036224 +v -0.024448 -0.058212 -0.020768 +v -0.014467 -0.058741 -0.013560 +v 0.002728 -0.057104 -0.014942 +v -0.011283 -0.052962 -0.010453 +v 0.003581 -0.050341 -0.014707 +v -0.023109 -0.054412 -0.015299 +v -0.018768 -0.050057 0.001933 +v -0.025460 -0.045819 -0.022495 +v -0.020290 -0.044042 -0.000815 +v -0.017023 -0.044357 0.010329 +v -0.016685 -0.049490 0.009712 +v 0.001109 -0.049272 0.019433 +v -0.008427 -0.048672 0.017761 +v -0.008907 -0.043825 0.017732 +v 0.001612 -0.043251 0.019801 +v 0.013580 -0.043318 0.014564 +v 0.012620 -0.049351 0.014818 +v 0.019159 -0.049826 -0.001200 +v 0.016911 -0.050051 0.007878 +v 0.017372 -0.052966 -0.014247 +v 0.016488 -0.058478 -0.023305 +v 0.016969 -0.058265 -0.040873 +v 0.018947 -0.063175 -0.050702 +v 0.016312 -0.050784 -0.030172 +v 0.021427 -0.065385 -0.062003 +v -0.011592 -0.036933 -0.051761 +v 0.011643 -0.037043 -0.053404 +v 0.010008 -0.049159 -0.076199 +v 0.012433 -0.049128 -0.058073 +v 0.026560 -0.065417 -0.077276 +v 0.014352 -0.056605 -0.060519 +v 0.013909 -0.059355 -0.080333 +v 0.035257 -0.063551 -0.090741 +v 0.014671 -0.061976 -0.100203 +v 0.044748 -0.058247 -0.100437 +v 0.020061 -0.063798 -0.114016 +v 0.057666 -0.048148 -0.108833 +v 0.067226 -0.035293 -0.112889 +v 0.075454 -0.017420 -0.114897 +v 0.051605 -0.048524 -0.122165 +v 0.042554 -0.055538 -0.117378 +v 0.031463 -0.060449 -0.126207 +v 0.062896 -0.035113 -0.127302 +v 0.070632 -0.017745 -0.130163 +v 0.042569 -0.054277 -0.132095 +v 0.033899 -0.057918 -0.150673 +v 0.057088 -0.039008 -0.149044 +v 0.034633 -0.058261 -0.139827 +v 0.066844 -0.019270 -0.152124 +v 0.049648 -0.021511 -0.231929 +v 0.044571 -0.030644 -0.235268 +v 0.052727 -0.013079 -0.228476 +v 0.054525 -0.007096 -0.225480 +v 0.056237 -0.010027 -0.218595 +v 0.054433 -0.016126 -0.221489 +v 0.052068 -0.022414 -0.223415 +v 0.060447 -0.018655 -0.188680 +v 0.051707 -0.037643 -0.185117 +v 0.056640 -0.017535 -0.209527 +v 0.048825 -0.031752 -0.218611 +v 0.033360 -0.045082 -0.238111 +v 0.035164 -0.053906 -0.183740 +v 0.035233 -0.049825 -0.213514 +v 0.016915 -0.058386 -0.239959 +v -0.050002 -0.005266 -0.075510 +v 0.008750 -0.005778 -0.082837 +v -0.004001 -0.007059 -0.084437 +v -0.049270 -0.007748 -0.082138 +v -0.050032 -0.020476 -0.078169 +v 0.008411 -0.021992 -0.086118 +v -0.049928 -0.025124 -0.079050 +v 0.007618 -0.037280 -0.093094 +v -0.049850 -0.036288 -0.085169 +v -0.049991 -0.043619 -0.090420 +v 0.007022 -0.059059 -0.119752 +v -0.049875 -0.065812 -0.127255 +v 0.018481 -0.064170 -0.135138 +v -0.049562 -0.067112 -0.157743 +v 0.018132 -0.063760 -0.152513 +v -0.049610 -0.067189 -0.194135 +v 0.019649 -0.061780 -0.187044 +v -0.049663 -0.066815 -0.232044 +v 0.018748 -0.060234 -0.214026 +v 0.013345 -0.058078 -0.251320 +v -0.049451 -0.061993 -0.264309 +v 0.008428 -0.054798 -0.274922 +v -0.049834 -0.056842 -0.284994 +v -0.049674 -0.050099 -0.301524 +v -0.034328 -0.044953 -0.311729 +v -0.025952 -0.045995 -0.310719 +v -0.014959 -0.047932 -0.307356 +v -0.008392 -0.049944 -0.301149 +v -0.004395 -0.050665 -0.298388 +v 0.001363 -0.050488 -0.295027 +v 0.004997 -0.052970 -0.284512 +v -0.006459 -0.052027 -0.295982 +v -0.010384 -0.051578 -0.298594 +v -0.031675 -0.050136 -0.301023 +v -0.035197 -0.023423 -0.362323 +v -0.046059 -0.023426 -0.355836 +v -0.021383 -0.025615 -0.363879 +v -0.035746 -0.023417 -0.375410 +v -0.039232 -0.024058 -0.366437 +v -0.037749 -0.025847 -0.389772 +v -0.041708 -0.023418 -0.385697 +v -0.058841 -0.025176 -0.391829 +v -0.056711 -0.023416 -0.387430 +v -0.067070 -0.025093 -0.384014 +v -0.062647 -0.023416 -0.381225 +v -0.069692 -0.025043 -0.371977 +v -0.063772 -0.023420 -0.371415 +v -0.048883 -0.024915 -0.360798 +v -0.058924 -0.024263 -0.349888 +v -0.056390 -0.023423 -0.361987 +v -0.049812 -0.016750 -0.083017 +v -0.041899 -0.016882 -0.110110 +v -0.042507 -0.007904 -0.109758 +v -0.048832 -0.007935 -0.100897 +v -0.047770 -0.017046 -0.103410 +v -0.032304 -0.007709 -0.111353 +v -0.022263 -0.007747 -0.104138 +v -0.030785 -0.016334 -0.111746 +v -0.007517 -0.018729 -0.086631 +v -0.023064 -0.016730 -0.105888 +v -0.016255 -0.038262 0.011158 +v -0.020063 -0.038205 -0.000854 +v -0.007368 -0.038317 0.018215 +v 0.002900 -0.038954 0.019684 +v 0.017434 -0.038567 -0.020092 +v 0.019784 -0.038509 -0.002576 +v -0.025830 -0.037867 -0.024984 +v 0.002772 -0.036918 -0.010565 +v -0.004320 -0.036928 -0.019682 +v 0.010044 -0.036952 -0.004601 +v -0.006552 -0.036964 -0.008660 +v -0.010807 -0.036956 -0.000106 +v -0.006775 -0.036953 0.008465 +v 0.002431 -0.036948 0.010722 +v 0.013947 -0.038168 0.013991 +v 0.009885 -0.036952 0.004852 +v 0.010044 -0.031046 -0.004601 +v 0.002772 -0.031013 -0.010565 +v -0.006552 -0.031059 -0.008660 +v -0.010807 -0.031051 -0.000106 +v -0.006775 -0.031049 0.008465 +v 0.002431 -0.031044 0.010722 +v 0.009885 -0.031047 0.004852 +v 0.004455 -0.031045 -0.001995 +v 0.001288 -0.031030 -0.004592 +v -0.002772 -0.031050 -0.003762 +v -0.004625 -0.031047 -0.000038 +v -0.002869 -0.031046 0.003695 +v 0.001139 -0.031044 0.004678 +v 0.004385 -0.031045 0.002122 +v 0.004455 -0.019368 -0.001995 +v 0.001288 -0.019354 -0.004592 +v -0.002772 -0.019373 -0.003762 +v -0.004625 -0.019371 -0.000038 +v -0.002869 -0.019369 0.003695 +v 0.001139 -0.019367 0.004678 +v 0.004385 -0.019369 0.002122 +# 1246 vertices, 0 vertices normals + +f 1 4 3 +f 3 2 1 +f 2 6 1 +f 6 2 5 +f 5 8 6 +f 8 5 7 +f 7 10 8 +f 10 7 9 +f 12 11 13 +f 13 11 14 +f 9 12 10 +f 12 9 11 +f 17 11 16 +f 16 15 17 +f 16 11 18 +f 11 9 18 +f 16 19 15 +f 19 16 18 +f 20 9 7 +f 9 20 18 +f 18 21 19 +f 21 18 20 +f 7 5 22 +f 7 22 20 +f 26 25 23 +f 25 24 23 +f 2 28 27 +f 28 2 3 +f 30 27 28 +f 27 30 29 +f 2 27 5 +f 5 27 22 +f 30 23 29 +f 23 30 26 +f 31 23 24 +f 23 31 32 +f 32 29 23 +f 29 32 33 +f 15 32 31 +f 32 15 19 +f 32 21 33 +f 21 32 19 +f 22 21 20 +f 22 33 21 +f 29 22 27 +f 22 29 33 +f 15 34 17 +f 34 15 31 +f 31 35 34 +f 35 31 24 +f 36 24 25 +f 24 36 35 +f 37 35 36 +f 35 37 38 +f 38 34 35 +f 34 38 39 +f 39 17 34 +f 17 39 40 +f 40 11 17 +f 11 40 14 +f 14 41 13 +f 41 14 40 +f 13 42 12 +f 42 13 41 +f 41 44 42 +f 44 41 43 +f 40 43 41 +f 43 40 45 +f 39 45 40 +f 45 39 46 +f 38 46 39 +f 46 38 47 +f 37 47 38 +f 47 37 48 +f 48 50 47 +f 50 48 49 +f 47 51 46 +f 51 47 50 +f 46 52 45 +f 52 46 51 +f 45 53 43 +f 53 45 52 +f 43 53 44 +f 44 53 54 +f 53 55 54 +f 54 55 56 +f 52 57 53 +f 53 57 55 +f 58 52 51 +f 52 58 57 +f 50 58 51 +f 58 50 59 +f 60 50 49 +f 50 60 59 +f 60 61 59 +f 59 61 62 +f 62 58 59 +f 58 62 63 +f 58 63 57 +f 57 63 64 +f 64 66 65 +f 66 64 63 +f 57 67 55 +f 67 57 64 +f 55 68 56 +f 68 55 67 +f 67 69 68 +f 68 69 70 +f 64 71 67 +f 67 71 69 +f 71 65 72 +f 65 71 64 +f 71 73 69 +f 73 71 72 +f 69 74 70 +f 74 69 73 +f 73 76 74 +f 76 73 75 +f 78 80 79 +f 80 78 77 +f 82 77 78 +f 77 82 81 +f 75 82 76 +f 82 75 81 +f 84 77 81 +f 77 84 83 +f 85 81 75 +f 75 73 85 +f 86 81 85 +f 81 86 84 +f 85 72 87 +f 72 85 73 +f 87 88 86 +f 86 85 87 +f 87 65 89 +f 65 87 72 +f 90 88 89 +f 88 87 89 +f 89 66 91 +f 66 89 65 +f 62 66 63 +f 66 62 91 +f 89 91 90 +f 90 91 92 +f 93 62 61 +f 62 93 91 +f 91 93 92 +f 92 93 94 +f 80 95 79 +f 79 95 96 +f 83 80 77 +f 80 83 97 +f 97 95 80 +f 95 97 98 +f 100 3 99 +f 99 3 4 +f 102 100 99 +f 100 102 101 +f 104 101 102 +f 101 104 103 +f 106 103 104 +f 103 106 105 +f 107 110 109 +f 107 109 108 +f 110 105 106 +f 105 110 107 +f 112 113 107 +f 113 112 111 +f 107 114 105 +f 114 107 113 +f 115 113 111 +f 113 115 114 +f 116 105 114 +f 105 116 103 +f 117 114 115 +f 114 117 116 +f 116 118 103 +f 103 118 101 +f 119 120 25 +f 119 25 26 +f 100 28 3 +f 28 100 121 +f 121 30 28 +f 30 121 122 +f 100 101 121 +f 101 118 121 +f 119 30 122 +f 30 119 26 +f 123 119 124 +f 119 123 120 +f 124 122 125 +f 122 124 119 +f 111 124 115 +f 124 111 123 +f 117 124 125 +f 124 117 115 +f 117 125 118 +f 117 118 116 +f 125 122 118 +f 118 122 121 +f 111 126 123 +f 126 111 112 +f 123 127 120 +f 127 123 126 +f 120 36 25 +f 36 120 127 +f 128 37 127 +f 36 127 37 +f 127 126 128 +f 126 129 128 +f 126 112 129 +f 112 130 129 +f 112 107 130 +f 130 107 108 +f 131 108 109 +f 108 131 130 +f 132 109 110 +f 109 132 131 +f 131 134 133 +f 134 131 132 +f 130 133 135 +f 133 130 131 +f 129 135 136 +f 135 129 130 +f 128 136 137 +f 136 128 129 +f 137 37 128 +f 37 137 48 +f 48 138 49 +f 138 48 137 +f 137 139 138 +f 139 137 136 +f 136 140 139 +f 140 136 135 +f 135 141 140 +f 141 135 133 +f 133 134 141 +f 134 142 141 +f 143 141 142 +f 142 144 143 +f 140 141 145 +f 141 143 145 +f 139 140 146 +f 140 145 146 +f 138 146 147 +f 146 138 139 +f 49 138 60 +f 138 147 60 +f 60 147 61 +f 147 148 61 +f 147 146 148 +f 146 149 148 +f 146 145 149 +f 145 150 149 +f 150 152 149 +f 152 150 151 +f 145 153 150 +f 153 145 143 +f 154 143 144 +f 143 154 153 +f 153 154 155 +f 154 156 155 +f 157 150 153 +f 153 155 157 +f 151 157 158 +f 157 151 150 +f 159 157 155 +f 157 159 158 +f 160 155 156 +f 155 160 159 +f 159 162 161 +f 162 159 160 +f 166 164 163 +f 164 166 165 +f 163 168 166 +f 168 163 167 +f 168 161 162 +f 161 168 167 +f 169 163 170 +f 163 169 167 +f 171 161 167 +f 161 171 159 +f 172 167 169 +f 167 172 171 +f 171 158 159 +f 158 171 173 +f 173 172 174 +f 172 173 171 +f 173 151 158 +f 151 173 175 +f 176 175 174 +f 174 175 173 +f 175 152 151 +f 152 175 177 +f 148 152 177 +f 152 148 149 +f 175 176 177 +f 176 178 177 +f 61 148 93 +f 148 177 93 +f 93 178 94 +f 93 177 178 +f 179 164 165 +f 165 180 179 +f 170 163 164 +f 170 164 181 +f 181 179 182 +f 179 181 164 +f 186 185 183 +f 185 184 183 +f 188 186 183 +f 186 188 187 +f 190 187 188 +f 187 190 189 +f 192 189 190 +f 189 192 191 +f 193 196 195 +f 193 195 194 +f 196 191 192 +f 191 196 193 +f 198 199 193 +f 199 198 197 +f 193 200 191 +f 200 193 199 +f 201 199 197 +f 199 201 200 +f 202 191 200 +f 191 202 189 +f 203 200 201 +f 200 203 202 +f 202 204 189 +f 187 189 204 +f 205 208 207 +f 205 207 206 +f 186 210 185 +f 210 186 209 +f 209 212 210 +f 212 209 211 +f 186 187 209 +f 187 204 209 +f 205 212 211 +f 212 205 206 +f 213 205 214 +f 205 213 208 +f 214 211 215 +f 211 214 205 +f 197 214 201 +f 214 197 213 +f 203 214 215 +f 214 203 201 +f 203 215 204 +f 203 204 202 +f 215 211 204 +f 204 211 209 +f 197 216 213 +f 216 197 198 +f 213 217 208 +f 217 213 216 +f 208 218 207 +f 218 208 217 +f 220 219 217 +f 218 217 219 +f 217 216 220 +f 216 221 220 +f 216 198 221 +f 198 222 221 +f 198 193 222 +f 222 193 194 +f 223 194 195 +f 194 223 222 +f 224 195 196 +f 195 224 223 +f 223 224 225 +f 224 226 225 +f 222 225 227 +f 225 222 223 +f 221 227 228 +f 227 221 222 +f 220 228 229 +f 228 220 221 +f 229 219 220 +f 219 229 230 +f 230 232 231 +f 232 230 229 +f 229 233 232 +f 233 229 228 +f 228 234 233 +f 234 228 227 +f 227 235 234 +f 235 227 225 +f 235 225 226 +f 226 236 235 +f 237 235 236 +f 236 238 237 +f 234 235 239 +f 235 237 239 +f 233 234 240 +f 234 239 240 +f 232 240 241 +f 240 232 233 +f 231 232 242 +f 232 241 242 +f 242 241 243 +f 241 244 243 +f 241 240 244 +f 240 245 244 +f 240 239 245 +f 239 246 245 +f 246 248 245 +f 248 246 247 +f 239 237 246 +f 237 249 246 +f 250 237 238 +f 237 250 249 +f 249 250 251 +f 250 252 251 +f 253 246 249 +f 249 251 253 +f 247 253 254 +f 253 247 246 +f 255 253 251 +f 253 255 254 +f 256 251 252 +f 251 256 255 +f 255 258 257 +f 258 255 256 +f 262 260 259 +f 260 262 261 +f 259 264 262 +f 264 259 263 +f 264 257 258 +f 257 264 263 +f 265 259 266 +f 259 265 263 +f 263 267 257 +f 257 267 255 +f 268 263 265 +f 263 268 267 +f 267 254 255 +f 254 267 269 +f 269 268 270 +f 268 269 267 +f 269 247 254 +f 247 269 271 +f 272 271 270 +f 270 271 269 +f 271 248 247 +f 248 271 273 +f 244 248 273 +f 248 244 245 +f 271 272 273 +f 272 274 273 +f 243 244 275 +f 244 273 275 +f 275 274 276 +f 275 273 274 +f 260 278 277 +f 278 260 261 +f 266 259 260 +f 266 260 279 +f 279 277 280 +f 277 279 260 +f 281 184 185 +f 185 282 281 +f 282 284 281 +f 284 282 283 +f 283 286 284 +f 286 283 285 +f 285 288 286 +f 288 285 287 +f 290 289 291 +f 291 289 292 +f 287 290 288 +f 290 287 289 +f 295 289 294 +f 294 293 295 +f 294 289 296 +f 289 287 296 +f 294 297 293 +f 297 294 296 +f 287 285 298 +f 287 298 296 +f 296 299 297 +f 299 296 298 +f 285 283 300 +f 285 300 298 +f 206 207 301 +f 207 302 301 +f 282 210 303 +f 210 282 185 +f 212 303 210 +f 303 212 304 +f 282 303 283 +f 283 303 300 +f 212 301 304 +f 301 212 206 +f 305 301 302 +f 301 305 306 +f 306 304 301 +f 304 306 307 +f 293 306 305 +f 306 293 297 +f 306 299 307 +f 299 306 297 +f 300 299 298 +f 300 307 299 +f 304 300 303 +f 300 304 307 +f 293 308 295 +f 308 293 305 +f 305 309 308 +f 309 305 302 +f 218 302 207 +f 302 218 309 +f 219 309 218 +f 309 219 310 +f 310 308 309 +f 308 310 311 +f 311 295 308 +f 295 311 312 +f 312 289 295 +f 289 312 292 +f 292 313 291 +f 313 292 312 +f 291 314 290 +f 314 291 313 +f 315 314 313 +f 314 315 316 +f 312 315 313 +f 315 312 317 +f 311 317 312 +f 317 311 318 +f 310 318 311 +f 318 310 319 +f 219 319 310 +f 319 219 230 +f 230 320 319 +f 320 230 231 +f 319 321 318 +f 321 319 320 +f 318 322 317 +f 322 318 321 +f 317 323 315 +f 323 317 322 +f 315 323 316 +f 316 323 324 +f 323 325 324 +f 324 325 326 +f 322 327 323 +f 323 327 325 +f 328 322 321 +f 322 328 327 +f 320 328 321 +f 328 320 329 +f 242 320 231 +f 320 242 329 +f 242 243 329 +f 329 243 330 +f 330 328 329 +f 328 330 331 +f 328 331 327 +f 327 331 332 +f 332 334 333 +f 334 332 331 +f 327 332 325 +f 325 332 335 +f 325 336 326 +f 336 325 335 +f 335 337 336 +f 336 337 338 +f 332 339 335 +f 335 339 337 +f 339 333 340 +f 333 339 332 +f 339 341 337 +f 341 339 340 +f 337 342 338 +f 342 337 341 +f 341 344 342 +f 344 341 343 +f 346 348 347 +f 348 346 345 +f 350 345 346 +f 345 350 349 +f 343 350 344 +f 350 343 349 +f 352 345 349 +f 345 352 351 +f 353 349 343 +f 343 341 353 +f 354 349 353 +f 349 354 352 +f 353 340 355 +f 340 353 341 +f 355 356 354 +f 354 353 355 +f 355 333 357 +f 333 355 340 +f 358 356 357 +f 356 355 357 +f 357 334 359 +f 334 357 333 +f 330 334 331 +f 334 330 359 +f 357 359 358 +f 358 359 360 +f 275 330 243 +f 330 275 359 +f 359 275 360 +f 360 275 276 +f 348 362 347 +f 362 348 361 +f 351 348 345 +f 348 351 363 +f 363 361 348 +f 361 363 364 +f 1 184 4 +f 184 1 183 +f 1 188 183 +f 188 1 6 +f 190 6 8 +f 6 190 188 +f 192 190 10 +f 190 8 10 +f 196 192 12 +f 192 10 12 +f 12 224 196 +f 224 12 42 +f 42 226 224 +f 226 42 44 +f 44 54 226 +f 226 54 236 +f 54 238 236 +f 238 54 56 +f 56 250 238 +f 250 56 68 +f 68 252 250 +f 252 68 70 +f 70 256 252 +f 256 70 74 +f 74 258 256 +f 258 74 76 +f 79 262 78 +f 262 79 261 +f 82 262 264 +f 262 82 78 +f 82 258 76 +f 258 82 264 +f 83 265 266 +f 265 83 84 +f 84 268 265 +f 268 84 86 +f 88 268 86 +f 268 88 270 +f 88 272 270 +f 272 88 90 +f 90 274 272 +f 274 90 92 +f 92 276 274 +f 276 92 94 +f 278 96 277 +f 96 95 277 +f 96 261 79 +f 261 96 278 +f 266 97 83 +f 97 266 279 +f 279 280 97 +f 97 280 98 +f 95 98 277 +f 277 98 280 +f 99 184 281 +f 184 99 4 +f 99 284 102 +f 284 99 281 +f 104 102 286 +f 286 102 284 +f 106 286 288 +f 286 106 104 +f 110 288 290 +f 288 110 106 +f 132 110 314 +f 314 110 290 +f 134 132 316 +f 314 316 132 +f 316 142 134 +f 142 316 324 +f 324 326 142 +f 142 326 144 +f 326 336 144 +f 144 336 154 +f 336 338 154 +f 154 338 156 +f 338 342 156 +f 156 342 160 +f 342 344 160 +f 160 344 162 +f 165 346 347 +f 346 165 166 +f 350 346 168 +f 168 346 166 +f 344 168 162 +f 168 344 350 +f 170 352 169 +f 352 170 351 +f 169 354 172 +f 354 169 352 +f 174 354 356 +f 354 174 172 +f 174 358 176 +f 358 174 356 +f 178 176 360 +f 360 176 358 +f 94 178 276 +f 276 178 360 +f 180 362 361 +f 361 179 180 +f 180 347 362 +f 347 180 165 +f 181 351 170 +f 351 181 363 +f 182 361 364 +f 361 182 179 +f 181 364 363 +f 364 181 182 +f 366 368 367 +f 368 366 365 +f 370 369 366 +f 366 369 365 +f 371 366 372 +f 372 366 367 +f 370 371 373 +f 371 370 366 +f 377 376 374 +f 376 375 374 +f 379 376 377 +f 376 379 378 +f 376 380 375 +f 380 376 378 +f 378 379 382 +f 378 382 381 +f 380 378 381 +f 381 383 380 +f 383 381 385 +f 385 384 383 +f 386 384 385 +f 384 386 387 +f 388 381 382 +f 381 388 385 +f 386 389 387 +f 389 386 390 +f 386 388 391 +f 388 386 385 +f 386 392 390 +f 392 386 391 +f 392 394 393 +f 394 392 391 +f 392 395 390 +f 395 392 393 +f 390 396 389 +f 396 390 395 +f 371 398 397 +f 398 371 372 +f 397 399 371 +f 399 373 371 +f 397 401 400 +f 401 397 398 +f 400 403 402 +f 403 400 401 +f 405 404 403 +f 404 402 403 +f 407 406 405 +f 406 404 405 +f 409 408 407 +f 408 406 407 +f 395 409 396 +f 409 395 410 +f 410 393 411 +f 393 410 395 +f 394 411 393 +f 411 394 412 +f 399 400 413 +f 400 399 397 +f 413 402 414 +f 402 413 400 +f 414 404 415 +f 404 414 402 +f 415 406 416 +f 406 415 404 +f 417 416 408 +f 408 416 406 +f 408 409 410 +f 410 417 408 +f 417 410 411 +f 417 411 418 +f 418 412 419 +f 412 418 411 +f 399 420 373 +f 420 399 421 +f 421 413 422 +f 413 421 399 +f 422 414 423 +f 414 422 413 +f 423 415 424 +f 415 423 414 +f 425 415 416 +f 415 425 424 +f 426 416 417 +f 416 426 425 +f 426 418 427 +f 418 426 417 +f 427 419 428 +f 419 427 418 +f 429 426 430 +f 426 429 425 +f 431 425 429 +f 425 431 424 +f 432 424 431 +f 424 432 423 +f 433 423 432 +f 423 433 422 +f 435 434 436 +f 436 434 437 +f 433 432 438 +f 438 436 433 +f 439 436 438 +f 436 439 435 +f 432 431 440 +f 440 438 432 +f 441 439 440 +f 440 439 438 +f 429 442 431 +f 442 440 431 +f 441 442 443 +f 442 441 440 +f 430 442 429 +f 442 430 444 +f 428 445 444 +f 444 427 428 +f 430 427 444 +f 427 430 426 +f 446 442 444 +f 442 446 443 +f 445 447 444 +f 447 446 444 +f 421 449 448 +f 421 448 420 +f 437 448 449 +f 448 437 450 +f 449 422 433 +f 422 449 421 +f 436 449 433 +f 449 436 437 +f 434 451 437 +f 437 451 450 +f 450 451 453 +f 450 453 452 +f 450 454 448 +f 454 450 452 +f 420 448 454 +f 420 454 455 +f 420 456 373 +f 456 420 455 +f 370 456 457 +f 456 370 373 +f 369 457 458 +f 457 369 370 +f 369 459 365 +f 459 369 458 +f 368 365 459 +f 459 460 368 +f 462 459 458 +f 459 462 461 +f 461 460 459 +f 460 461 463 +f 463 465 464 +f 465 463 461 +f 466 461 462 +f 461 466 465 +f 468 466 462 +f 466 468 467 +f 468 469 467 +f 469 468 470 +f 471 469 470 +f 470 472 471 +f 473 472 474 +f 472 473 471 +f 464 475 463 +f 475 464 476 +f 367 460 477 +f 460 367 368 +f 460 463 475 +f 475 477 460 +f 474 475 476 +f 474 476 473 +f 479 478 480 +f 480 478 481 +f 477 475 478 +f 478 479 477 +f 485 484 483 +f 483 482 485 +f 484 487 486 +f 487 484 485 +f 487 488 486 +f 488 487 489 +f 490 492 491 +f 492 490 493 +f 494 493 490 +f 494 490 495 +f 496 494 495 +f 495 497 496 +f 496 498 489 +f 498 496 497 +f 495 491 499 +f 491 495 490 +f 491 492 500 +f 500 499 491 +f 495 501 497 +f 501 495 499 +f 497 502 498 +f 502 497 501 +f 489 503 488 +f 503 489 498 +f 498 504 503 +f 504 498 502 +f 488 506 505 +f 506 488 503 +f 505 508 507 +f 505 506 508 +f 507 510 509 +f 510 507 508 +f 502 511 504 +f 501 511 502 +f 503 512 506 +f 512 503 504 +f 513 510 508 +f 508 514 513 +f 506 514 508 +f 514 506 512 +f 501 499 515 +f 515 511 501 +f 504 516 512 +f 516 504 511 +f 517 513 514 +f 514 518 517 +f 514 516 518 +f 516 514 512 +f 500 519 499 +f 519 515 499 +f 511 515 520 +f 520 516 511 +f 521 518 522 +f 518 521 517 +f 516 520 522 +f 522 518 516 +f 522 524 523 +f 522 523 521 +f 520 525 524 +f 520 524 522 +f 515 519 525 +f 525 520 515 +f 525 527 526 +f 527 525 519 +f 528 530 529 +f 528 480 530 +f 531 530 532 +f 530 531 529 +f 529 534 533 +f 534 529 531 +f 535 533 534 +f 535 534 536 +f 535 538 537 +f 538 535 536 +f 540 537 538 +f 537 540 539 +f 540 526 539 +f 539 526 527 +f 541 524 526 +f 526 524 525 +f 541 540 542 +f 540 541 526 +f 541 523 524 +f 523 541 543 +f 544 458 545 +f 457 545 458 +f 544 547 546 +f 547 544 545 +f 546 531 532 +f 531 546 547 +f 545 457 548 +f 548 457 456 +f 545 549 547 +f 549 545 548 +f 547 534 531 +f 534 547 549 +f 456 550 548 +f 550 456 455 +f 548 551 549 +f 551 548 550 +f 549 536 534 +f 536 549 551 +f 455 454 552 +f 455 552 550 +f 550 553 551 +f 553 550 552 +f 551 538 536 +f 538 551 553 +f 538 542 540 +f 542 538 553 +f 452 554 454 +f 454 554 552 +f 552 555 553 +f 555 552 554 +f 453 554 452 +f 554 453 556 +f 557 554 556 +f 554 557 555 +f 557 542 555 +f 555 542 553 +f 541 557 543 +f 557 541 542 +f 558 496 487 +f 487 496 489 +f 485 558 487 +f 558 485 559 +f 482 560 559 +f 482 559 485 +f 561 494 558 +f 558 494 496 +f 562 493 561 +f 561 493 494 +f 562 492 493 +f 492 562 563 +f 500 492 563 +f 563 564 500 +f 564 563 565 +f 565 563 562 +f 562 561 566 +f 562 566 565 +f 561 567 566 +f 561 558 567 +f 500 568 519 +f 568 500 564 +f 569 565 566 +f 565 569 564 +f 569 568 564 +f 568 569 570 +f 519 571 527 +f 571 519 568 +f 568 570 572 +f 568 572 571 +f 573 571 574 +f 574 571 572 +f 539 527 571 +f 571 573 539 +f 575 537 573 +f 539 573 537 +f 535 575 576 +f 575 535 537 +f 577 533 576 +f 576 533 535 +f 577 529 533 +f 529 577 528 +f 559 567 558 +f 567 559 578 +f 579 566 567 +f 566 579 569 +f 580 569 579 +f 569 580 570 +f 581 578 560 +f 559 560 578 +f 567 578 579 +f 578 582 579 +f 582 578 581 +f 581 583 582 +f 580 572 570 +f 572 580 584 +f 585 584 580 +f 582 580 579 +f 580 582 585 +f 574 584 586 +f 584 574 572 +f 586 585 587 +f 585 586 584 +f 582 583 587 +f 587 585 582 +f 588 367 477 +f 367 588 372 +f 589 372 588 +f 372 589 398 +f 479 588 477 +f 588 479 590 +f 590 479 528 +f 480 528 479 +f 591 398 589 +f 398 591 401 +f 592 401 591 +f 401 592 403 +f 593 403 592 +f 403 593 405 +f 594 405 593 +f 405 594 407 +f 595 407 594 +f 407 595 409 +f 396 595 596 +f 595 396 409 +f 597 396 596 +f 396 597 389 +f 387 597 598 +f 597 387 389 +f 600 597 601 +f 597 600 599 +f 598 599 602 +f 598 597 599 +f 600 603 599 +f 603 602 599 +f 604 606 605 +f 607 609 608 +f 609 607 610 +f 611 608 612 +f 608 611 607 +f 604 612 613 +f 612 604 611 +f 614 606 613 +f 613 606 604 +f 614 616 615 +f 616 614 613 +f 616 612 617 +f 612 616 613 +f 617 608 618 +f 608 617 612 +f 608 619 618 +f 619 608 609 +f 620 445 621 +f 445 620 447 +f 621 428 622 +f 428 621 445 +f 622 419 623 +f 622 428 419 +f 623 419 412 +f 623 412 624 +f 624 412 394 +f 394 625 624 +f 394 391 625 +f 391 626 625 +f 627 626 388 +f 391 388 626 +f 628 627 382 +f 382 627 388 +f 629 628 379 +f 379 628 382 +f 629 630 628 +f 630 629 631 +f 379 377 629 +f 377 632 629 +f 377 633 632 +f 633 377 374 +f 634 374 375 +f 374 634 633 +f 635 375 380 +f 375 635 634 +f 603 605 602 +f 605 636 602 +f 637 380 383 +f 380 637 635 +f 638 383 384 +f 383 638 637 +f 637 638 640 +f 639 637 640 +f 598 638 384 +f 598 384 387 +f 598 636 638 +f 602 636 598 +f 642 630 631 +f 630 642 641 +f 643 629 632 +f 629 643 631 +f 644 632 633 +f 632 644 643 +f 645 633 634 +f 633 645 644 +f 634 646 645 +f 646 634 635 +f 635 647 646 +f 635 637 647 +f 640 638 648 +f 648 638 636 +f 649 637 639 +f 637 649 647 +f 648 649 639 +f 648 639 640 +f 636 606 650 +f 636 605 606 +f 636 651 648 +f 651 636 650 +f 652 647 649 +f 647 652 646 +f 648 651 649 +f 651 652 649 +f 652 653 645 +f 652 645 646 +f 644 645 653 +f 653 654 644 +f 654 653 656 +f 654 656 655 +f 653 652 657 +f 657 656 653 +f 657 658 656 +f 652 651 659 +f 659 657 652 +f 660 657 659 +f 657 660 658 +f 658 662 661 +f 660 662 658 +f 658 663 656 +f 663 661 664 +f 661 663 658 +f 661 665 664 +f 665 661 662 +f 666 663 668 +f 666 668 667 +f 664 668 663 +f 668 664 665 +f 663 655 656 +f 655 663 669 +f 663 670 669 +f 670 663 666 +f 669 671 655 +f 654 671 672 +f 671 654 655 +f 642 643 672 +f 643 642 631 +f 643 644 654 +f 654 672 643 +f 641 674 673 +f 674 641 642 +f 642 675 674 +f 675 642 672 +f 673 627 628 +f 627 673 676 +f 673 628 641 +f 641 628 630 +f 650 614 677 +f 614 650 606 +f 678 677 614 +f 678 614 615 +f 679 615 680 +f 615 679 678 +f 626 627 676 +f 676 681 626 +f 674 679 682 +f 679 674 675 +f 674 682 673 +f 682 676 673 +f 683 676 682 +f 676 683 681 +f 625 626 681 +f 681 684 625 +f 680 682 679 +f 682 680 683 +f 683 684 681 +f 684 683 685 +f 624 625 684 +f 624 684 686 +f 684 685 687 +f 687 686 684 +f 623 686 688 +f 686 623 624 +f 622 688 689 +f 688 622 623 +f 689 690 621 +f 689 621 622 +f 690 620 621 +f 620 690 691 +f 688 693 692 +f 693 688 686 +f 687 693 686 +f 693 687 694 +f 689 692 695 +f 692 689 688 +f 690 695 696 +f 695 690 689 +f 691 696 697 +f 696 691 690 +f 698 692 693 +f 698 693 694 +f 699 701 700 +f 701 699 698 +f 695 698 699 +f 698 695 692 +f 696 699 702 +f 699 696 695 +f 697 702 703 +f 702 697 696 +f 705 704 483 +f 705 483 484 +f 486 705 484 +f 705 486 706 +f 706 486 505 +f 505 486 488 +f 505 707 706 +f 707 505 507 +f 708 507 509 +f 507 708 707 +f 709 707 710 +f 707 709 706 +f 706 711 705 +f 711 706 709 +f 702 713 712 +f 713 702 699 +f 703 712 714 +f 712 703 702 +f 714 716 715 +f 716 714 712 +f 716 710 715 +f 710 716 709 +f 710 707 708 +f 708 715 710 +f 717 704 711 +f 711 704 705 +f 482 483 704 +f 704 718 482 +f 711 716 717 +f 716 711 709 +f 712 713 716 +f 713 717 716 +f 700 713 699 +f 713 700 719 +f 720 718 717 +f 717 718 704 +f 482 718 560 +f 718 721 560 +f 720 713 719 +f 713 720 717 +f 607 722 610 +f 722 607 723 +f 619 725 618 +f 618 725 724 +f 725 722 723 +f 725 723 724 +f 724 723 726 +f 726 723 727 +f 611 723 607 +f 723 611 728 +f 617 618 724 +f 724 729 617 +f 604 728 611 +f 728 604 730 +f 731 615 616 +f 615 731 680 +f 617 729 616 +f 729 731 616 +f 605 732 604 +f 732 730 604 +f 732 731 730 +f 731 683 680 +f 683 731 685 +f 729 728 730 +f 729 730 731 +f 732 605 733 +f 733 605 603 +f 731 734 685 +f 685 734 687 +f 601 733 600 +f 600 733 603 +f 601 734 733 +f 731 732 733 +f 731 733 734 +f 601 596 735 +f 596 601 597 +f 734 601 735 +f 735 736 734 +f 734 736 687 +f 736 694 687 +f 694 701 698 +f 701 694 736 +f 596 737 735 +f 737 596 595 +f 736 735 737 +f 736 737 738 +f 701 738 700 +f 738 701 736 +f 595 739 737 +f 739 595 594 +f 737 740 738 +f 740 737 739 +f 738 719 700 +f 719 738 740 +f 594 741 739 +f 741 594 593 +f 739 742 740 +f 742 739 741 +f 720 719 740 +f 740 742 720 +f 720 742 718 +f 742 721 718 +f 560 743 581 +f 743 560 721 +f 744 743 721 +f 593 592 744 +f 593 744 741 +f 741 721 742 +f 721 741 744 +f 583 581 743 +f 743 745 583 +f 592 591 746 +f 592 746 744 +f 589 590 747 +f 590 589 588 +f 528 748 590 +f 748 528 577 +f 577 749 748 +f 749 577 576 +f 576 750 749 +f 750 576 575 +f 575 751 750 +f 751 575 573 +f 573 752 751 +f 752 573 574 +f 752 574 753 +f 753 574 586 +f 583 745 587 +f 745 754 587 +f 587 753 586 +f 753 587 754 +f 753 755 752 +f 755 753 754 +f 757 756 750 +f 757 750 751 +f 751 755 757 +f 755 751 752 +f 591 747 746 +f 747 591 589 +f 756 746 747 +f 744 745 743 +f 745 744 746 +f 754 746 756 +f 745 746 754 +f 756 749 750 +f 749 756 748 +f 747 748 756 +f 748 747 590 +f 755 756 757 +f 754 756 755 +f 546 759 758 +f 759 546 532 +f 544 462 458 +f 462 544 760 +f 546 760 544 +f 760 546 758 +f 760 758 761 +f 761 758 762 +f 760 468 462 +f 468 760 763 +f 763 761 764 +f 761 763 760 +f 763 470 468 +f 470 763 765 +f 765 764 766 +f 764 765 763 +f 472 765 767 +f 765 472 470 +f 767 766 768 +f 766 767 765 +f 474 472 769 +f 769 472 767 +f 769 768 770 +f 768 769 767 +f 762 759 771 +f 759 762 758 +f 480 481 530 +f 772 530 481 +f 475 474 772 +f 772 474 769 +f 772 769 773 +f 773 769 770 +f 475 481 478 +f 481 475 772 +f 532 772 759 +f 772 532 530 +f 759 772 771 +f 772 773 771 +f 723 728 774 +f 723 774 727 +f 778 776 775 +f 776 778 777 +f 779 775 780 +f 780 775 776 +f 727 779 726 +f 779 727 775 +f 777 780 776 +f 780 777 781 +f 726 729 724 +f 729 726 782 +f 728 729 782 +f 728 782 774 +f 774 775 727 +f 775 774 778 +f 774 782 783 +f 774 783 778 +f 783 777 778 +f 777 783 781 +f 779 781 783 +f 781 779 780 +f 782 779 783 +f 779 782 726 +f 662 785 784 +f 785 662 660 +f 668 665 787 +f 787 786 668 +f 665 662 784 +f 784 787 665 +f 789 671 669 +f 671 789 788 +f 675 671 788 +f 671 675 672 +f 675 678 679 +f 678 675 788 +f 659 651 790 +f 650 790 651 +f 785 659 790 +f 659 785 660 +f 792 791 788 +f 792 788 793 +f 792 794 791 +f 791 794 790 +f 678 788 791 +f 791 677 678 +f 790 677 791 +f 677 790 650 +f 785 790 794 +f 785 794 795 +f 784 795 796 +f 795 784 785 +f 787 798 786 +f 798 797 786 +f 667 786 797 +f 786 667 668 +f 667 670 666 +f 670 667 797 +f 670 789 669 +f 789 670 797 +f 799 797 798 +f 789 797 799 +f 787 796 798 +f 796 787 784 +f 789 793 788 +f 793 789 799 +f 801 792 793 +f 792 801 800 +f 802 792 800 +f 792 802 794 +f 795 802 803 +f 802 795 794 +f 796 803 804 +f 803 796 795 +f 799 798 805 +f 798 806 805 +f 798 804 806 +f 804 798 796 +f 805 793 799 +f 793 805 801 +f 800 808 807 +f 808 800 801 +f 800 809 802 +f 809 800 807 +f 803 809 810 +f 809 803 802 +f 804 810 811 +f 810 804 803 +f 805 813 812 +f 813 805 806 +f 813 804 811 +f 806 804 813 +f 808 805 812 +f 801 805 808 +f 815 807 808 +f 807 815 814 +f 816 807 814 +f 807 816 809 +f 810 816 817 +f 816 810 809 +f 811 817 818 +f 817 811 810 +f 819 812 813 +f 813 820 819 +f 813 818 820 +f 818 813 811 +f 819 808 812 +f 808 819 815 +f 818 819 820 +f 819 818 814 +f 814 818 817 +f 814 817 816 +f 814 815 819 +f 822 824 823 +f 824 822 821 +f 825 822 826 +f 826 822 823 +f 827 822 828 +f 822 827 821 +f 829 828 825 +f 825 828 822 +f 830 833 832 +f 830 832 831 +f 835 834 830 +f 830 834 833 +f 830 836 835 +f 836 830 831 +f 834 835 837 +f 835 838 837 +f 835 836 838 +f 836 839 838 +f 838 839 840 +f 839 841 840 +f 841 842 840 +f 842 841 843 +f 838 844 837 +f 844 838 840 +f 842 846 845 +f 846 842 843 +f 842 844 840 +f 844 842 847 +f 842 848 847 +f 848 842 845 +f 850 849 848 +f 848 849 847 +f 851 848 845 +f 848 851 850 +f 845 852 851 +f 852 845 846 +f 853 828 854 +f 828 853 827 +f 855 854 828 +f 855 828 829 +f 856 854 857 +f 854 856 853 +f 859 857 858 +f 857 859 856 +f 860 861 859 +f 860 859 858 +f 862 863 861 +f 862 861 860 +f 864 865 863 +f 864 863 862 +f 865 851 852 +f 851 865 866 +f 866 850 851 +f 850 866 867 +f 867 849 850 +f 849 867 868 +f 857 855 869 +f 855 857 854 +f 858 869 870 +f 869 858 857 +f 860 870 871 +f 870 860 858 +f 862 871 872 +f 871 862 860 +f 864 872 873 +f 872 864 862 +f 865 864 866 +f 864 873 866 +f 866 873 867 +f 873 874 867 +f 874 868 867 +f 868 874 875 +f 855 877 876 +f 877 855 829 +f 869 876 878 +f 876 869 855 +f 870 878 879 +f 878 870 869 +f 871 879 880 +f 879 871 870 +f 881 871 880 +f 871 881 872 +f 882 872 881 +f 872 882 873 +f 883 874 882 +f 882 874 873 +f 883 875 874 +f 875 883 884 +f 882 886 885 +f 886 882 881 +f 881 887 886 +f 887 881 880 +f 880 888 887 +f 888 880 879 +f 879 889 888 +f 889 879 878 +f 890 434 435 +f 434 890 891 +f 888 889 892 +f 889 890 892 +f 439 890 435 +f 890 439 892 +f 887 888 893 +f 893 888 892 +f 893 439 441 +f 439 893 892 +f 894 886 887 +f 894 887 893 +f 894 441 443 +f 441 894 893 +f 885 894 895 +f 894 885 886 +f 896 884 895 +f 884 883 895 +f 895 883 885 +f 885 883 882 +f 446 894 443 +f 894 446 895 +f 447 896 895 +f 447 895 446 +f 876 898 897 +f 898 876 877 +f 891 898 899 +f 898 891 897 +f 878 897 889 +f 897 878 876 +f 897 890 889 +f 890 897 891 +f 891 451 434 +f 451 891 899 +f 451 899 453 +f 899 900 453 +f 899 901 900 +f 901 899 898 +f 898 877 901 +f 877 902 901 +f 903 877 829 +f 877 903 902 +f 903 825 904 +f 825 903 829 +f 905 904 826 +f 826 904 825 +f 906 826 823 +f 826 906 905 +f 823 824 906 +f 824 907 906 +f 906 909 905 +f 909 906 908 +f 907 908 906 +f 908 907 910 +f 912 910 911 +f 910 912 908 +f 913 908 912 +f 908 913 909 +f 914 913 915 +f 913 914 909 +f 916 914 917 +f 917 914 915 +f 916 919 918 +f 917 919 916 +f 920 918 921 +f 921 918 919 +f 923 911 910 +f 911 923 922 +f 924 907 821 +f 821 907 824 +f 910 907 923 +f 907 924 923 +f 923 920 922 +f 922 920 921 +f 927 926 925 +f 927 925 928 +f 926 927 924 +f 923 924 927 +f 932 930 929 +f 930 932 931 +f 934 929 933 +f 929 934 932 +f 934 936 935 +f 936 934 933 +f 938 937 939 +f 939 937 940 +f 940 942 939 +f 942 941 939 +f 942 944 941 +f 944 943 941 +f 944 945 943 +f 945 944 935 +f 941 938 939 +f 938 941 946 +f 937 938 947 +f 938 946 947 +f 943 948 941 +f 941 948 946 +f 943 949 948 +f 949 943 945 +f 950 935 936 +f 935 950 945 +f 950 951 945 +f 945 951 949 +f 936 952 950 +f 952 936 953 +f 955 954 953 +f 952 953 954 +f 955 510 954 +f 510 955 509 +f 951 956 949 +f 956 948 949 +f 952 957 950 +f 950 957 951 +f 510 513 954 +f 954 513 958 +f 954 958 952 +f 952 958 957 +f 946 948 959 +f 948 956 959 +f 957 960 951 +f 951 960 956 +f 513 517 958 +f 517 961 958 +f 958 960 957 +f 960 958 961 +f 962 947 946 +f 946 959 962 +f 963 956 960 +f 959 956 963 +f 964 961 521 +f 517 521 961 +f 961 964 960 +f 960 964 963 +f 965 964 523 +f 521 523 964 +f 966 963 965 +f 964 965 963 +f 962 959 966 +f 959 963 966 +f 968 966 967 +f 966 968 962 +f 969 971 970 +f 925 971 969 +f 969 973 972 +f 973 969 970 +f 970 974 973 +f 974 970 975 +f 975 977 974 +f 977 976 974 +f 977 978 976 +f 978 977 979 +f 979 980 978 +f 980 979 981 +f 981 967 980 +f 967 981 968 +f 982 967 965 +f 965 967 966 +f 980 982 983 +f 982 980 967 +f 523 543 982 +f 523 982 965 +f 984 904 905 +f 984 905 985 +f 985 986 984 +f 986 985 987 +f 987 973 986 +f 973 987 972 +f 988 903 904 +f 904 984 988 +f 984 989 988 +f 989 984 986 +f 986 974 989 +f 974 986 973 +f 990 902 903 +f 990 903 988 +f 988 991 990 +f 991 988 989 +f 989 976 991 +f 976 989 974 +f 902 992 901 +f 992 902 990 +f 990 993 992 +f 993 990 991 +f 991 978 993 +f 978 991 976 +f 978 983 993 +f 983 978 980 +f 994 901 992 +f 901 994 900 +f 995 992 993 +f 992 995 994 +f 994 453 900 +f 453 994 556 +f 557 994 995 +f 994 557 556 +f 557 995 983 +f 983 995 993 +f 543 557 982 +f 982 557 983 +f 996 934 944 +f 935 944 934 +f 996 932 934 +f 932 996 997 +f 998 931 997 +f 932 997 931 +f 944 942 996 +f 942 999 996 +f 942 940 999 +f 940 1000 999 +f 1000 937 1001 +f 937 1000 940 +f 937 947 1001 +f 1001 947 1002 +f 1002 1003 1001 +f 1001 1003 1000 +f 1003 1004 1000 +f 999 1000 1004 +f 1004 1005 999 +f 996 999 1005 +f 947 1006 1002 +f 1006 947 962 +f 1003 1007 1004 +f 1007 1003 1002 +f 1006 1007 1002 +f 1007 1006 1008 +f 1009 962 968 +f 962 1009 1006 +f 1008 1006 1010 +f 1006 1009 1010 +f 1011 1010 1009 +f 1009 1012 1011 +f 968 981 1009 +f 981 1012 1009 +f 1012 981 979 +f 1012 979 1013 +f 979 977 1013 +f 977 1014 1013 +f 977 975 1014 +f 975 1015 1014 +f 970 1015 975 +f 1015 970 971 +f 1005 997 996 +f 997 1005 1016 +f 1017 1004 1007 +f 1004 1017 1005 +f 1007 1018 1017 +f 1018 1007 1008 +f 998 997 1016 +f 998 1016 1019 +f 1016 1005 1017 +f 1017 1020 1016 +f 1016 1020 1019 +f 1019 1020 1021 +f 1018 1010 1022 +f 1010 1018 1008 +f 1018 1022 1023 +f 1020 1018 1023 +f 1018 1020 1017 +f 1022 1011 1024 +f 1011 1022 1010 +f 1024 1023 1022 +f 1023 1024 1025 +f 1023 1025 1020 +f 1021 1020 1025 +f 1026 821 827 +f 821 1026 924 +f 1027 827 853 +f 827 1027 1026 +f 1026 926 924 +f 926 1026 1028 +f 1028 971 926 +f 971 925 926 +f 1029 853 856 +f 853 1029 1027 +f 1030 856 859 +f 856 1030 1029 +f 1031 859 861 +f 859 1031 1030 +f 1032 861 863 +f 861 1032 1031 +f 1033 863 865 +f 863 1033 1032 +f 1033 852 1034 +f 852 1033 865 +f 1035 852 846 +f 852 1035 1034 +f 843 1035 846 +f 1035 843 1036 +f 1038 1035 1039 +f 1035 1038 1037 +f 1039 1036 1040 +f 1035 1036 1039 +f 1041 1038 1039 +f 1041 1039 1040 +f 1042 1044 1043 +f 609 610 1046 +f 609 1046 1045 +f 1045 1046 1048 +f 1045 1048 1047 +f 1047 1048 1043 +f 1047 1043 1049 +f 1049 1043 1044 +f 1044 1050 1049 +f 1051 1049 1050 +f 1051 1050 1052 +f 1047 1051 1053 +f 1051 1047 1049 +f 1045 1053 1054 +f 1053 1045 1047 +f 619 609 1045 +f 619 1045 1054 +f 620 896 447 +f 896 620 1055 +f 1056 884 1055 +f 1055 884 896 +f 1057 875 1056 +f 884 1056 875 +f 1058 868 1057 +f 875 1057 868 +f 868 1058 849 +f 1058 1059 849 +f 847 849 1059 +f 847 1059 1060 +f 844 847 1060 +f 844 1060 1061 +f 1061 837 844 +f 837 1061 1062 +f 1062 834 837 +f 834 1062 1063 +f 1063 1065 1064 +f 1065 1063 1062 +f 833 834 1063 +f 1063 1066 833 +f 1067 833 1066 +f 833 1067 832 +f 1068 832 1067 +f 832 1068 831 +f 831 1069 836 +f 1069 831 1068 +f 1042 1041 1040 +f 1040 1070 1042 +f 836 1071 839 +f 1071 836 1069 +f 839 1072 841 +f 1072 839 1071 +f 1071 1074 1073 +f 1072 1071 1073 +f 1072 1036 841 +f 841 1036 843 +f 1070 1036 1072 +f 1070 1040 1036 +f 1075 1065 1076 +f 1065 1075 1064 +f 1077 1063 1064 +f 1063 1077 1066 +f 1078 1066 1077 +f 1066 1078 1067 +f 1079 1067 1078 +f 1067 1079 1068 +f 1068 1080 1069 +f 1080 1068 1079 +f 1071 1069 1081 +f 1069 1080 1081 +f 1072 1082 1070 +f 1082 1072 1073 +f 1071 1083 1074 +f 1083 1071 1081 +f 1083 1082 1074 +f 1074 1082 1073 +f 1042 1070 1044 +f 1070 1084 1044 +f 1085 1070 1082 +f 1070 1085 1084 +f 1086 1081 1080 +f 1081 1086 1083 +f 1085 1082 1083 +f 1083 1086 1085 +f 1086 1079 1087 +f 1079 1086 1080 +f 1088 1087 1078 +f 1078 1087 1079 +f 1089 1088 1090 +f 1088 1089 1087 +f 1089 1091 1087 +f 1087 1091 1086 +f 1089 1092 1091 +f 1085 1086 1093 +f 1086 1091 1093 +f 1094 1091 1092 +f 1091 1094 1093 +f 1095 1092 1096 +f 1095 1094 1092 +f 1089 1097 1092 +f 1097 1096 1092 +f 1096 1097 1098 +f 1099 1095 1096 +f 1099 1096 1098 +f 1100 1102 1101 +f 1102 1100 1097 +f 1100 1098 1097 +f 1098 1100 1099 +f 1103 1097 1090 +f 1090 1097 1089 +f 1104 1097 1103 +f 1097 1104 1102 +f 1090 1105 1103 +f 1105 1090 1088 +f 1105 1088 1106 +f 1106 1077 1075 +f 1075 1077 1064 +f 1106 1088 1077 +f 1077 1088 1078 +f 1107 1076 1108 +f 1076 1107 1075 +f 1109 1075 1107 +f 1075 1109 1106 +f 1108 1061 1110 +f 1061 1108 1062 +f 1062 1108 1076 +f 1062 1076 1065 +f 1050 1084 1111 +f 1084 1050 1044 +f 1112 1050 1111 +f 1050 1112 1052 +f 1114 1052 1112 +f 1052 1114 1113 +f 1061 1060 1110 +f 1110 1060 1115 +f 1114 1107 1116 +f 1107 1114 1109 +f 1116 1107 1108 +f 1108 1110 1116 +f 1110 1117 1116 +f 1117 1110 1115 +f 1060 1059 1115 +f 1059 1118 1115 +f 1116 1113 1114 +f 1113 1116 1117 +f 1117 1118 1119 +f 1118 1117 1115 +f 1059 1058 1118 +f 1058 1120 1118 +f 1119 1118 1121 +f 1121 1118 1120 +f 1058 1057 1120 +f 1057 1122 1120 +f 1123 1122 1056 +f 1057 1056 1122 +f 1124 1123 1055 +f 1056 1055 1123 +f 620 1124 1055 +f 1124 620 691 +f 1122 1126 1120 +f 1126 1122 1125 +f 1121 1126 1127 +f 1126 1121 1120 +f 1123 1125 1122 +f 1125 1123 1128 +f 1124 1128 1123 +f 1128 1124 1129 +f 691 1129 1124 +f 1129 691 697 +f 1130 1126 1125 +f 1126 1130 1127 +f 1132 1133 1130 +f 1133 1132 1131 +f 1128 1130 1125 +f 1130 1128 1132 +f 1129 1132 1128 +f 1132 1129 1134 +f 697 1134 1129 +f 1134 697 703 +f 1135 930 1136 +f 930 1135 929 +f 933 1135 1137 +f 1135 933 929 +f 936 933 953 +f 933 1137 953 +f 953 1138 955 +f 1138 953 1137 +f 708 955 1138 +f 955 708 509 +f 1140 1138 1137 +f 1138 1140 1139 +f 1141 1140 1137 +f 1141 1137 1135 +f 1134 1143 1132 +f 1143 1134 1142 +f 703 1142 1134 +f 1142 703 714 +f 714 1144 1142 +f 1144 714 715 +f 1144 1139 1140 +f 1139 1144 715 +f 1138 1139 708 +f 1139 715 708 +f 1141 1136 1145 +f 1136 1141 1135 +f 1146 1136 931 +f 931 1136 930 +f 1145 1144 1141 +f 1141 1144 1140 +f 1143 1144 1145 +f 1143 1142 1144 +f 1131 1143 1147 +f 1143 1131 1132 +f 1145 1146 1148 +f 1146 1145 1136 +f 1149 1146 998 +f 931 998 1146 +f 1143 1148 1147 +f 1148 1143 1145 +f 1046 722 1150 +f 722 1046 610 +f 725 619 1054 +f 1054 1151 725 +f 1150 725 1151 +f 725 1150 722 +f 1150 1151 1152 +f 1150 1152 1153 +f 1150 1048 1046 +f 1048 1150 1154 +f 1054 1053 1151 +f 1053 1155 1151 +f 1043 1154 1156 +f 1154 1043 1048 +f 1157 1052 1113 +f 1052 1157 1051 +f 1155 1053 1051 +f 1051 1157 1155 +f 1158 1042 1043 +f 1158 1043 1156 +f 1156 1157 1158 +f 1119 1157 1117 +f 1117 1157 1113 +f 1156 1155 1157 +f 1155 1156 1154 +f 1042 1159 1041 +f 1159 1042 1158 +f 1160 1157 1119 +f 1160 1119 1121 +f 1038 1159 1037 +f 1159 1038 1041 +f 1159 1160 1037 +f 1160 1159 1157 +f 1158 1157 1159 +f 1037 1034 1035 +f 1034 1037 1161 +f 1162 1161 1160 +f 1037 1160 1161 +f 1162 1160 1121 +f 1162 1121 1127 +f 1133 1127 1130 +f 1127 1133 1162 +f 1163 1034 1161 +f 1034 1163 1033 +f 1164 1163 1162 +f 1161 1162 1163 +f 1133 1164 1162 +f 1164 1133 1131 +f 1163 1165 1033 +f 1033 1165 1032 +f 1163 1166 1165 +f 1166 1163 1164 +f 1164 1147 1166 +f 1147 1164 1131 +f 1165 1167 1032 +f 1032 1167 1031 +f 1165 1168 1167 +f 1168 1165 1166 +f 1147 1148 1166 +f 1166 1148 1168 +f 1168 1148 1146 +f 1168 1146 1149 +f 998 1169 1149 +f 1169 998 1019 +f 1149 1169 1170 +f 1167 1170 1031 +f 1030 1031 1170 +f 1167 1149 1170 +f 1149 1167 1168 +f 1019 1021 1169 +f 1169 1021 1171 +f 1170 1172 1030 +f 1029 1030 1172 +f 1027 1028 1026 +f 1028 1027 1173 +f 1015 971 1174 +f 971 1028 1174 +f 1015 1175 1014 +f 1175 1015 1174 +f 1176 1013 1014 +f 1014 1175 1176 +f 1177 1012 1013 +f 1013 1176 1177 +f 1178 1011 1012 +f 1012 1177 1178 +f 1179 1024 1011 +f 1011 1178 1179 +f 1171 1021 1025 +f 1171 1025 1180 +f 1025 1179 1180 +f 1179 1025 1024 +f 1181 1179 1178 +f 1179 1181 1180 +f 1183 1182 1176 +f 1176 1182 1177 +f 1182 1181 1177 +f 1177 1181 1178 +f 1029 1173 1027 +f 1173 1029 1172 +f 1173 1172 1183 +f 1171 1170 1169 +f 1170 1171 1172 +f 1172 1171 1180 +f 1172 1180 1183 +f 1175 1183 1176 +f 1183 1175 1174 +f 1173 1174 1028 +f 1174 1173 1183 +f 1183 1181 1182 +f 1183 1180 1181 +f 987 1185 972 +f 1185 987 1184 +f 985 909 1186 +f 909 985 905 +f 1186 987 985 +f 987 1186 1184 +f 1187 1184 1186 +f 1184 1187 1188 +f 1186 914 1189 +f 914 1186 909 +f 1189 1187 1186 +f 1187 1189 1190 +f 916 1189 914 +f 1189 916 1191 +f 1191 1190 1189 +f 1190 1191 1192 +f 918 1191 916 +f 1191 918 1193 +f 1193 1192 1191 +f 1192 1193 1194 +f 1195 918 920 +f 918 1195 1193 +f 1195 1194 1193 +f 1194 1195 1196 +f 1188 1185 1184 +f 1185 1188 1197 +f 928 925 969 +f 969 1198 928 +f 1198 920 923 +f 920 1198 1195 +f 1195 1198 1199 +f 1195 1199 1196 +f 928 923 927 +f 923 928 1198 +f 972 1185 1198 +f 972 1198 969 +f 1198 1185 1197 +f 1198 1197 1199 +f 1154 1150 1200 +f 1150 1153 1200 +f 1204 1202 1201 +f 1202 1204 1203 +f 1205 1203 1206 +f 1203 1205 1202 +f 1206 1153 1152 +f 1153 1206 1203 +f 1201 1205 1207 +f 1205 1201 1202 +f 1155 1152 1151 +f 1152 1155 1208 +f 1200 1208 1154 +f 1155 1154 1208 +f 1200 1203 1204 +f 1203 1200 1153 +f 1208 1200 1209 +f 1200 1204 1209 +f 1209 1201 1207 +f 1201 1209 1204 +f 1207 1206 1209 +f 1206 1207 1205 +f 1208 1206 1152 +f 1206 1208 1209 +f 1095 1211 1094 +f 1211 1095 1210 +f 1212 1100 1213 +f 1100 1212 1099 +f 1210 1099 1212 +f 1099 1210 1095 +f 1215 1105 1214 +f 1105 1215 1103 +f 1109 1105 1106 +f 1105 1109 1214 +f 1112 1109 1114 +f 1109 1112 1214 +f 1216 1084 1085 +f 1216 1085 1093 +f 1211 1093 1094 +f 1093 1211 1216 +f 1214 1218 1217 +f 1214 1217 1219 +f 1218 1220 1217 +f 1220 1218 1216 +f 1214 1112 1218 +f 1112 1111 1218 +f 1111 1216 1218 +f 1216 1111 1084 +f 1216 1211 1220 +f 1211 1221 1220 +f 1221 1210 1222 +f 1210 1221 1211 +f 1223 1212 1213 +f 1213 1224 1223 +f 1213 1101 1224 +f 1101 1213 1100 +f 1104 1101 1102 +f 1101 1104 1224 +f 1104 1215 1224 +f 1215 1104 1103 +f 1223 1224 1225 +f 1224 1215 1225 +f 1212 1222 1210 +f 1222 1212 1223 +f 1215 1219 1225 +f 1219 1215 1214 +f 1217 1226 1219 +f 1226 1217 1227 +f 1217 1220 1228 +f 1217 1228 1227 +f 1221 1228 1220 +f 1228 1221 1229 +f 1222 1229 1221 +f 1229 1222 1230 +f 1231 1223 1232 +f 1232 1223 1225 +f 1230 1223 1231 +f 1223 1230 1222 +f 1232 1219 1226 +f 1219 1232 1225 +f 1227 1233 1226 +f 1233 1227 1234 +f 1227 1235 1234 +f 1235 1227 1228 +f 1229 1235 1228 +f 1235 1229 1236 +f 1236 1230 1237 +f 1230 1236 1229 +f 1238 1232 1239 +f 1232 1238 1231 +f 1230 1231 1238 +f 1230 1238 1237 +f 1232 1233 1239 +f 1232 1226 1233 +f 1234 1240 1233 +f 1240 1234 1241 +f 1235 1242 1234 +f 1234 1242 1241 +f 1242 1236 1243 +f 1236 1242 1235 +f 1243 1237 1244 +f 1237 1243 1236 +f 1245 1238 1246 +f 1246 1238 1239 +f 1244 1238 1245 +f 1238 1244 1237 +f 1246 1233 1240 +f 1233 1246 1239 +f 1244 1241 1243 +f 1243 1241 1242 +f 1244 1246 1241 +f 1246 1244 1245 +f 1246 1240 1241 +# 2464 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/r_uleg_chull.obj b/examples/Atlas/urdf/mesh/r_uleg_chull.obj new file mode 100644 index 0000000..33f2b84 --- /dev/null +++ b/examples/Atlas/urdf/mesh/r_uleg_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object r_uleg_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v -0.128024 0.013473 -0.196928 +v -0.066338 0.040351 -0.386306 +v -0.100668 0.058048 -0.221429 +v -0.033850 0.042532 -0.387191 +v 0.014000 0.050346 0.013891 +v -0.064298 0.072732 -0.238607 +v -0.121670 -0.019266 -0.106035 +v -0.107679 0.047446 -0.102959 +v 0.010297 0.070432 -0.257128 +v -0.066886 -0.041337 -0.383422 +v 0.057502 0.028211 -0.245659 +v 0.012880 -0.051141 0.016002 +v -0.027756 0.077954 -0.040144 +v 0.031240 0.073621 -0.075705 +v -0.063133 -0.074138 -0.236752 +v -0.110790 -0.046504 -0.219980 +v -0.091498 -0.061663 -0.101093 +v 0.038708 -0.006205 -0.329533 +v 0.078030 -0.028717 -0.117900 +v 0.082925 0.017804 -0.117727 +v 0.051005 -0.036670 -0.248941 +v 0.000424 -0.074580 -0.001100 +v 0.011051 -0.068951 -0.267147 +v 0.041881 -0.068481 -0.094516 +v -0.040340 -0.041827 -0.391602 +v -0.011042 -0.049436 0.016944 +v -0.009904 0.049233 0.018210 +# 27 vertices, 0 vertices normals + +f 6 2 4 +f 12 22 26 +f 6 3 2 +f 8 7 1 +f 3 8 1 +f 3 1 2 +f 19 24 12 +f 10 15 25 +f 25 2 10 +f 10 1 16 +f 10 2 1 +f 9 4 11 +f 6 4 9 +f 8 3 13 +f 3 6 13 +f 7 16 1 +f 26 17 7 +f 17 26 22 +f 19 12 20 +f 9 14 6 +f 11 14 9 +f 18 4 25 +f 18 11 4 +f 20 14 11 +f 14 20 5 +f 6 14 13 +f 8 27 7 +f 26 7 27 +f 8 13 27 +f 21 24 19 +f 27 14 5 +f 27 13 14 +f 10 16 15 +f 15 23 25 +f 15 16 17 +f 20 12 5 +f 22 12 24 +f 23 15 22 +f 21 23 24 +f 5 12 27 +f 7 17 16 +f 22 15 17 +f 25 23 18 +f 19 20 11 +f 21 19 11 +f 24 23 22 +f 11 18 21 +f 21 18 23 +f 2 25 4 +f 12 26 27 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/utorso.obj b/examples/Atlas/urdf/mesh/utorso.obj new file mode 100644 index 0000000..6acd1df --- /dev/null +++ b/examples/Atlas/urdf/mesh/utorso.obj @@ -0,0 +1,10874 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object utorso.obj +# +# Vertices: 3894 +# Faces: 6964 +# +#### +v -0.024319 0.111745 0.032934 +v -0.024320 0.170897 0.032934 +v -0.014050 0.170897 0.037979 +v -0.014049 0.111745 0.037980 +v -0.026855 0.111745 0.021596 +v -0.026856 0.170897 0.021596 +v -0.019748 0.111745 0.012503 +v -0.020281 0.170897 0.002040 +v -0.008350 0.111745 0.012503 +v -0.008351 0.170897 0.012503 +v -0.001242 0.111745 0.021596 +v -0.001244 0.170897 0.021596 +v -0.003779 0.111745 0.032933 +v -0.003780 0.170897 0.032933 +v -0.014049 0.111745 0.035061 +v -0.022083 0.111745 0.031114 +v -0.024067 0.111745 0.022245 +v -0.018507 0.111745 0.015133 +v -0.009591 0.111745 0.015133 +v -0.004031 0.111745 0.022245 +v -0.006015 0.111745 0.031114 +v -0.079149 0.164425 0.033059 +v 0.003047 0.164425 0.033059 +v 0.003047 0.154154 0.038105 +v -0.079149 0.154154 0.038105 +v -0.079149 0.166960 0.021721 +v 0.003047 0.166960 0.021721 +v -0.079149 0.159852 0.012629 +v 0.003047 0.159855 0.012629 +v -0.079149 0.148454 0.012629 +v 0.003047 0.148455 0.012629 +v -0.079149 0.141347 0.021721 +v 0.003047 0.141349 0.021721 +v -0.079149 0.143884 0.033059 +v 0.003047 0.143885 0.033058 +v -0.081283 -0.157481 0.669171 +v 0.068095 -0.110507 0.787600 +v 0.067759 -0.104954 0.785545 +v -0.083835 -0.152298 0.667036 +v -0.083103 -0.161055 0.673969 +v 0.065148 -0.113001 0.792219 +v -0.087926 -0.160329 0.677817 +v 0.061137 -0.110561 0.795923 +v -0.092119 -0.155850 0.677817 +v 0.059082 -0.105023 0.795923 +v -0.092525 -0.150990 0.673969 +v 0.060532 -0.100557 0.792219 +v -0.088838 -0.149410 0.669171 +v 0.064393 -0.100527 0.787600 +v -0.019552 0.148023 0.533327 +v -0.015454 0.148023 0.553598 +v -0.012065 0.154920 0.553598 +v -0.016428 0.154920 0.532019 +v -0.026573 0.146319 0.536266 +v -0.023069 0.146319 0.553598 +v -0.032203 0.151092 0.538623 +v -0.029176 0.151092 0.553598 +v -0.032203 0.158748 0.538623 +v -0.029176 0.158748 0.553598 +v -0.026573 0.163522 0.536266 +v -0.023069 0.163522 0.553598 +v -0.019552 0.161818 0.533327 +v -0.015454 0.161818 0.553598 +v -0.030743 0.148023 0.516738 +v -0.028350 0.154920 0.514345 +v -0.036119 0.146319 0.522114 +v -0.040431 0.151092 0.526426 +v -0.040431 0.158748 0.526426 +v -0.036119 0.163522 0.522114 +v -0.030743 0.161818 0.516738 +v -0.047332 0.148023 0.505547 +v -0.046024 0.154920 0.502423 +v -0.050271 0.146319 0.512568 +v -0.052628 0.151092 0.518198 +v -0.052628 0.158748 0.518198 +v -0.050271 0.163522 0.512568 +v -0.047332 0.161818 0.505547 +v -0.067602 0.148023 0.501449 +v -0.067602 0.154920 0.498060 +v -0.067602 0.146319 0.509064 +v -0.067602 0.151092 0.515171 +v -0.067602 0.158748 0.515171 +v -0.067602 0.163522 0.509064 +v -0.067602 0.161818 0.501449 +v -0.015454 0.148023 0.571451 +v -0.012065 0.154920 0.571451 +v -0.023069 0.146319 0.571451 +v -0.029176 0.151092 0.571451 +v -0.029176 0.158748 0.571451 +v -0.023069 0.163522 0.571451 +v -0.015454 0.161818 0.571451 +v -0.086573 0.154920 0.498060 +v -0.086573 0.148023 0.501449 +v -0.086573 0.146319 0.509064 +v -0.086573 0.151092 0.515171 +v -0.086573 0.158748 0.515171 +v -0.086573 0.163522 0.509064 +v -0.086573 0.161818 0.501449 +v -0.153594 0.161818 0.533327 +v -0.157692 0.161818 0.553598 +v -0.161081 0.154920 0.553598 +v -0.156719 0.154920 0.532019 +v -0.146573 0.163522 0.536266 +v -0.150077 0.163522 0.553598 +v -0.140943 0.158748 0.538623 +v -0.143970 0.158748 0.553598 +v -0.140943 0.151092 0.538623 +v -0.143970 0.151092 0.553598 +v -0.146573 0.146319 0.536266 +v -0.150077 0.146319 0.553598 +v -0.153594 0.148023 0.533327 +v -0.157692 0.148023 0.553598 +v -0.142404 0.161818 0.516738 +v -0.144797 0.154920 0.514345 +v -0.137027 0.163522 0.522114 +v -0.132715 0.158748 0.526426 +v -0.132715 0.151092 0.526426 +v -0.137027 0.146319 0.522114 +v -0.142404 0.148023 0.516738 +v -0.125814 0.161818 0.505547 +v -0.127122 0.154920 0.502423 +v -0.122875 0.163522 0.512568 +v -0.120518 0.158748 0.518198 +v -0.120518 0.151092 0.518198 +v -0.122875 0.146319 0.512568 +v -0.125814 0.148023 0.505547 +v -0.105544 0.161818 0.501449 +v -0.105544 0.154920 0.498060 +v -0.105544 0.163522 0.509064 +v -0.105544 0.158748 0.515171 +v -0.105544 0.151092 0.515171 +v -0.105544 0.146319 0.509064 +v -0.105544 0.148023 0.501449 +v -0.157692 0.161818 0.571451 +v -0.161081 0.154920 0.571451 +v -0.150077 0.163522 0.571451 +v -0.143970 0.158748 0.571451 +v -0.143970 0.151092 0.571451 +v -0.150077 0.146319 0.571451 +v -0.157692 0.148023 0.571451 +v 0.059184 0.110695 0.674739 +v 0.059184 0.126265 0.677887 +v 0.064442 0.126265 0.680471 +v 0.064442 0.109698 0.677121 +v 0.057885 0.112935 0.669387 +v 0.057885 0.126265 0.672083 +v 0.061524 0.114732 0.665096 +v 0.061524 0.126265 0.667428 +v 0.067360 0.114732 0.665096 +v 0.067360 0.126265 0.667428 +v 0.070999 0.112935 0.669387 +v 0.070999 0.126265 0.672083 +v 0.069700 0.110695 0.674739 +v 0.069700 0.126265 0.677887 +v 0.059184 0.097952 0.666144 +v 0.064442 0.096128 0.667968 +v 0.057885 0.102051 0.662045 +v 0.061524 0.105337 0.658759 +v 0.067360 0.105337 0.658759 +v 0.070999 0.102051 0.662045 +v 0.069700 0.097952 0.666144 +v 0.059184 0.089357 0.653401 +v 0.064442 0.086975 0.654398 +v 0.057885 0.094709 0.651161 +v 0.061524 0.099000 0.649364 +v 0.067360 0.099000 0.649364 +v 0.070999 0.094709 0.651161 +v 0.069700 0.089357 0.653401 +v 0.059184 0.086209 0.637830 +v 0.064442 0.083626 0.637830 +v 0.057885 0.092013 0.637830 +v 0.061524 0.096668 0.637830 +v 0.067360 0.096668 0.637830 +v 0.070999 0.092013 0.637830 +v 0.069700 0.086209 0.637830 +v 0.059184 0.154186 0.677887 +v 0.064442 0.154186 0.680471 +v 0.057885 0.154186 0.672083 +v 0.061524 0.154186 0.667428 +v 0.067360 0.154186 0.667428 +v 0.070999 0.154186 0.672083 +v 0.069700 0.154186 0.677887 +v 0.069700 0.110695 0.570687 +v 0.069700 0.126265 0.567539 +v 0.064442 0.126265 0.564956 +v 0.064442 0.109698 0.568306 +v 0.070999 0.112936 0.576039 +v 0.070999 0.126265 0.573344 +v 0.067360 0.114732 0.580331 +v 0.067360 0.126265 0.577999 +v 0.061524 0.114732 0.580331 +v 0.061524 0.126265 0.577999 +v 0.057885 0.112936 0.576039 +v 0.057885 0.126265 0.573344 +v 0.059184 0.110695 0.570687 +v 0.059184 0.126265 0.567539 +v 0.069700 0.097952 0.579283 +v 0.064442 0.096128 0.577459 +v 0.070999 0.102051 0.583381 +v 0.067360 0.105337 0.586668 +v 0.061524 0.105337 0.586668 +v 0.057885 0.102051 0.583381 +v 0.059184 0.097952 0.579283 +v 0.069700 0.089357 0.592026 +v 0.064442 0.086975 0.591029 +v 0.070999 0.094709 0.594266 +v 0.067360 0.099000 0.596063 +v 0.061524 0.099000 0.596063 +v 0.057885 0.094709 0.594266 +v 0.059184 0.089357 0.592026 +v 0.069700 0.086209 0.607596 +v 0.064442 0.083626 0.607596 +v 0.070999 0.092013 0.607596 +v 0.067360 0.096668 0.607596 +v 0.061524 0.096668 0.607596 +v 0.057885 0.092013 0.607596 +v 0.059184 0.086209 0.607596 +v 0.069700 0.154186 0.567539 +v 0.064442 0.154186 0.564956 +v 0.070999 0.154186 0.573344 +v 0.067360 0.154186 0.577999 +v 0.061524 0.154186 0.577999 +v 0.057885 0.154186 0.573344 +v 0.059184 0.154186 0.567539 +v -0.019552 -0.147942 0.533327 +v -0.016428 -0.154840 0.532019 +v -0.012065 -0.154840 0.553597 +v -0.015454 -0.147942 0.553597 +v -0.026573 -0.146238 0.536266 +v -0.023069 -0.146238 0.553597 +v -0.032203 -0.151012 0.538623 +v -0.029176 -0.151012 0.553597 +v -0.032203 -0.158668 0.538623 +v -0.029176 -0.158668 0.553597 +v -0.026573 -0.163441 0.536266 +v -0.023069 -0.163441 0.553597 +v -0.019552 -0.161738 0.533327 +v -0.015454 -0.161738 0.553597 +v -0.030743 -0.147942 0.516737 +v -0.028350 -0.154840 0.514344 +v -0.036119 -0.146238 0.522114 +v -0.040431 -0.151012 0.526426 +v -0.040431 -0.158668 0.526426 +v -0.036119 -0.163441 0.522114 +v -0.030743 -0.161738 0.516737 +v -0.047332 -0.147942 0.505547 +v -0.046024 -0.154840 0.502422 +v -0.050271 -0.146238 0.512568 +v -0.052628 -0.151012 0.518198 +v -0.052628 -0.158668 0.518198 +v -0.050271 -0.163441 0.512568 +v -0.047332 -0.161738 0.505547 +v -0.067602 -0.147942 0.501449 +v -0.067602 -0.154840 0.498060 +v -0.067602 -0.146238 0.509064 +v -0.067602 -0.151012 0.515171 +v -0.067602 -0.158668 0.515171 +v -0.067602 -0.163441 0.509064 +v -0.067602 -0.161738 0.501449 +v -0.012065 -0.154840 0.571451 +v -0.015454 -0.147942 0.571451 +v -0.023069 -0.146238 0.571451 +v -0.029176 -0.151012 0.571451 +v -0.029176 -0.158668 0.571451 +v -0.023069 -0.163441 0.571451 +v -0.015454 -0.161738 0.571451 +v -0.086573 -0.147942 0.501449 +v -0.086573 -0.154840 0.498060 +v -0.086573 -0.146238 0.509064 +v -0.086573 -0.151012 0.515171 +v -0.086573 -0.158668 0.515171 +v -0.086573 -0.163441 0.509064 +v -0.086573 -0.161738 0.501449 +v -0.153594 -0.161738 0.533327 +v -0.156719 -0.154840 0.532019 +v -0.161081 -0.154840 0.553597 +v -0.157692 -0.161738 0.553597 +v -0.146573 -0.163441 0.536266 +v -0.150077 -0.163441 0.553597 +v -0.140943 -0.158668 0.538623 +v -0.143970 -0.158668 0.553597 +v -0.140943 -0.151012 0.538623 +v -0.143970 -0.151012 0.553597 +v -0.146573 -0.146238 0.536266 +v -0.150077 -0.146238 0.553597 +v -0.153594 -0.147942 0.533327 +v -0.157692 -0.147942 0.553597 +v -0.142404 -0.161738 0.516737 +v -0.144797 -0.154840 0.514344 +v -0.137027 -0.163441 0.522114 +v -0.132715 -0.158668 0.526426 +v -0.132715 -0.151012 0.526426 +v -0.137027 -0.146238 0.522114 +v -0.142404 -0.147942 0.516737 +v -0.125814 -0.161738 0.505547 +v -0.127122 -0.154840 0.502422 +v -0.122875 -0.163441 0.512568 +v -0.120518 -0.158668 0.518198 +v -0.120518 -0.151012 0.518198 +v -0.122875 -0.146238 0.512568 +v -0.125814 -0.147942 0.505547 +v -0.105544 -0.161738 0.501449 +v -0.105544 -0.154840 0.498060 +v -0.105544 -0.163441 0.509064 +v -0.105544 -0.158668 0.515171 +v -0.105544 -0.151012 0.515171 +v -0.105544 -0.146238 0.509064 +v -0.105544 -0.147942 0.501449 +v -0.161081 -0.154840 0.571451 +v -0.157692 -0.161738 0.571451 +v -0.150077 -0.163441 0.571451 +v -0.143970 -0.158668 0.571451 +v -0.143970 -0.151012 0.571451 +v -0.150077 -0.146238 0.571451 +v -0.157692 -0.147942 0.571451 +v 0.198952 -0.091985 0.518739 +v 0.198952 -0.091985 0.536918 +v 0.198952 -0.133388 0.536919 +v 0.198952 -0.133388 0.518739 +v 0.208372 -0.138826 0.536918 +v 0.208372 -0.138827 0.524733 +v 0.217791 -0.133388 0.536919 +v 0.217791 -0.133388 0.518739 +v 0.217791 -0.091985 0.536918 +v 0.217791 -0.091985 0.518739 +v 0.208372 -0.086546 0.536918 +v 0.208372 -0.086546 0.518739 +v 0.064024 -0.091984 0.518739 +v 0.064024 -0.091984 0.536918 +v 0.064024 -0.133388 0.536918 +v 0.064024 -0.133388 0.518739 +v 0.073443 -0.138826 0.536918 +v 0.073443 -0.138826 0.518739 +v 0.082862 -0.133388 0.536918 +v 0.082862 -0.133388 0.518739 +v 0.082862 -0.091984 0.536918 +v 0.082862 -0.091984 0.518739 +v 0.073443 -0.086546 0.536918 +v 0.073443 -0.086546 0.518739 +v -0.290557 0.036265 0.525390 +v -0.286722 0.038002 0.524663 +v -0.286722 0.041228 0.540621 +v -0.290557 0.039344 0.540621 +v -0.291504 0.032362 0.527024 +v -0.291504 0.035111 0.540621 +v -0.288850 0.029232 0.528335 +v -0.288850 0.031716 0.540621 +v -0.284594 0.029232 0.528335 +v -0.284594 0.031716 0.540621 +v -0.281940 0.032362 0.527024 +v -0.281940 0.035111 0.540621 +v -0.282887 0.036265 0.525390 +v -0.282887 0.039344 0.540621 +v -0.290557 0.027860 0.512931 +v -0.286722 0.029190 0.511601 +v -0.291504 0.024871 0.515920 +v -0.288850 0.022474 0.518317 +v -0.284594 0.022474 0.518317 +v -0.281940 0.024871 0.515920 +v -0.282888 0.027860 0.512931 +v -0.290557 0.015400 0.504526 +v -0.286722 0.016127 0.502789 +v -0.291504 0.013766 0.508429 +v -0.288850 0.012456 0.511559 +v -0.284594 0.012456 0.511559 +v -0.281940 0.013766 0.508429 +v -0.282888 0.015400 0.504526 +v -0.290557 0.000170 0.501447 +v -0.286722 0.000170 0.499563 +v -0.291504 0.000170 0.505680 +v -0.288850 0.000170 0.509075 +v -0.284594 0.000170 0.509075 +v -0.281940 0.000170 0.505680 +v -0.282888 0.000170 0.501447 +v -0.290557 -0.015060 0.504526 +v -0.286722 -0.015787 0.502789 +v -0.291504 -0.013426 0.508429 +v -0.288850 -0.012116 0.511559 +v -0.284594 -0.012116 0.511559 +v -0.281940 -0.013426 0.508429 +v -0.282888 -0.015060 0.504526 +v -0.290557 -0.027520 0.512931 +v -0.286722 -0.028850 0.511601 +v -0.291504 -0.024531 0.515920 +v -0.288850 -0.022134 0.518317 +v -0.284594 -0.022134 0.518317 +v -0.281940 -0.024531 0.515920 +v -0.282888 -0.027520 0.512931 +v -0.290557 -0.035924 0.525390 +v -0.286722 -0.037661 0.524663 +v -0.291504 -0.032022 0.527024 +v -0.288850 -0.028891 0.528335 +v -0.284594 -0.028891 0.528335 +v -0.281940 -0.032022 0.527024 +v -0.282888 -0.035924 0.525390 +v -0.290557 -0.039004 0.540621 +v -0.286722 -0.040888 0.540621 +v -0.291504 -0.034770 0.540621 +v -0.288850 -0.031376 0.540621 +v -0.284594 -0.031376 0.540621 +v -0.281940 -0.034770 0.540621 +v -0.282888 -0.039004 0.540621 +v -0.286722 0.041228 0.569987 +v -0.290557 0.039344 0.569987 +v -0.291504 0.035111 0.569987 +v -0.288850 0.031716 0.569987 +v -0.284594 0.031716 0.569987 +v -0.281940 0.035111 0.569987 +v -0.282887 0.039344 0.569987 +v -0.290557 -0.039004 0.569987 +v -0.286722 -0.040888 0.569987 +v -0.291504 -0.034770 0.569987 +v -0.288850 -0.031376 0.569987 +v -0.284594 -0.031376 0.569987 +v -0.281940 -0.034770 0.569987 +v -0.282888 -0.039004 0.569987 +v 0.059184 -0.110615 0.674489 +v 0.064442 -0.109618 0.676871 +v 0.064442 -0.126185 0.680220 +v 0.059184 -0.126185 0.677637 +v 0.057885 -0.112855 0.669137 +v 0.057885 -0.126185 0.671832 +v 0.061524 -0.114652 0.664846 +v 0.061524 -0.126185 0.667177 +v 0.067360 -0.114652 0.664846 +v 0.067360 -0.126185 0.667177 +v 0.070999 -0.112855 0.669137 +v 0.070999 -0.126185 0.671832 +v 0.069700 -0.110615 0.674489 +v 0.069700 -0.126185 0.677637 +v 0.059184 -0.097872 0.665893 +v 0.064442 -0.096048 0.667717 +v 0.057885 -0.101970 0.661795 +v 0.061524 -0.105257 0.658508 +v 0.067360 -0.105257 0.658508 +v 0.070999 -0.101970 0.661795 +v 0.069700 -0.097872 0.665893 +v 0.059184 -0.089277 0.653151 +v 0.064442 -0.086894 0.654148 +v 0.057885 -0.094628 0.650910 +v 0.061524 -0.098920 0.649114 +v 0.067360 -0.098920 0.649114 +v 0.070999 -0.094628 0.650910 +v 0.069700 -0.089277 0.653151 +v 0.059184 -0.086128 0.637580 +v 0.064442 -0.083545 0.637580 +v 0.057885 -0.091933 0.637580 +v 0.061524 -0.096588 0.637580 +v 0.067360 -0.096588 0.637580 +v 0.070999 -0.091933 0.637580 +v 0.069700 -0.086128 0.637580 +v 0.064442 -0.154106 0.680220 +v 0.059184 -0.154106 0.677637 +v 0.057885 -0.154106 0.671832 +v 0.061524 -0.154106 0.667177 +v 0.067360 -0.154106 0.667177 +v 0.070999 -0.154106 0.671832 +v 0.069700 -0.154106 0.677637 +v 0.069700 -0.110615 0.570437 +v 0.064442 -0.109618 0.568055 +v 0.064442 -0.126185 0.564706 +v 0.069700 -0.126185 0.567289 +v 0.070999 -0.112855 0.575789 +v 0.070999 -0.126185 0.573094 +v 0.067360 -0.114652 0.580081 +v 0.067360 -0.126185 0.577749 +v 0.061524 -0.114652 0.580081 +v 0.061524 -0.126185 0.577749 +v 0.057885 -0.112855 0.575789 +v 0.057885 -0.126185 0.573094 +v 0.059184 -0.110615 0.570437 +v 0.059184 -0.126185 0.567289 +v 0.069700 -0.097872 0.579033 +v 0.064442 -0.096048 0.577209 +v 0.070999 -0.101970 0.583131 +v 0.067360 -0.105257 0.586418 +v 0.061524 -0.105257 0.586418 +v 0.057885 -0.101970 0.583131 +v 0.059184 -0.097872 0.579033 +v 0.069700 -0.089276 0.591776 +v 0.064442 -0.086894 0.590778 +v 0.070999 -0.094628 0.594016 +v 0.067360 -0.098920 0.595813 +v 0.061524 -0.098920 0.595813 +v 0.057885 -0.094628 0.594016 +v 0.059184 -0.089276 0.591776 +v 0.069700 -0.086128 0.607346 +v 0.064442 -0.083545 0.607346 +v 0.070999 -0.091933 0.607346 +v 0.067360 -0.096588 0.607346 +v 0.061524 -0.096588 0.607346 +v 0.057885 -0.091933 0.607346 +v 0.059184 -0.086128 0.607346 +v 0.064442 -0.154106 0.564706 +v 0.069700 -0.154106 0.567289 +v 0.070999 -0.154106 0.573094 +v 0.067360 -0.154106 0.577749 +v 0.061524 -0.154106 0.577749 +v 0.057885 -0.154106 0.573094 +v 0.059184 -0.154106 0.567289 +v -0.258513 0.155389 0.579151 +v -0.260018 0.158985 0.573227 +v -0.237337 0.163156 0.573445 +v -0.237337 0.159008 0.579219 +v -0.255751 0.148791 0.579855 +v -0.237337 0.151904 0.579571 +v -0.253812 0.144159 0.574810 +v -0.237337 0.147194 0.574237 +v -0.254156 0.144981 0.567815 +v -0.237337 0.148424 0.567233 +v -0.256524 0.150638 0.564136 +v -0.237337 0.154668 0.563833 +v -0.259133 0.156870 0.566545 +v -0.237337 0.161224 0.566598 +v -0.275836 0.143704 0.579151 +v -0.278589 0.146458 0.573227 +v -0.270783 0.138651 0.579855 +v -0.267235 0.135104 0.574810 +v -0.267865 0.135734 0.567815 +v -0.272197 0.140066 0.564136 +v -0.276970 0.144839 0.566545 +v -0.287521 0.126382 0.579151 +v -0.291116 0.127887 0.573227 +v -0.280922 0.123620 0.579855 +v -0.276290 0.121680 0.574810 +v -0.277112 0.122025 0.567815 +v -0.282769 0.124393 0.564136 +v -0.289002 0.127002 0.566545 +v -0.291802 0.105207 0.579151 +v -0.295702 0.105207 0.573227 +v -0.284645 0.105207 0.579855 +v -0.279621 0.105207 0.574811 +v -0.280512 0.105207 0.567815 +v -0.286648 0.105207 0.564136 +v -0.293408 0.105207 0.566545 +v 0.276256 0.148468 0.570998 +v 0.277461 0.154820 0.568121 +v 0.254756 0.154820 0.563531 +v 0.254756 0.148468 0.566651 +v 0.273549 0.146899 0.577463 +v 0.254756 0.146899 0.573664 +v 0.271379 0.151295 0.582648 +v 0.254756 0.151295 0.579287 +v 0.271379 0.158345 0.582648 +v 0.254756 0.158345 0.579287 +v 0.273549 0.162741 0.577463 +v 0.254756 0.162741 0.573664 +v 0.276256 0.161172 0.570998 +v 0.254756 0.161172 0.566651 +v 0.293848 0.148468 0.582865 +v 0.296052 0.154820 0.580662 +v 0.288897 0.146899 0.587816 +v 0.284927 0.151295 0.591787 +v 0.284927 0.158345 0.591787 +v 0.288897 0.162741 0.587816 +v 0.293848 0.161172 0.582865 +v 0.305715 0.148468 0.600458 +v 0.308592 0.154820 0.599253 +v 0.299250 0.146899 0.603164 +v 0.294066 0.151295 0.605334 +v 0.294066 0.158345 0.605335 +v 0.299250 0.162741 0.603164 +v 0.305715 0.161172 0.600458 +v 0.310062 0.148468 0.622898 +v 0.313183 0.154820 0.622898 +v 0.303050 0.146899 0.622898 +v 0.297426 0.151295 0.622898 +v 0.297426 0.158345 0.622898 +v 0.303050 0.162741 0.622898 +v 0.310062 0.161172 0.622898 +v -0.258513 0.155389 0.666647 +v -0.237337 0.159008 0.666578 +v -0.237337 0.163156 0.672352 +v -0.260018 0.158985 0.672570 +v -0.255751 0.148791 0.665942 +v -0.237337 0.151904 0.666226 +v -0.253812 0.144159 0.670987 +v -0.237337 0.147194 0.671560 +v -0.254156 0.144981 0.677982 +v -0.237337 0.148425 0.678564 +v -0.256524 0.150638 0.681661 +v -0.237337 0.154668 0.681964 +v -0.259133 0.156871 0.679252 +v -0.237337 0.161224 0.679199 +v -0.275836 0.143704 0.666647 +v -0.278589 0.146458 0.672570 +v -0.270783 0.138652 0.665942 +v -0.267235 0.135104 0.670987 +v -0.267865 0.135734 0.677982 +v -0.272197 0.140066 0.681661 +v -0.276970 0.144839 0.679252 +v -0.287521 0.126382 0.666647 +v -0.291116 0.127887 0.672570 +v -0.280922 0.123620 0.665942 +v -0.276290 0.121681 0.670987 +v -0.277112 0.122025 0.677982 +v -0.282769 0.124393 0.681661 +v -0.289001 0.127002 0.679252 +v -0.291802 0.105207 0.666647 +v -0.295702 0.105207 0.672570 +v -0.284645 0.105207 0.665942 +v -0.279621 0.105207 0.670987 +v -0.280512 0.105207 0.677983 +v -0.286648 0.105207 0.681661 +v -0.293408 0.105207 0.679252 +v 0.276256 0.148468 0.674799 +v 0.254756 0.148468 0.679146 +v 0.254756 0.154820 0.682267 +v 0.277460 0.154820 0.677676 +v 0.273549 0.146899 0.668334 +v 0.254756 0.146899 0.672133 +v 0.271379 0.151295 0.663149 +v 0.254756 0.151295 0.666510 +v 0.271379 0.158345 0.663149 +v 0.254756 0.158345 0.666510 +v 0.273549 0.162741 0.668334 +v 0.254756 0.162741 0.672133 +v 0.276256 0.161172 0.674799 +v 0.254756 0.161172 0.679146 +v 0.293848 0.148468 0.662932 +v 0.296052 0.154820 0.665135 +v 0.288897 0.146899 0.657981 +v 0.284927 0.151295 0.654010 +v 0.284927 0.158345 0.654010 +v 0.288897 0.162741 0.657981 +v 0.293848 0.161172 0.662932 +v 0.305715 0.148468 0.645340 +v 0.308593 0.154820 0.646544 +v 0.299250 0.146899 0.642633 +v 0.294065 0.151295 0.640463 +v 0.294065 0.158345 0.640463 +v 0.299250 0.162741 0.642633 +v 0.305715 0.161172 0.645340 +v -0.258513 -0.156320 0.579151 +v -0.237337 -0.159938 0.579219 +v -0.237337 -0.164086 0.573445 +v -0.260018 -0.159916 0.573227 +v -0.255751 -0.149722 0.579855 +v -0.237337 -0.152835 0.579571 +v -0.253812 -0.145090 0.574811 +v -0.237337 -0.148125 0.574237 +v -0.254156 -0.145912 0.567815 +v -0.237337 -0.149355 0.567233 +v -0.256524 -0.151569 0.564136 +v -0.237337 -0.155599 0.563834 +v -0.259133 -0.157801 0.566545 +v -0.237337 -0.162155 0.566598 +v -0.275836 -0.144635 0.579151 +v -0.278589 -0.147389 0.573227 +v -0.270783 -0.139582 0.579855 +v -0.267235 -0.136035 0.574810 +v -0.267865 -0.136664 0.567815 +v -0.272197 -0.140996 0.564136 +v -0.276970 -0.145769 0.566545 +v -0.287521 -0.127313 0.579151 +v -0.291116 -0.128818 0.573227 +v -0.280922 -0.124551 0.579855 +v -0.276290 -0.122611 0.574810 +v -0.277112 -0.122955 0.567815 +v -0.282769 -0.125324 0.564136 +v -0.289001 -0.127933 0.566545 +v -0.291802 -0.106138 0.579151 +v -0.295702 -0.106138 0.573227 +v -0.284645 -0.106138 0.579855 +v -0.279621 -0.106138 0.574810 +v -0.280512 -0.106138 0.567815 +v -0.286648 -0.106138 0.564136 +v -0.293408 -0.106138 0.566545 +v 0.276256 -0.149399 0.570998 +v 0.254756 -0.149399 0.566652 +v 0.254756 -0.155751 0.563531 +v 0.277461 -0.155750 0.568121 +v 0.273549 -0.147830 0.577463 +v 0.254756 -0.147830 0.573664 +v 0.271379 -0.152226 0.582648 +v 0.254756 -0.152226 0.579287 +v 0.271379 -0.159276 0.582648 +v 0.254756 -0.159276 0.579287 +v 0.273550 -0.163671 0.577463 +v 0.254756 -0.163671 0.573664 +v 0.276256 -0.162103 0.570998 +v 0.254756 -0.162103 0.566651 +v 0.293848 -0.149399 0.582865 +v 0.296052 -0.155751 0.580662 +v 0.288897 -0.147830 0.587816 +v 0.284927 -0.152226 0.591787 +v 0.284927 -0.159276 0.591787 +v 0.288897 -0.163671 0.587816 +v 0.293849 -0.162103 0.582865 +v 0.305715 -0.149399 0.600458 +v 0.308592 -0.155751 0.599253 +v 0.299250 -0.147830 0.603164 +v 0.294066 -0.152226 0.605335 +v 0.294066 -0.159276 0.605335 +v 0.299250 -0.163671 0.603164 +v 0.305715 -0.162103 0.600458 +v 0.310062 -0.149399 0.622898 +v 0.313183 -0.155751 0.622898 +v 0.303050 -0.147830 0.622898 +v 0.297426 -0.152226 0.622899 +v 0.297426 -0.159276 0.622899 +v 0.303050 -0.163671 0.622899 +v 0.310062 -0.162103 0.622899 +v -0.258513 -0.156320 0.666647 +v -0.260018 -0.159916 0.672570 +v -0.237337 -0.164086 0.672352 +v -0.237337 -0.159939 0.666578 +v -0.255751 -0.149722 0.665942 +v -0.237337 -0.152835 0.666226 +v -0.253812 -0.145090 0.670987 +v -0.237337 -0.148125 0.671560 +v -0.254156 -0.145912 0.677983 +v -0.237337 -0.149355 0.678564 +v -0.256524 -0.151569 0.681661 +v -0.237337 -0.155599 0.681964 +v -0.259133 -0.157801 0.679252 +v -0.237337 -0.162155 0.679199 +v -0.275836 -0.144635 0.666647 +v -0.278589 -0.147389 0.672570 +v -0.270783 -0.139582 0.665942 +v -0.267235 -0.136035 0.670987 +v -0.267865 -0.136664 0.677982 +v -0.272197 -0.140997 0.681661 +v -0.276970 -0.145769 0.679252 +v -0.287520 -0.127313 0.666647 +v -0.291116 -0.128818 0.672570 +v -0.280922 -0.124551 0.665942 +v -0.276290 -0.122611 0.670987 +v -0.277112 -0.122955 0.677982 +v -0.282769 -0.125324 0.681661 +v -0.289001 -0.127933 0.679252 +v -0.291802 -0.106138 0.666647 +v -0.295702 -0.106138 0.672570 +v -0.284645 -0.106138 0.665942 +v -0.279621 -0.106138 0.670987 +v -0.280512 -0.106138 0.677983 +v -0.286648 -0.106138 0.681661 +v -0.293408 -0.106138 0.679252 +v 0.276256 -0.149399 0.674799 +v 0.277461 -0.155751 0.677676 +v 0.254756 -0.155751 0.682266 +v 0.254756 -0.149399 0.679146 +v 0.273550 -0.147830 0.668334 +v 0.254756 -0.147830 0.672133 +v 0.271379 -0.152226 0.663149 +v 0.254756 -0.152226 0.666510 +v 0.271379 -0.159276 0.663149 +v 0.254756 -0.159276 0.666510 +v 0.273550 -0.163671 0.668334 +v 0.254756 -0.163671 0.672134 +v 0.276256 -0.162103 0.674799 +v 0.254756 -0.162103 0.679146 +v 0.293848 -0.149399 0.662932 +v 0.296052 -0.155751 0.665135 +v 0.288897 -0.147830 0.657981 +v 0.284927 -0.152226 0.654010 +v 0.284927 -0.159276 0.654010 +v 0.288897 -0.163671 0.657981 +v 0.293849 -0.162103 0.662932 +v 0.305715 -0.149399 0.645340 +v 0.308592 -0.155751 0.646544 +v 0.299250 -0.147830 0.642633 +v 0.294066 -0.152226 0.640463 +v 0.294066 -0.159276 0.640463 +v 0.299250 -0.163671 0.642633 +v 0.305715 -0.162103 0.645340 +v 0.201639 0.098928 0.811620 +v 0.201639 0.110794 0.794028 +v 0.207990 0.113672 0.795232 +v 0.207990 0.101131 0.813824 +v 0.200070 0.093976 0.806669 +v 0.200070 0.104329 0.791321 +v 0.204465 0.090006 0.802699 +v 0.204465 0.099145 0.789151 +v 0.211516 0.090006 0.802699 +v 0.211516 0.099145 0.789151 +v 0.215911 0.093976 0.806669 +v 0.215911 0.104329 0.791321 +v 0.214342 0.098928 0.811620 +v 0.214342 0.110794 0.794028 +v 0.201639 0.081335 0.823487 +v 0.207990 0.082540 0.826364 +v 0.200070 0.078628 0.817022 +v 0.204465 0.076458 0.811837 +v 0.211516 0.076458 0.811837 +v 0.215911 0.078628 0.817022 +v 0.214342 0.081335 0.823487 +v 0.201639 0.059835 0.827834 +v 0.207990 0.059835 0.830955 +v 0.200070 0.059835 0.820822 +v 0.204465 0.059835 0.815198 +v 0.211516 0.059835 0.815198 +v 0.215911 0.059835 0.820822 +v 0.214342 0.059835 0.827834 +v 0.207990 -0.059258 0.830955 +v 0.201639 -0.059258 0.827834 +v 0.200070 -0.059258 0.820822 +v 0.204465 -0.059258 0.815198 +v 0.211515 -0.059258 0.815198 +v 0.215911 -0.059258 0.820822 +v 0.214342 -0.059258 0.827834 +v 0.201639 0.159803 0.676162 +v 0.207990 0.162681 0.677367 +v 0.200070 0.153338 0.673456 +v 0.204465 0.148154 0.671286 +v 0.211516 0.148154 0.671286 +v 0.215911 0.153338 0.673456 +v 0.214342 0.159803 0.676162 +v 0.201639 -0.098351 0.811620 +v 0.207990 -0.100554 0.813824 +v 0.207990 -0.113095 0.795232 +v 0.201639 -0.110217 0.794028 +v 0.200070 -0.093400 0.806669 +v 0.200070 -0.103752 0.791321 +v 0.204465 -0.089429 0.802699 +v 0.204465 -0.098567 0.789151 +v 0.211516 -0.089429 0.802699 +v 0.211516 -0.098567 0.789151 +v 0.215911 -0.093400 0.806669 +v 0.215911 -0.103752 0.791321 +v 0.214342 -0.098351 0.811620 +v 0.214342 -0.110217 0.794028 +v 0.201639 -0.080758 0.823487 +v 0.207990 -0.081963 0.826364 +v 0.200070 -0.078052 0.817022 +v 0.204465 -0.075881 0.811837 +v 0.211515 -0.075881 0.811837 +v 0.215911 -0.078052 0.817022 +v 0.214342 -0.080758 0.823487 +v 0.207990 -0.162104 0.677367 +v 0.201639 -0.159227 0.676162 +v 0.200070 -0.152762 0.673456 +v 0.204465 -0.147577 0.671285 +v 0.211516 -0.147577 0.671285 +v 0.215911 -0.152762 0.673456 +v 0.214342 -0.159227 0.676162 +v 0.057511 0.098928 0.811621 +v 0.057511 0.110794 0.794028 +v 0.063863 0.113672 0.795232 +v 0.063863 0.101131 0.813824 +v 0.055942 0.093976 0.806669 +v 0.055942 0.104329 0.791321 +v 0.060338 0.090006 0.802699 +v 0.060338 0.099145 0.789151 +v 0.067388 0.090006 0.802699 +v 0.067388 0.099145 0.789151 +v 0.071784 0.093976 0.806669 +v 0.071784 0.104329 0.791321 +v 0.070215 0.098928 0.811620 +v 0.070215 0.110794 0.794028 +v 0.057511 0.081335 0.823487 +v 0.063863 0.082539 0.826364 +v 0.055942 0.078628 0.817022 +v 0.060338 0.076458 0.811837 +v 0.067388 0.076458 0.811837 +v 0.071784 0.078628 0.817022 +v 0.070215 0.081335 0.823487 +v 0.057511 0.059835 0.827834 +v 0.063863 0.059835 0.830955 +v 0.055942 0.059835 0.820822 +v 0.060338 0.059835 0.815198 +v 0.067388 0.059835 0.815198 +v 0.071784 0.059835 0.820822 +v 0.070215 0.059835 0.827834 +v 0.063863 -0.059258 0.830955 +v 0.057511 -0.059258 0.827834 +v 0.055942 -0.059258 0.820822 +v 0.060338 -0.059258 0.815198 +v 0.067388 -0.059258 0.815198 +v 0.071784 -0.059258 0.820822 +v 0.070215 -0.059258 0.827834 +v 0.057511 0.159803 0.676162 +v 0.063863 0.162681 0.677367 +v 0.055942 0.153338 0.673456 +v 0.060338 0.148154 0.671286 +v 0.067388 0.148154 0.671286 +v 0.071784 0.153338 0.673456 +v 0.070215 0.159803 0.676162 +v 0.057511 -0.098350 0.811621 +v 0.063863 -0.100554 0.813824 +v 0.063863 -0.113095 0.795232 +v 0.057511 -0.110217 0.794028 +v 0.055942 -0.093400 0.806669 +v 0.055942 -0.103752 0.791321 +v 0.060338 -0.089429 0.802699 +v 0.060338 -0.098567 0.789151 +v 0.067388 -0.089429 0.802699 +v 0.067388 -0.098567 0.789151 +v 0.071784 -0.093400 0.806669 +v 0.071784 -0.103752 0.791321 +v 0.070215 -0.098350 0.811620 +v 0.070215 -0.110217 0.794028 +v 0.057511 -0.080758 0.823487 +v 0.063863 -0.081963 0.826365 +v 0.055942 -0.078052 0.817022 +v 0.060338 -0.075881 0.811837 +v 0.067388 -0.075881 0.811837 +v 0.071784 -0.078052 0.817022 +v 0.070215 -0.080758 0.823487 +v 0.063863 -0.162104 0.677367 +v 0.057511 -0.159226 0.676162 +v 0.055942 -0.152762 0.673456 +v 0.060338 -0.147577 0.671286 +v 0.067388 -0.147577 0.671286 +v 0.071784 -0.152762 0.673456 +v 0.070215 -0.159226 0.676162 +v 0.142663 -0.067642 0.240663 +v 0.146113 -0.075258 0.239219 +v 0.150554 -0.075258 0.261186 +v 0.146812 -0.067642 0.261186 +v 0.134910 -0.065760 0.243908 +v 0.138404 -0.065760 0.261186 +v 0.128693 -0.071031 0.246511 +v 0.131660 -0.071031 0.261186 +v 0.128693 -0.079485 0.246511 +v 0.131660 -0.079485 0.261186 +v 0.134910 -0.084756 0.243908 +v 0.138404 -0.084756 0.261186 +v 0.142663 -0.082875 0.240663 +v 0.146812 -0.082875 0.261186 +v 0.131331 -0.067642 0.223864 +v 0.133973 -0.075258 0.221222 +v 0.125394 -0.065760 0.229801 +v 0.120633 -0.071031 0.234562 +v 0.120633 -0.079485 0.234562 +v 0.125394 -0.084756 0.229801 +v 0.131331 -0.082875 0.223864 +v 0.114532 -0.067642 0.212532 +v 0.115977 -0.075258 0.209082 +v 0.111287 -0.065760 0.220285 +v 0.108684 -0.071031 0.226502 +v 0.108684 -0.079485 0.226502 +v 0.111287 -0.084756 0.220285 +v 0.114532 -0.082875 0.212532 +v 0.094009 -0.067642 0.208383 +v 0.094009 -0.075258 0.204641 +v 0.094009 -0.065760 0.216792 +v 0.094009 -0.071031 0.223535 +v 0.094009 -0.079485 0.223535 +v 0.094009 -0.084756 0.216792 +v 0.094009 -0.082875 0.208383 +v 0.150554 -0.075259 0.374613 +v 0.146812 -0.067642 0.374613 +v 0.138404 -0.065761 0.374613 +v 0.131660 -0.071031 0.374613 +v 0.131660 -0.079486 0.374613 +v 0.138404 -0.084756 0.374613 +v 0.146812 -0.082875 0.374613 +v 0.081731 -0.067642 0.208383 +v 0.081731 -0.075258 0.204641 +v 0.081731 -0.065760 0.216792 +v 0.081731 -0.071031 0.223535 +v 0.081731 -0.079485 0.223535 +v 0.081731 -0.084756 0.216792 +v 0.081731 -0.082875 0.208383 +v 0.083843 -0.129460 0.206802 +v 0.087293 -0.130904 0.214419 +v 0.091734 -0.108937 0.214418 +v 0.087992 -0.108938 0.206802 +v 0.076090 -0.126215 0.204921 +v 0.079583 -0.108938 0.204921 +v 0.069873 -0.123612 0.210191 +v 0.072840 -0.108937 0.210191 +v 0.069873 -0.123612 0.218645 +v 0.072840 -0.108937 0.218645 +v 0.076090 -0.126215 0.223916 +v 0.079583 -0.108937 0.223916 +v 0.083843 -0.129460 0.222035 +v 0.087992 -0.108937 0.222035 +v 0.072511 -0.146259 0.206802 +v 0.075153 -0.148901 0.214419 +v 0.066574 -0.140322 0.204921 +v 0.061813 -0.135561 0.210191 +v 0.061813 -0.135561 0.218645 +v 0.066574 -0.140322 0.223916 +v 0.072511 -0.146259 0.222035 +v 0.055712 -0.157591 0.206802 +v 0.057156 -0.161041 0.214418 +v 0.052467 -0.149838 0.204921 +v 0.049864 -0.143621 0.210192 +v 0.049864 -0.143621 0.218645 +v 0.052467 -0.149838 0.223916 +v 0.055712 -0.157591 0.222035 +v 0.035189 -0.161740 0.206802 +v 0.035189 -0.165482 0.214418 +v 0.035189 -0.153331 0.204921 +v 0.035189 -0.146588 0.210192 +v 0.035189 -0.146588 0.218645 +v 0.035189 -0.153331 0.223916 +v 0.035189 -0.161740 0.222035 +v -0.083074 -0.161740 0.206802 +v -0.083074 -0.165482 0.214418 +v -0.083074 -0.153331 0.204921 +v -0.083074 -0.146588 0.210191 +v -0.083074 -0.146588 0.218645 +v -0.083074 -0.153331 0.223916 +v -0.083074 -0.161740 0.222035 +v 0.083843 0.130224 0.222035 +v 0.087293 0.131668 0.214419 +v 0.091734 0.109701 0.214418 +v 0.087992 0.109701 0.222035 +v 0.076090 0.126979 0.223916 +v 0.079583 0.109701 0.223916 +v 0.069873 0.124376 0.218645 +v 0.072840 0.109701 0.218645 +v 0.069873 0.124376 0.210191 +v 0.072840 0.109701 0.210191 +v 0.076090 0.126979 0.204921 +v 0.079583 0.109701 0.204921 +v 0.083843 0.130224 0.206802 +v 0.087992 0.109701 0.206802 +v 0.072511 0.147023 0.222035 +v 0.075153 0.149665 0.214419 +v 0.066574 0.141086 0.223916 +v 0.061813 0.136325 0.218645 +v 0.061813 0.136325 0.210191 +v 0.066574 0.141086 0.204921 +v 0.072511 0.147023 0.206802 +v 0.055712 0.158355 0.222035 +v 0.057156 0.161805 0.214419 +v 0.052467 0.150602 0.223916 +v 0.049864 0.144385 0.218645 +v 0.049864 0.144385 0.210191 +v 0.052467 0.150602 0.204921 +v 0.055712 0.158355 0.206802 +v 0.035189 0.162504 0.222035 +v 0.035189 0.166246 0.214419 +v 0.035189 0.154095 0.223916 +v 0.035189 0.147352 0.218645 +v 0.035189 0.147352 0.210191 +v 0.035189 0.154095 0.204921 +v 0.035189 0.162504 0.206802 +v -0.083074 0.162504 0.222035 +v -0.083074 0.166246 0.214419 +v -0.083074 0.154095 0.223916 +v -0.083074 0.147352 0.218646 +v -0.083074 0.147352 0.210192 +v -0.083074 0.154095 0.204921 +v -0.083074 0.162504 0.206802 +v 0.084656 -0.067532 0.050320 +v 0.088106 -0.075149 0.048876 +v 0.092548 -0.075149 0.070843 +v 0.088806 -0.067532 0.070843 +v 0.076904 -0.065651 0.053565 +v 0.080397 -0.065651 0.070843 +v 0.070687 -0.070922 0.056168 +v 0.073654 -0.070922 0.070843 +v 0.070687 -0.079376 0.056168 +v 0.073654 -0.079376 0.070843 +v 0.076904 -0.084647 0.053565 +v 0.080397 -0.084647 0.070843 +v 0.084656 -0.082765 0.050320 +v 0.088806 -0.082765 0.070843 +v 0.073325 -0.067532 0.033521 +v 0.075967 -0.075149 0.030879 +v 0.067388 -0.065651 0.039458 +v 0.062627 -0.070922 0.044219 +v 0.062627 -0.079376 0.044219 +v 0.067388 -0.084647 0.039458 +v 0.073325 -0.082765 0.033521 +v 0.056526 -0.067532 0.022190 +v 0.057970 -0.075149 0.018739 +v 0.053280 -0.065651 0.029942 +v 0.050678 -0.070922 0.036159 +v 0.050678 -0.079376 0.036159 +v 0.053280 -0.084647 0.029942 +v 0.056526 -0.082765 0.022190 +v 0.036003 -0.067532 0.018040 +v 0.036003 -0.075149 0.014298 +v 0.036003 -0.065651 0.026449 +v 0.036003 -0.070922 0.033192 +v 0.036003 -0.079376 0.033192 +v 0.036003 -0.084647 0.026449 +v 0.036003 -0.082765 0.018040 +v 0.092548 -0.075148 0.207827 +v 0.088806 -0.067532 0.207827 +v 0.080397 -0.065650 0.207827 +v 0.073654 -0.070921 0.207827 +v 0.073654 -0.079375 0.207827 +v 0.080397 -0.084646 0.207827 +v 0.088806 -0.082765 0.207827 +v -0.007682 -0.067532 0.018040 +v -0.007682 -0.075148 0.014298 +v -0.007682 -0.065651 0.026449 +v -0.007682 -0.070921 0.033192 +v -0.007682 -0.079375 0.033192 +v -0.007682 -0.084646 0.026449 +v -0.007682 -0.082765 0.018040 +v -0.015024 -0.129460 0.372904 +v -0.011573 -0.130905 0.380521 +v -0.007132 -0.108937 0.380521 +v -0.010874 -0.108937 0.372904 +v -0.022776 -0.126215 0.371023 +v -0.019283 -0.108937 0.371023 +v -0.028993 -0.123612 0.376294 +v -0.026026 -0.108937 0.376294 +v -0.028993 -0.123612 0.384747 +v -0.026026 -0.108937 0.384747 +v -0.022776 -0.126215 0.390018 +v -0.019283 -0.108937 0.390018 +v -0.015024 -0.129460 0.388137 +v -0.010874 -0.108937 0.388137 +v -0.026355 -0.146259 0.372904 +v -0.023713 -0.148901 0.380521 +v -0.032292 -0.140322 0.371023 +v -0.037053 -0.135561 0.376294 +v -0.037053 -0.135561 0.384747 +v -0.032292 -0.140322 0.390018 +v -0.026355 -0.146259 0.388137 +v -0.043154 -0.157591 0.372904 +v -0.041710 -0.161041 0.380521 +v -0.046399 -0.149838 0.371023 +v -0.049002 -0.143621 0.376294 +v -0.049002 -0.143621 0.384747 +v -0.046399 -0.149838 0.390018 +v -0.043154 -0.157591 0.388137 +v -0.063677 -0.161740 0.372904 +v -0.063677 -0.165482 0.380521 +v -0.063677 -0.153331 0.371023 +v -0.063677 -0.146588 0.376294 +v -0.063677 -0.146588 0.384747 +v -0.063677 -0.153331 0.390018 +v -0.063677 -0.161740 0.388137 +v -0.087533 -0.161740 0.372904 +v -0.087533 -0.165482 0.380521 +v -0.087533 -0.153331 0.371023 +v -0.087533 -0.146588 0.376294 +v -0.087533 -0.146588 0.384747 +v -0.087533 -0.153331 0.390018 +v -0.087533 -0.161740 0.388137 +v -0.015024 0.130224 0.388137 +v -0.011573 0.131668 0.380521 +v -0.007132 0.109701 0.380521 +v -0.010874 0.109701 0.388137 +v -0.022776 0.126978 0.390018 +v -0.019283 0.109701 0.390018 +v -0.028993 0.124376 0.384747 +v -0.026026 0.109701 0.384747 +v -0.028993 0.124376 0.376294 +v -0.026026 0.109701 0.376294 +v -0.022776 0.126978 0.371023 +v -0.019283 0.109701 0.371023 +v -0.015024 0.130224 0.372904 +v -0.010874 0.109701 0.372904 +v -0.026355 0.147023 0.388137 +v -0.023713 0.149665 0.380521 +v -0.032292 0.141086 0.390018 +v -0.037053 0.136325 0.384747 +v -0.037053 0.136325 0.376294 +v -0.032292 0.141086 0.371023 +v -0.026355 0.147023 0.372904 +v -0.043154 0.158355 0.388137 +v -0.041710 0.161805 0.380521 +v -0.046399 0.150602 0.390018 +v -0.049002 0.144385 0.384747 +v -0.049002 0.144385 0.376294 +v -0.046399 0.150602 0.371023 +v -0.043154 0.158355 0.372904 +v -0.063677 0.162504 0.388137 +v -0.063677 0.166246 0.380521 +v -0.063677 0.154095 0.390018 +v -0.063677 0.147352 0.384748 +v -0.063677 0.147352 0.376294 +v -0.063677 0.154095 0.371023 +v -0.063677 0.162504 0.372904 +v -0.087533 0.162504 0.388137 +v -0.087533 0.166246 0.380521 +v -0.087533 0.154095 0.390018 +v -0.087533 0.147352 0.384748 +v -0.087533 0.147352 0.376294 +v -0.087533 0.154095 0.371023 +v -0.087533 0.162504 0.372904 +v 0.154985 -0.105921 0.645879 +v 0.170785 -0.105921 0.634323 +v 0.178222 -0.105921 0.639758 +v 0.172080 -0.105921 0.658360 +v 0.170785 -0.118944 0.634323 +v 0.178222 -0.118944 0.639758 +v 0.154985 -0.118944 0.645879 +v 0.172080 -0.118944 0.658360 +v 0.187863 -0.105921 0.639758 +v 0.194004 -0.105921 0.658360 +v 0.187863 -0.118944 0.639758 +v 0.194004 -0.118944 0.658360 +v 0.195300 -0.105921 0.634323 +v 0.211100 -0.105921 0.645879 +v 0.195300 -0.118944 0.634323 +v 0.211100 -0.118944 0.645879 +v 0.198226 -0.105921 0.625352 +v 0.217821 -0.105921 0.625352 +v 0.198226 -0.118944 0.625352 +v 0.217821 -0.118944 0.625353 +v 0.198226 -0.105922 0.584785 +v 0.217821 -0.105922 0.584785 +v 0.198226 -0.118944 0.584785 +v 0.217821 -0.118944 0.584785 +v 0.063424 -0.105922 0.537136 +v 0.081818 -0.105922 0.528866 +v 0.081818 -0.118944 0.528866 +v 0.063424 -0.118944 0.537136 +v 0.217821 -0.105921 0.517099 +v 0.198226 -0.105921 0.517099 +v 0.198226 -0.118944 0.517099 +v 0.217821 -0.118944 0.517099 +v 0.222802 -0.105922 0.658360 +v 0.222802 -0.118944 0.658360 +v 0.222803 -0.105922 0.645879 +v 0.222803 -0.118944 0.645879 +v 0.222803 -0.105922 0.625352 +v 0.222803 -0.118944 0.625352 +v 0.222803 -0.105922 0.584785 +v 0.222803 -0.118944 0.584785 +v 0.142663 0.082558 0.240663 +v 0.146113 0.074942 0.239219 +v 0.150554 0.074942 0.261186 +v 0.146812 0.082558 0.261186 +v 0.134910 0.084439 0.243908 +v 0.138404 0.084439 0.261186 +v 0.128693 0.079168 0.246511 +v 0.131660 0.079168 0.261186 +v 0.128693 0.070715 0.246511 +v 0.131660 0.070715 0.261186 +v 0.134910 0.065444 0.243908 +v 0.138404 0.065444 0.261186 +v 0.142663 0.067325 0.240663 +v 0.146812 0.067325 0.261186 +v 0.131331 0.082558 0.223864 +v 0.133974 0.074942 0.221222 +v 0.125394 0.084439 0.229801 +v 0.120633 0.079168 0.234562 +v 0.120633 0.070715 0.234562 +v 0.125394 0.065444 0.229801 +v 0.131331 0.067325 0.223864 +v 0.114532 0.082558 0.212532 +v 0.115977 0.074941 0.209082 +v 0.111287 0.084439 0.220285 +v 0.108684 0.079168 0.226502 +v 0.108684 0.070715 0.226502 +v 0.111287 0.065444 0.220285 +v 0.114532 0.067325 0.212532 +v 0.094009 0.082558 0.208383 +v 0.094009 0.074941 0.204641 +v 0.094009 0.084439 0.216792 +v 0.094009 0.079168 0.223535 +v 0.094009 0.070715 0.223535 +v 0.094009 0.065444 0.216792 +v 0.094009 0.067325 0.208383 +v 0.150554 0.074942 0.374613 +v 0.146812 0.082558 0.374613 +v 0.138404 0.084439 0.374613 +v 0.131660 0.079168 0.374613 +v 0.131660 0.070715 0.374613 +v 0.138404 0.065444 0.374613 +v 0.146812 0.067325 0.374613 +v 0.081731 0.082558 0.208383 +v 0.081731 0.074941 0.204641 +v 0.081731 0.084439 0.216792 +v 0.081731 0.079168 0.223535 +v 0.081731 0.070715 0.223535 +v 0.081731 0.065444 0.216792 +v 0.081731 0.067325 0.208383 +v 0.084568 0.082643 0.050231 +v 0.088018 0.075026 0.048787 +v 0.092459 0.075026 0.070755 +v 0.088717 0.082643 0.070755 +v 0.076815 0.084524 0.053477 +v 0.080309 0.084524 0.070755 +v 0.070598 0.079253 0.056080 +v 0.073565 0.079253 0.070755 +v 0.070598 0.070799 0.056080 +v 0.073565 0.070799 0.070755 +v 0.076815 0.065528 0.053477 +v 0.080308 0.065528 0.070755 +v 0.084568 0.067410 0.050231 +v 0.088717 0.067410 0.070755 +v 0.073236 0.082643 0.033433 +v 0.075878 0.075026 0.030790 +v 0.067299 0.084524 0.039369 +v 0.062538 0.079253 0.044131 +v 0.062538 0.070799 0.044131 +v 0.067299 0.065528 0.039369 +v 0.073236 0.067410 0.033433 +v 0.056437 0.082643 0.022101 +v 0.057882 0.075026 0.018651 +v 0.053192 0.084524 0.029854 +v 0.050589 0.079253 0.036071 +v 0.050589 0.070799 0.036071 +v 0.053192 0.065528 0.029854 +v 0.056437 0.067410 0.022101 +v 0.035914 0.082643 0.017952 +v 0.035914 0.075026 0.014209 +v 0.035914 0.084524 0.026360 +v 0.035914 0.079253 0.033104 +v 0.035914 0.070799 0.033104 +v 0.035914 0.065528 0.026360 +v 0.035914 0.067410 0.017952 +v 0.092459 0.075026 0.207738 +v 0.088717 0.082643 0.207738 +v 0.080309 0.084524 0.207738 +v 0.073565 0.079253 0.207738 +v 0.073565 0.070799 0.207738 +v 0.080309 0.065529 0.207738 +v 0.088717 0.067410 0.207738 +v -0.007771 0.082643 0.017952 +v -0.007770 0.075026 0.014209 +v -0.007771 0.084524 0.026360 +v -0.007771 0.079253 0.033104 +v -0.007771 0.070799 0.033104 +v -0.007770 0.065529 0.026360 +v -0.007770 0.067410 0.017952 +v 0.199121 0.133132 0.518739 +v 0.199121 0.133132 0.536918 +v 0.199121 0.091728 0.536918 +v 0.199121 0.091728 0.518739 +v 0.208540 0.086290 0.536918 +v 0.208540 0.086290 0.518739 +v 0.217960 0.091728 0.536918 +v 0.217960 0.091728 0.518739 +v 0.217960 0.133132 0.536918 +v 0.217960 0.133132 0.518739 +v 0.208540 0.138570 0.536918 +v 0.208540 0.138569 0.524696 +v 0.063955 0.133137 0.518739 +v 0.063955 0.133137 0.536918 +v 0.063955 0.091733 0.536918 +v 0.063955 0.091733 0.518739 +v 0.073374 0.086295 0.536918 +v 0.073374 0.086295 0.518739 +v 0.082793 0.091733 0.536918 +v 0.082793 0.091733 0.518739 +v 0.082793 0.133137 0.536918 +v 0.082793 0.133137 0.518739 +v 0.073374 0.138575 0.536918 +v 0.073374 0.138575 0.524999 +v 0.154985 0.119312 0.645879 +v 0.170785 0.119312 0.634322 +v 0.178222 0.119312 0.639758 +v 0.172080 0.119312 0.658360 +v 0.170785 0.106290 0.634322 +v 0.178222 0.106290 0.639758 +v 0.154985 0.106290 0.645879 +v 0.172080 0.106290 0.658360 +v 0.187863 0.119312 0.639758 +v 0.194004 0.119312 0.658360 +v 0.187863 0.106290 0.639758 +v 0.194004 0.106290 0.658360 +v 0.195300 0.119312 0.634322 +v 0.211100 0.119312 0.645879 +v 0.195300 0.106290 0.634322 +v 0.211100 0.106290 0.645879 +v 0.198226 0.119312 0.625352 +v 0.217821 0.119312 0.625352 +v 0.198226 0.106290 0.625352 +v 0.217821 0.106290 0.625352 +v 0.198226 0.119312 0.584785 +v 0.217821 0.119312 0.584785 +v 0.198226 0.106290 0.584785 +v 0.217821 0.106290 0.584785 +v 0.063424 0.119312 0.537136 +v 0.081818 0.119312 0.528866 +v 0.081818 0.106290 0.528865 +v 0.063424 0.106290 0.537136 +v 0.217821 0.119312 0.517099 +v 0.198226 0.119312 0.517099 +v 0.198226 0.106290 0.517099 +v 0.217821 0.106290 0.517099 +v 0.222802 0.119312 0.658360 +v 0.222802 0.106290 0.658360 +v 0.222802 0.119312 0.645879 +v 0.222802 0.106290 0.645879 +v 0.222803 0.119312 0.625352 +v 0.222803 0.106290 0.625352 +v 0.222803 0.119312 0.584785 +v 0.222803 0.106290 0.584785 +v 0.207398 -0.054020 0.827173 +v 0.207398 -0.059342 0.829788 +v 0.066516 -0.059342 0.829788 +v 0.066516 -0.054020 0.827173 +v 0.207398 -0.052705 0.821298 +v 0.066516 -0.052705 0.821298 +v 0.207398 -0.056388 0.816586 +v 0.066516 -0.056388 0.816586 +v 0.207398 -0.062295 0.816586 +v 0.066516 -0.062295 0.816586 +v 0.207398 -0.065978 0.821298 +v 0.066516 -0.065978 0.821298 +v 0.207398 -0.064663 0.827173 +v 0.066516 -0.064663 0.827173 +v 0.207404 0.064919 0.827173 +v 0.207404 0.059596 0.829788 +v 0.066521 0.059596 0.829788 +v 0.066521 0.064919 0.827173 +v 0.207404 0.066233 0.821298 +v 0.066521 0.066233 0.821298 +v 0.207404 0.062550 0.816586 +v 0.066521 0.062550 0.816586 +v 0.207404 0.056643 0.816586 +v 0.066521 0.056643 0.816586 +v 0.207404 0.052960 0.821298 +v 0.066521 0.052960 0.821298 +v 0.207404 0.054274 0.827173 +v 0.066521 0.054275 0.827173 +v 0.212486 -0.150147 0.572549 +v 0.215101 -0.155469 0.572549 +v 0.215101 -0.155469 0.675081 +v 0.212486 -0.150146 0.675081 +v 0.206611 -0.148832 0.572549 +v 0.206611 -0.148832 0.675081 +v 0.201899 -0.152515 0.572549 +v 0.201899 -0.152515 0.675081 +v 0.201899 -0.158422 0.572549 +v 0.201899 -0.158422 0.675081 +v 0.206611 -0.162105 0.572549 +v 0.206611 -0.162105 0.675081 +v 0.212486 -0.160790 0.572549 +v 0.212486 -0.160790 0.675081 +v 0.068770 -0.150146 0.572549 +v 0.071385 -0.155469 0.572549 +v 0.071385 -0.155469 0.675081 +v 0.068770 -0.150146 0.675081 +v 0.062895 -0.148832 0.572549 +v 0.062895 -0.148832 0.675081 +v 0.058183 -0.152515 0.572549 +v 0.058183 -0.152515 0.675081 +v 0.058183 -0.158422 0.572549 +v 0.058183 -0.158422 0.675081 +v 0.062895 -0.162105 0.572549 +v 0.062895 -0.162105 0.675081 +v 0.068770 -0.160790 0.572549 +v 0.068770 -0.160790 0.675081 +v -0.082060 -0.150146 0.572553 +v -0.079445 -0.155468 0.572553 +v -0.079445 -0.155469 0.675086 +v -0.082060 -0.150146 0.675086 +v -0.087936 -0.148832 0.572553 +v -0.087936 -0.148832 0.675086 +v -0.092647 -0.152515 0.572553 +v -0.092647 -0.152515 0.675086 +v -0.092647 -0.158422 0.572553 +v -0.092647 -0.158422 0.675086 +v -0.087936 -0.162105 0.572553 +v -0.087936 -0.162105 0.675086 +v -0.082060 -0.160790 0.572553 +v -0.082060 -0.160790 0.675086 +v -0.236358 -0.150146 0.572551 +v -0.233743 -0.155468 0.572551 +v -0.233743 -0.155468 0.675084 +v -0.236358 -0.150146 0.675084 +v -0.242233 -0.148832 0.572551 +v -0.242233 -0.148832 0.675084 +v -0.246945 -0.152515 0.572551 +v -0.246945 -0.152515 0.675084 +v -0.246945 -0.158422 0.572551 +v -0.246945 -0.158422 0.675084 +v -0.242233 -0.162105 0.572551 +v -0.242233 -0.162105 0.675084 +v -0.236358 -0.160790 0.572551 +v -0.236358 -0.160790 0.675084 +v -0.282380 0.005293 0.572532 +v -0.279765 -0.000028 0.572532 +v -0.279765 -0.000028 0.675065 +v -0.282380 0.005294 0.675065 +v -0.288255 0.006608 0.572532 +v -0.288255 0.006608 0.675065 +v -0.292967 0.002925 0.572532 +v -0.292967 0.002925 0.675065 +v -0.292967 -0.002982 0.572532 +v -0.292967 -0.002982 0.675065 +v -0.288255 -0.006665 0.572532 +v -0.288255 -0.006665 0.675065 +v -0.282380 -0.005350 0.572532 +v -0.282380 -0.005350 0.675065 +v 0.212736 0.160689 0.572551 +v 0.215351 0.155367 0.572551 +v 0.215351 0.155367 0.675084 +v 0.212736 0.160690 0.675084 +v 0.206861 0.162004 0.572551 +v 0.206861 0.162004 0.675084 +v 0.202149 0.158320 0.572551 +v 0.202149 0.158321 0.675084 +v 0.202149 0.152414 0.572551 +v 0.202149 0.152414 0.675084 +v 0.206861 0.148730 0.572551 +v 0.206861 0.148731 0.675084 +v 0.212736 0.150045 0.572551 +v 0.212736 0.150045 0.675084 +v 0.068770 0.160689 0.572551 +v 0.071385 0.155367 0.572551 +v 0.071385 0.155367 0.675084 +v 0.068770 0.160690 0.675084 +v 0.062895 0.162004 0.572551 +v 0.062895 0.162004 0.675084 +v 0.058183 0.158321 0.572551 +v 0.058183 0.158321 0.675084 +v 0.058183 0.152414 0.572551 +v 0.058183 0.152414 0.675084 +v 0.062895 0.148731 0.572551 +v 0.062895 0.148731 0.675084 +v 0.068770 0.150045 0.572551 +v 0.068770 0.150045 0.675084 +v -0.082060 0.160689 0.572549 +v -0.079445 0.155367 0.572549 +v -0.079445 0.155367 0.675081 +v -0.082060 0.160690 0.675081 +v -0.087935 0.162004 0.572549 +v -0.087935 0.162004 0.675081 +v -0.092647 0.158321 0.572549 +v -0.092647 0.158321 0.675081 +v -0.092647 0.152414 0.572549 +v -0.092647 0.152414 0.675081 +v -0.087935 0.148731 0.572549 +v -0.087935 0.148731 0.675081 +v -0.082060 0.150045 0.572549 +v -0.082060 0.150045 0.675081 +v -0.236607 0.160690 0.572553 +v -0.233993 0.155367 0.572553 +v -0.233993 0.155367 0.675086 +v -0.236607 0.160690 0.675086 +v -0.242483 0.162004 0.572553 +v -0.242483 0.162004 0.675086 +v -0.247195 0.158321 0.572553 +v -0.247195 0.158321 0.675086 +v -0.247195 0.152414 0.572553 +v -0.247195 0.152414 0.675086 +v -0.242483 0.148731 0.572553 +v -0.242483 0.148731 0.675086 +v -0.236607 0.150045 0.572553 +v -0.236607 0.150046 0.675086 +v -0.081282 0.157103 0.669418 +v -0.083835 0.151920 0.667283 +v 0.067760 0.104577 0.785791 +v 0.068095 0.110129 0.787847 +v -0.083103 0.160677 0.674216 +v 0.065148 0.112624 0.792466 +v -0.087926 0.159952 0.678064 +v 0.061137 0.110183 0.796170 +v -0.092119 0.155472 0.678063 +v 0.059083 0.104645 0.796170 +v -0.092525 0.150612 0.674216 +v 0.060532 0.100179 0.792466 +v -0.088838 0.149032 0.669418 +v 0.064394 0.100149 0.787847 +v 0.233595 0.120055 0.521860 +v 0.233595 0.112646 0.525500 +v 0.075377 0.112647 0.525500 +v 0.075377 0.120056 0.521860 +v 0.233595 0.121884 0.513681 +v 0.075377 0.121885 0.513681 +v 0.233595 0.116757 0.507122 +v 0.075377 0.116759 0.507122 +v 0.233595 0.108534 0.507122 +v 0.075377 0.108535 0.507122 +v 0.233595 0.103408 0.513681 +v 0.075377 0.103409 0.513681 +v 0.233595 0.105237 0.521860 +v 0.075377 0.105238 0.521860 +v 0.233595 -0.104920 0.521860 +v 0.233595 -0.112329 0.525500 +v 0.075377 -0.112328 0.525500 +v 0.075377 -0.104920 0.521860 +v 0.233595 -0.103091 0.513681 +v 0.075377 -0.103090 0.513681 +v 0.233595 -0.108218 0.507122 +v 0.075377 -0.108216 0.507122 +v 0.233595 -0.116441 0.507122 +v 0.075377 -0.116440 0.507122 +v 0.233595 -0.121567 0.513681 +v 0.075377 -0.121566 0.513681 +v 0.233595 -0.119737 0.521860 +v 0.075377 -0.119737 0.521860 +v 0.200216 0.137745 0.521734 +v 0.207983 0.137745 0.525551 +v 0.207983 -0.138567 0.525550 +v 0.200215 -0.138567 0.521734 +v 0.198298 0.137745 0.513160 +v 0.198297 -0.138567 0.513160 +v 0.203674 0.137745 0.506283 +v 0.203671 -0.138567 0.506283 +v 0.212294 0.137745 0.506283 +v 0.212293 -0.138567 0.506283 +v 0.217669 0.137745 0.513160 +v 0.217667 -0.138567 0.513160 +v 0.215750 0.137745 0.521734 +v 0.215749 -0.138567 0.521734 +v 0.199604 0.123380 0.513454 +v 0.204263 0.123380 0.507493 +v 0.211704 0.123380 0.507493 +v 0.214696 0.123380 0.520904 +v 0.216363 0.123380 0.513454 +v 0.201270 0.123380 0.520904 +v 0.207983 0.123380 0.524203 +v 0.201270 0.137745 0.520904 +v 0.207983 0.137745 0.524203 +v 0.214696 0.137745 0.520904 +v 0.216363 0.137745 0.513454 +v 0.211704 0.137745 0.507493 +v 0.204263 0.137745 0.507493 +v 0.199604 0.137745 0.513454 +v 0.207983 -0.138567 0.524007 +v 0.201398 -0.138567 0.520772 +v 0.199772 -0.138567 0.513503 +v 0.204328 -0.138567 0.507674 +v 0.211637 -0.138567 0.507674 +v 0.216193 -0.138567 0.513503 +v 0.214567 -0.138567 0.520772 +v 0.207983 -0.117634 0.524007 +v 0.201398 -0.117634 0.520772 +v 0.199772 -0.117634 0.513503 +v 0.204328 -0.117634 0.507674 +v 0.211637 -0.117634 0.507674 +v 0.216193 -0.117634 0.513503 +v 0.214567 -0.117634 0.520772 +v 0.065598 0.137870 0.521726 +v 0.073366 0.137870 0.525542 +v 0.073365 -0.143684 0.525542 +v 0.065598 -0.143684 0.521726 +v 0.063681 0.137870 0.513151 +v 0.063680 -0.143684 0.513151 +v 0.069056 0.137870 0.506275 +v 0.069054 -0.143684 0.506275 +v 0.077676 0.137870 0.506275 +v 0.077675 -0.143684 0.506275 +v 0.083051 0.137870 0.513151 +v 0.083050 -0.143684 0.513151 +v 0.081133 0.137870 0.521726 +v 0.081132 -0.143684 0.521726 +v 0.064986 0.123505 0.513446 +v 0.069646 0.123505 0.507485 +v 0.077086 0.123505 0.507485 +v 0.080079 0.123505 0.520896 +v 0.081746 0.123505 0.513445 +v 0.066653 0.123505 0.520896 +v 0.073366 0.123505 0.524194 +v 0.066653 0.137870 0.520896 +v 0.073366 0.137870 0.524194 +v 0.080079 0.137870 0.520896 +v 0.081746 0.137870 0.513445 +v 0.077086 0.137870 0.507485 +v 0.069646 0.137870 0.507485 +v 0.064986 0.137870 0.513446 +v -0.096835 0.172185 0.488825 +v -0.086785 0.172185 0.493763 +v -0.086786 -0.171592 0.493763 +v -0.096836 -0.171592 0.488825 +v -0.099317 0.172185 0.477730 +v -0.099318 -0.171592 0.477730 +v -0.092362 0.172185 0.468833 +v -0.092364 -0.171592 0.468833 +v -0.081208 0.172185 0.468833 +v -0.081209 -0.171592 0.468833 +v -0.074253 0.172185 0.477730 +v -0.074255 -0.171592 0.477730 +v -0.076735 0.172185 0.488825 +v -0.076737 -0.171592 0.488825 +v -0.096589 0.172185 0.033602 +v -0.086539 0.172185 0.038539 +v -0.086540 -0.171592 0.038539 +v -0.096590 -0.171592 0.033601 +v -0.099071 0.172185 0.022507 +v -0.099071 -0.171592 0.022507 +v -0.092115 0.172185 0.013609 +v -0.092118 -0.171592 0.013609 +v -0.080961 0.172185 0.013609 +v -0.080963 -0.171592 0.013609 +v -0.074007 0.172185 0.022507 +v -0.074009 -0.171592 0.022507 +v -0.076489 0.172185 0.033601 +v -0.076490 -0.171592 0.033601 +v -0.096714 0.146337 0.496660 +v -0.086664 0.141399 0.496660 +v -0.086665 0.141399 0.006752 +v -0.096715 0.146337 0.006752 +v -0.099196 0.157431 0.496660 +v -0.099196 0.157432 0.006752 +v -0.092240 0.166329 0.496660 +v -0.092243 0.166329 0.006752 +v -0.081086 0.166329 0.496660 +v -0.081087 0.166329 0.006752 +v -0.074132 0.157431 0.496660 +v -0.074134 0.157432 0.006752 +v -0.076614 0.146337 0.496660 +v -0.076615 0.146337 0.006752 +v -0.096714 -0.162480 0.496785 +v -0.086664 -0.167418 0.496785 +v -0.086665 -0.167418 0.006877 +v -0.096715 -0.162480 0.006877 +v -0.099196 -0.151386 0.496785 +v -0.099196 -0.151385 0.006877 +v -0.092240 -0.142488 0.496785 +v -0.092243 -0.142488 0.006877 +v -0.081086 -0.142488 0.496785 +v -0.081087 -0.142488 0.006877 +v -0.074132 -0.151386 0.496785 +v -0.074134 -0.151385 0.006877 +v -0.076614 -0.162480 0.496785 +v -0.076615 -0.162480 0.006877 +v 0.227539 -0.122683 0.380520 +v -0.017813 -0.122683 0.380521 +v -0.017813 -0.118941 0.388137 +v 0.227539 -0.118941 0.388137 +v -0.017813 -0.110532 0.390018 +v 0.227539 -0.110532 0.390018 +v -0.017813 -0.103789 0.384748 +v 0.227539 -0.103789 0.384748 +v -0.017813 -0.103789 0.376294 +v 0.227539 -0.103789 0.376294 +v -0.017813 -0.110532 0.371023 +v 0.227539 -0.110532 0.371023 +v -0.017813 -0.118941 0.372904 +v 0.227539 -0.118941 0.372904 +v 0.227539 -0.118107 0.387113 +v 0.227539 -0.121347 0.380520 +v 0.227539 -0.110830 0.388741 +v 0.227539 -0.104993 0.384179 +v 0.227539 -0.104993 0.376862 +v 0.227539 -0.110830 0.372300 +v 0.227539 -0.118108 0.373928 +v 0.161669 -0.118107 0.387113 +v 0.161669 -0.121347 0.380520 +v 0.161669 -0.110830 0.388741 +v 0.161669 -0.104993 0.384179 +v 0.161669 -0.104993 0.376862 +v 0.161669 -0.110830 0.372300 +v 0.161669 -0.118108 0.373928 +v 0.227539 0.102852 0.380521 +v -0.017813 0.102852 0.380521 +v -0.017813 0.106594 0.388137 +v 0.227539 0.106595 0.388137 +v -0.017813 0.115003 0.390018 +v 0.227539 0.115003 0.390018 +v -0.017813 0.121746 0.384748 +v 0.227539 0.121746 0.384748 +v -0.017813 0.121746 0.376294 +v 0.227539 0.121746 0.376294 +v -0.017813 0.115003 0.371023 +v 0.227539 0.115003 0.371023 +v -0.017813 0.106595 0.372904 +v 0.227539 0.106595 0.372904 +v 0.227539 0.107428 0.387113 +v 0.227539 0.104189 0.380521 +v 0.227539 0.114706 0.388741 +v 0.227539 0.120543 0.384179 +v 0.227539 0.120543 0.376862 +v 0.227539 0.114706 0.372300 +v 0.227539 0.107428 0.373928 +v 0.161669 0.107428 0.387113 +v 0.161669 0.104189 0.380521 +v 0.161669 0.114706 0.388741 +v 0.161669 0.120543 0.384179 +v 0.161669 0.120543 0.376862 +v 0.161669 0.114706 0.372300 +v 0.161669 0.107428 0.373928 +v -0.022725 0.143123 0.031635 +v -0.014049 0.143123 0.035898 +v -0.014050 -0.116008 0.035898 +v -0.022725 -0.116008 0.031635 +v -0.024867 0.143123 0.022058 +v -0.024868 -0.116008 0.022058 +v -0.018863 0.143123 0.014378 +v -0.018865 -0.116008 0.014378 +v -0.009235 0.143123 0.014378 +v -0.009235 -0.116008 0.014378 +v -0.003231 0.143123 0.022058 +v -0.003233 -0.116008 0.022058 +v -0.005374 0.143123 0.031635 +v -0.005375 -0.116008 0.031635 +v -0.021106 0.143123 0.030318 +v -0.014049 0.143123 0.033786 +v -0.022848 0.143123 0.022528 +v -0.017965 0.143123 0.016281 +v -0.010133 0.143123 0.016281 +v -0.005250 0.143123 0.022528 +v -0.006993 0.143123 0.030318 +v -0.021106 0.076724 0.030319 +v -0.014049 0.076724 0.033786 +v -0.022848 0.076724 0.022528 +v -0.017965 0.076724 0.016281 +v -0.010133 0.076724 0.016281 +v -0.005250 0.076724 0.022528 +v -0.006993 0.076724 0.030318 +v -0.025550 0.016009 0.034182 +v -0.014049 0.016009 0.039832 +v -0.014050 -0.016014 0.039832 +v -0.025550 -0.016014 0.034182 +v -0.028389 0.016009 0.021486 +v -0.028390 -0.016014 0.021486 +v -0.020430 0.016009 0.011305 +v -0.020433 -0.016014 0.011305 +v -0.007667 0.016009 0.011305 +v -0.007668 -0.016014 0.011305 +v 0.000291 0.016009 0.021486 +v 0.000289 -0.016014 0.021486 +v -0.002549 0.016009 0.034182 +v -0.002550 -0.016014 0.034182 +v -0.014050 -0.041929 0.031135 +v -0.018885 -0.041929 0.028760 +v -0.018884 0.041922 0.028760 +v -0.014049 0.041922 0.031135 +v -0.020079 -0.041929 0.023422 +v -0.020078 0.041922 0.023422 +v -0.016734 -0.041929 0.019142 +v -0.016732 0.041922 0.019142 +v -0.011367 -0.041929 0.019142 +v -0.011366 0.041922 0.019142 +v -0.008021 -0.041929 0.023422 +v -0.008020 0.041922 0.023422 +v -0.009215 -0.041929 0.028760 +v -0.009214 0.041922 0.028760 +v -0.024319 -0.112563 0.033183 +v -0.014049 -0.112563 0.038229 +v -0.014050 -0.171714 0.038229 +v -0.024320 -0.171714 0.033184 +v -0.026855 -0.112563 0.021845 +v -0.026856 -0.171714 0.021845 +v -0.019748 -0.112563 0.012753 +v -0.019750 -0.171714 0.012753 +v -0.008350 -0.112563 0.012753 +v -0.008351 -0.171714 0.012753 +v -0.001242 -0.112563 0.021845 +v -0.001244 -0.171714 0.021845 +v -0.003779 -0.112563 0.033183 +v -0.003780 -0.171714 0.033183 +v -0.022083 -0.112563 0.031364 +v -0.014049 -0.112563 0.035311 +v -0.024067 -0.112563 0.022495 +v -0.018507 -0.112563 0.015382 +v -0.009591 -0.112563 0.015382 +v -0.004031 -0.112563 0.022495 +v -0.006015 -0.112563 0.031364 +v -0.079024 -0.165367 0.033066 +v -0.079024 -0.155096 0.038112 +v 0.003172 -0.155097 0.038112 +v 0.003172 -0.165367 0.033066 +v -0.079024 -0.167903 0.021728 +v 0.003172 -0.167903 0.021728 +v -0.079024 -0.160795 0.012636 +v 0.003172 -0.160797 0.012636 +v -0.079024 -0.149396 0.012636 +v 0.003172 -0.149398 0.012636 +v -0.079024 -0.142290 0.021728 +v 0.003172 -0.142291 0.021728 +v -0.079024 -0.144826 0.033066 +v 0.003172 -0.144827 0.033066 +v 0.074090 0.075158 0.095806 +v 0.081932 0.075158 0.099659 +v 0.081931 -0.075043 0.099659 +v 0.074090 -0.075043 0.095807 +v 0.072154 0.075158 0.087150 +v 0.072154 -0.075043 0.087150 +v 0.077581 0.075158 0.080208 +v 0.077579 -0.075043 0.080209 +v 0.086283 0.075158 0.080208 +v 0.086282 -0.075043 0.080209 +v 0.091709 0.075158 0.087150 +v 0.091708 -0.075043 0.087150 +v 0.089772 0.075158 0.095806 +v 0.089771 -0.075043 0.095806 +v -0.199231 -0.005303 0.548466 +v -0.199231 -0.009694 0.541797 +v -0.205750 -0.009694 0.541797 +v -0.205750 -0.005303 0.548466 +v -0.199231 0.002754 0.549259 +v -0.205750 0.002754 0.549259 +v -0.199231 0.008409 0.543579 +v -0.205750 0.008409 0.543579 +v -0.199231 0.007406 0.535704 +v -0.205750 0.007406 0.535704 +v -0.199231 0.000498 0.531563 +v -0.205750 0.000498 0.531563 +v -0.199231 -0.007111 0.534274 +v -0.205750 -0.007112 0.534274 +v -0.211976 -0.018562 0.542883 +v -0.211977 -0.009965 0.555939 +v -0.211976 0.005808 0.557492 +v -0.211977 0.016880 0.546373 +v -0.211977 0.014915 0.530954 +v -0.211977 0.001392 0.522846 +v -0.211977 -0.013508 0.528155 +v -0.249508 -0.019066 0.542944 +v -0.249508 -0.010229 0.556364 +v -0.249508 0.005981 0.557960 +v -0.249508 0.017362 0.546532 +v -0.249508 0.015343 0.530684 +v -0.249508 0.001443 0.522351 +v -0.249508 -0.013871 0.527807 +v -0.249225 0.001450 0.518189 +v -0.249225 0.007462 0.518348 +v -0.253065 0.007462 0.513807 +v -0.253065 0.001450 0.513647 +v -0.196553 -0.055566 0.003134 +v -0.196553 0.056024 0.003134 +v -0.214527 0.056024 0.003134 +v -0.214527 -0.055566 0.003134 +v -0.160579 0.056024 0.501905 +v -0.160579 -0.055566 0.501905 +v -0.178553 -0.055566 0.501905 +v -0.178553 0.056024 0.501905 +v -0.179535 -0.166353 0.239298 +v -0.197509 -0.166353 0.239298 +v -0.195572 -0.166353 0.265736 +v -0.177598 -0.166353 0.265736 +v -0.195572 0.166811 0.265736 +v -0.197509 0.166811 0.239298 +v -0.179535 0.166811 0.239298 +v -0.177598 0.166811 0.265736 +v -0.171641 -0.175230 0.347205 +v -0.189615 -0.175230 0.347205 +v -0.179487 -0.175230 0.488958 +v -0.161513 -0.175230 0.488958 +v -0.203465 -0.175230 0.158000 +v -0.185491 -0.175230 0.158000 +v -0.195619 -0.175230 0.016081 +v -0.213593 -0.175230 0.016081 +v -0.179487 0.175689 0.488958 +v -0.189615 0.175689 0.347205 +v -0.171641 0.175689 0.347205 +v -0.161513 0.175689 0.488958 +v -0.195619 0.175688 0.016081 +v -0.185491 0.175689 0.158000 +v -0.203465 0.175689 0.158000 +v -0.213593 0.175688 0.016081 +v -0.172908 -0.166353 0.329754 +v -0.190882 -0.166353 0.329754 +v -0.202199 -0.166353 0.175280 +v -0.184225 -0.166353 0.175280 +v -0.190882 0.166811 0.329754 +v -0.172908 0.166811 0.329754 +v -0.184225 0.166811 0.175280 +v -0.202199 0.166811 0.175280 +v -0.214527 0.162707 0.003133 +v -0.196553 0.162707 0.003133 +v -0.196553 -0.162249 0.003134 +v -0.214527 -0.162249 0.003134 +v -0.178553 -0.162249 0.501905 +v -0.160579 -0.162249 0.501905 +v -0.160579 0.162708 0.501905 +v -0.178553 0.162708 0.501905 +v -0.196553 -0.054465 0.008057 +v -0.196553 0.054922 0.008058 +v -0.214527 0.054922 0.008058 +v -0.214527 -0.054465 0.008057 +v -0.160579 0.054923 0.496981 +v -0.160579 -0.054464 0.496981 +v -0.178553 -0.054464 0.496981 +v -0.178553 0.054923 0.496981 +v -0.185491 -0.171766 0.158017 +v -0.195619 -0.171766 0.020749 +v -0.189615 -0.171766 0.347189 +v -0.179487 -0.171766 0.484290 +v -0.203465 0.172224 0.158017 +v -0.213593 0.172224 0.020749 +v -0.171641 0.172224 0.347189 +v -0.161513 0.172224 0.484290 +v -0.184225 -0.163063 0.175297 +v -0.161513 -0.171766 0.484290 +v -0.171641 -0.171766 0.347189 +v -0.190882 -0.163063 0.329743 +v -0.213593 -0.171766 0.020749 +v -0.203465 -0.171766 0.158017 +v -0.202199 0.163522 0.175297 +v -0.179487 0.172224 0.484290 +v -0.189615 0.172224 0.347189 +v -0.172908 0.163522 0.329743 +v -0.195619 0.172224 0.020749 +v -0.185491 0.172224 0.158017 +v -0.177598 -0.163063 0.265737 +v -0.179535 -0.163064 0.239303 +v -0.172908 -0.163064 0.329743 +v -0.197509 -0.163063 0.239303 +v -0.195572 -0.163064 0.265737 +v -0.202199 -0.163063 0.175297 +v -0.195572 0.163522 0.265737 +v -0.197509 0.163522 0.239303 +v -0.190882 0.163522 0.329743 +v -0.179535 0.163522 0.239303 +v -0.177598 0.163522 0.265737 +v -0.184225 0.163522 0.175297 +v -0.214527 0.159499 0.008058 +v -0.196553 0.159499 0.008058 +v -0.196553 -0.159041 0.008058 +v -0.214527 -0.159041 0.008058 +v -0.178553 -0.159041 0.496981 +v -0.160579 -0.159041 0.496981 +v -0.160579 0.159499 0.496981 +v -0.178553 0.159500 0.496981 +v -0.113505 -0.054464 0.008057 +v -0.113505 0.054922 0.008058 +v -0.113491 0.054923 0.496981 +v -0.113491 -0.054464 0.496981 +v -0.113501 -0.171766 0.154062 +v -0.113505 -0.171766 0.020749 +v -0.113495 0.172224 0.351177 +v -0.113491 0.172224 0.484290 +v -0.113500 -0.163064 0.171342 +v -0.113491 -0.171766 0.484290 +v -0.113495 -0.171766 0.351177 +v -0.113496 0.163522 0.333731 +v -0.113505 0.172224 0.020749 +v -0.113501 0.172224 0.154062 +v -0.113498 -0.163064 0.266433 +v -0.113498 -0.163063 0.238640 +v -0.113496 -0.163063 0.333731 +v -0.113498 0.163522 0.238640 +v -0.113497 0.163522 0.266433 +v -0.113500 0.163522 0.171342 +v -0.113505 0.159499 0.008057 +v -0.113505 -0.159041 0.008058 +v -0.113491 -0.159041 0.496981 +v -0.113491 0.159500 0.496981 +v -0.105783 -0.053338 0.011853 +v -0.105783 0.053796 0.011853 +v -0.105768 0.053796 0.493186 +v -0.105768 -0.053337 0.493186 +v -0.105778 -0.168222 0.154075 +v -0.105782 -0.168222 0.024347 +v -0.105773 0.168680 0.349164 +v -0.105769 0.168680 0.480691 +v -0.105778 -0.159699 0.171356 +v -0.105769 -0.168222 0.480691 +v -0.105773 -0.168222 0.351164 +v -0.105773 0.160157 0.333722 +v -0.105782 0.168680 0.024347 +v -0.105778 0.168680 0.154075 +v -0.105775 -0.159699 0.266433 +v -0.105776 -0.159699 0.238644 +v -0.105773 -0.159699 0.333722 +v -0.105776 0.160157 0.238644 +v -0.105775 0.160157 0.266433 +v -0.105778 0.160157 0.171356 +v -0.105783 0.156218 0.011853 +v -0.105783 -0.155759 0.011853 +v -0.105768 -0.155759 0.493186 +v -0.105768 0.156218 0.493186 +v -0.099281 -0.050257 0.267000 +v -0.099281 0.050715 0.267068 +v -0.099282 0.050716 0.238214 +v -0.099282 -0.050257 0.238165 +v -0.099288 -0.051498 0.024761 +v -0.099288 0.051956 0.024761 +v -0.099288 0.150861 0.024761 +v -0.099288 0.155772 0.029684 +v -0.099284 0.155772 0.151065 +v -0.099284 0.147249 0.168345 +v -0.099282 0.147249 0.238260 +v -0.099281 0.147249 0.267134 +v -0.099279 0.147249 0.337048 +v -0.099278 0.155772 0.352490 +v -0.099275 0.155772 0.475354 +v -0.099274 0.150861 0.480278 +v -0.099274 0.051956 0.480278 +v -0.099274 -0.051498 0.480278 +v -0.099274 -0.150403 0.480278 +v -0.099275 -0.155314 0.475354 +v -0.099278 -0.155314 0.354149 +v -0.099279 -0.146790 0.336707 +v -0.099281 -0.146790 0.266934 +v -0.099282 -0.146790 0.238119 +v -0.099284 -0.146790 0.168345 +v -0.099284 -0.155314 0.151064 +v -0.099288 -0.155314 0.029684 +v -0.099288 -0.150403 0.024761 +v -0.272399 0.054922 0.008058 +v -0.272399 -0.054465 0.008057 +v -0.272395 -0.054464 0.496981 +v -0.272395 0.054923 0.496981 +v -0.272396 -0.171766 0.347189 +v -0.272395 -0.171766 0.484290 +v -0.272398 0.172224 0.158017 +v -0.272399 0.172224 0.020749 +v -0.272396 -0.163063 0.329743 +v -0.272399 -0.171766 0.020749 +v -0.272398 -0.171766 0.158017 +v -0.272398 0.163522 0.175297 +v -0.272395 0.172224 0.484290 +v -0.272396 0.172224 0.347189 +v -0.272397 -0.163063 0.239303 +v -0.272397 -0.163063 0.265737 +v -0.272398 -0.163063 0.175297 +v -0.272397 0.163522 0.265737 +v -0.272397 0.163522 0.239303 +v -0.272396 0.163522 0.329743 +v -0.272399 0.159500 0.008057 +v -0.272399 -0.159042 0.008058 +v -0.272395 -0.159041 0.496981 +v -0.272395 0.159500 0.496981 +v -0.281610 0.053968 0.013938 +v -0.281610 -0.053510 0.013938 +v -0.281606 -0.053510 0.491101 +v -0.281606 0.053968 0.491101 +v -0.281608 -0.168764 0.347189 +v -0.281606 -0.168764 0.478715 +v -0.281609 0.169223 0.158017 +v -0.281610 0.169222 0.026324 +v -0.281608 -0.160213 0.329743 +v -0.281610 -0.168765 0.026324 +v -0.281609 -0.168764 0.158017 +v -0.281609 0.160672 0.175297 +v -0.281606 0.169223 0.478715 +v -0.281608 0.169223 0.347189 +v -0.281608 -0.160213 0.239303 +v -0.281608 -0.160213 0.265737 +v -0.281609 -0.160213 0.175297 +v -0.281608 0.160672 0.265737 +v -0.281608 0.160672 0.239303 +v -0.281608 0.160672 0.329743 +v -0.281610 0.156720 0.013938 +v -0.281610 -0.156262 0.013938 +v -0.281606 -0.156262 0.491101 +v -0.281606 0.156720 0.491101 +v -0.288252 0.052951 0.021176 +v -0.287784 -0.052472 0.021176 +v -0.287930 -0.153283 0.021176 +v -0.287930 -0.161526 0.029342 +v -0.290426 -0.161526 0.156324 +v -0.290426 -0.152975 0.173604 +v -0.290425 -0.152975 0.239008 +v -0.290425 -0.152975 0.266018 +v -0.290424 -0.152975 0.331421 +v -0.290424 -0.161526 0.348867 +v -0.287926 -0.161526 0.475696 +v -0.287926 -0.153283 0.483862 +v -0.287926 -0.052487 0.483862 +v -0.287938 0.052823 0.483862 +v -0.287926 0.153741 0.483862 +v -0.287926 0.161984 0.475696 +v -0.290424 0.161984 0.348867 +v -0.290424 0.153433 0.331421 +v -0.290425 0.153433 0.266018 +v -0.290425 0.153433 0.239008 +v -0.290426 0.153433 0.173604 +v -0.290426 0.161984 0.156324 +v -0.287930 0.161984 0.029342 +v -0.287930 0.153741 0.021176 +v -0.099278 0.051198 0.350018 +v -0.306110 -0.065390 0.348867 +v -0.306110 -0.054249 0.331421 +v -0.306110 0.054645 0.331421 +v -0.306110 0.066924 0.348867 +v -0.291011 0.052622 0.475696 +v -0.291011 -0.051606 0.475696 +v -0.306112 0.056397 0.173604 +v -0.306111 0.069404 0.156324 +v -0.291015 0.052506 0.029342 +v -0.287954 0.052553 0.024625 +v -0.291015 -0.051388 0.029342 +v -0.287956 -0.051416 0.025193 +v -0.306111 -0.068717 0.156324 +v -0.306112 -0.056143 0.173604 +v -0.310627 -0.034268 0.223455 +v -0.310627 -0.034268 0.238987 +v -0.310627 0.034692 0.281570 +v -0.310627 0.034692 0.266039 +v -0.310627 -0.034268 0.266039 +v -0.310627 -0.034268 0.281570 +v -0.310627 0.034692 0.238987 +v -0.310627 0.034692 0.223455 +v -0.310666 0.012459 0.281570 +v -0.310666 -0.012475 0.223455 +v -0.310666 -0.012049 0.281570 +v -0.310666 0.012853 0.223455 +v -0.310666 0.012748 0.238999 +v 0.084499 -0.068806 0.355635 +v 0.097241 -0.068806 0.386395 +v 0.132043 -0.068806 0.351593 +v 0.101282 -0.068806 0.338852 +v 0.060764 -0.068806 0.355635 +v 0.048023 -0.068806 0.386395 +v 0.043981 -0.068806 0.338852 +v 0.013221 -0.068806 0.351593 +v 0.043981 -0.068806 0.315116 +v 0.013221 -0.068806 0.302375 +v 0.060764 -0.068806 0.298333 +v 0.048023 -0.068806 0.267572 +v 0.084499 -0.068806 0.298333 +v 0.097241 -0.068806 0.267572 +v 0.101282 -0.068806 0.315116 +v 0.132043 -0.068806 0.302375 +v 0.021863 -0.008387 0.367151 +v 0.032623 -0.008387 0.378218 +v 0.031822 -0.008756 0.276061 +v 0.021254 -0.008756 0.287368 +v 0.023075 -0.008387 0.386069 +v 0.044795 -0.063699 0.388334 +v 0.009993 -0.063699 0.353532 +v 0.012315 -0.008387 0.375003 +v 0.012194 -0.048697 0.292081 +v 0.012224 -0.008756 0.278443 +v 0.040972 -0.052626 0.267985 +v 0.022792 -0.008756 0.267136 +v 0.132043 -0.064146 0.351593 +v 0.097241 -0.064146 0.386395 +v 0.084499 -0.064146 0.355635 +v 0.101282 -0.064146 0.338851 +v 0.050079 -0.064731 0.385455 +v 0.060764 -0.064146 0.355635 +v 0.014412 -0.064927 0.349302 +v 0.043981 -0.064146 0.338851 +v 0.014635 -0.064740 0.304159 +v 0.043981 -0.064146 0.315116 +v 0.049691 -0.064640 0.268830 +v 0.060764 -0.064146 0.298333 +v 0.097241 -0.064146 0.267572 +v 0.084499 -0.064146 0.298333 +v 0.132043 -0.064146 0.302375 +v 0.101282 -0.064146 0.315116 +v 0.036107 -0.005292 0.378182 +v 0.022351 -0.005240 0.363748 +v 0.021576 -0.005674 0.290849 +v 0.035289 -0.005649 0.276249 +v 0.048603 -0.062115 0.390503 +v 0.024679 -0.004451 0.387981 +v 0.010649 -0.004535 0.372977 +v 0.009114 -0.062428 0.349135 +v 0.010652 -0.047428 0.296292 +v 0.010535 -0.004826 0.280293 +v 0.024587 -0.004858 0.265320 +v 0.043600 -0.051406 0.264335 +v -0.086315 0.102520 0.067024 +v -0.086315 0.093259 0.053627 +v -0.086315 -0.093584 0.053627 +v -0.086315 -0.102845 0.067024 +v -0.100829 -0.093584 0.053417 +v -0.100829 -0.102845 0.066814 +v -0.100829 0.102520 0.066814 +v -0.100829 0.093259 0.053417 +v -0.086315 0.066731 0.044962 +v -0.086315 -0.067056 0.044962 +v -0.100829 -0.067056 0.044752 +v -0.100829 0.066731 0.044752 +v 0.049475 -0.139929 0.735347 +v 0.041876 -0.144932 0.723173 +v 0.041118 -0.164469 0.732446 +v 0.047960 -0.159965 0.743406 +v 0.026678 -0.144932 0.723173 +v 0.027436 -0.164469 0.732446 +v 0.019079 -0.139929 0.735347 +v 0.020595 -0.159965 0.743406 +v 0.026678 -0.134926 0.747521 +v 0.027436 -0.155461 0.754366 +v 0.041876 -0.134926 0.747521 +v 0.041118 -0.155461 0.754366 +v 0.055983 -0.139929 0.735347 +v 0.045130 -0.147013 0.717936 +v 0.023424 -0.147013 0.717936 +v 0.012572 -0.139929 0.735347 +v 0.023424 -0.132845 0.752758 +v 0.045130 -0.132845 0.752758 +v 0.057528 -0.129811 0.731272 +v 0.045902 -0.137400 0.712621 +v 0.022651 -0.137400 0.712621 +v 0.011026 -0.129811 0.731272 +v 0.022651 -0.122224 0.749922 +v 0.045902 -0.122224 0.749922 +v 0.049475 0.140267 0.735595 +v 0.047960 0.160303 0.743654 +v 0.041118 0.164807 0.732694 +v 0.041876 0.145270 0.723421 +v 0.027436 0.164807 0.732694 +v 0.026678 0.145270 0.723421 +v 0.020595 0.160302 0.743654 +v 0.019079 0.140267 0.735595 +v 0.027436 0.155799 0.754614 +v 0.026678 0.135264 0.747769 +v 0.041118 0.155799 0.754614 +v 0.041876 0.135264 0.747769 +v -0.272569 0.103514 0.643895 +v -0.272569 0.103514 0.657225 +v -0.272569 -0.134404 0.657225 +v -0.272569 -0.134404 0.643895 +v -0.272569 -0.109274 0.682844 +v -0.272569 0.078437 0.682844 +v -0.270479 -0.134404 0.657225 +v -0.270479 0.103514 0.657225 +v -0.270479 0.103514 0.643895 +v -0.270479 -0.134404 0.643895 +v -0.270479 -0.109274 0.682844 +v -0.270479 0.078437 0.682844 +v -0.132144 0.145228 0.576893 +v -0.132144 0.145228 0.554607 +v -0.041823 0.145228 0.554607 +v -0.041823 0.145228 0.576893 +v -0.041823 -0.142156 0.554607 +v -0.132144 -0.142156 0.554607 +v -0.041823 -0.142156 0.576849 +v -0.132144 -0.142156 0.576849 +v -0.041823 0.142781 0.557053 +v -0.132144 0.142781 0.557053 +v -0.132144 0.141768 0.576893 +v -0.041823 0.141768 0.576893 +v -0.041823 -0.139710 0.557053 +v -0.132144 -0.139710 0.557053 +v -0.041823 -0.138697 0.576849 +v -0.132144 -0.138696 0.576849 +v 0.263085 0.118772 0.643912 +v 0.275061 0.118772 0.631936 +v 0.275061 0.102546 0.631936 +v 0.263085 0.102546 0.643912 +v 0.275061 0.118772 0.614999 +v 0.263085 0.118772 0.603023 +v 0.263085 0.102546 0.603023 +v 0.275061 0.102546 0.614999 +v 0.280883 -0.118863 0.643784 +v 0.280883 -0.152561 0.643784 +v 0.275598 -0.152562 0.649686 +v 0.275598 -0.118863 0.649686 +v 0.233747 -0.152561 0.649686 +v 0.233747 -0.118863 0.649686 +v 0.228049 -0.152561 0.643784 +v 0.228049 -0.118863 0.643784 +v 0.213577 -0.119005 0.638532 +v 0.213577 -0.149485 0.638532 +v 0.213577 -0.149485 0.607701 +v 0.213577 -0.119005 0.607701 +v 0.228049 -0.118863 0.602449 +v 0.228049 -0.152561 0.602449 +v 0.232471 -0.152561 0.598305 +v 0.232471 -0.118863 0.598305 +v 0.276461 -0.152561 0.598305 +v 0.276461 -0.118863 0.598305 +v 0.280883 -0.152561 0.602449 +v 0.280883 -0.118863 0.602449 +v 0.072632 -0.041487 0.268759 +v 0.028964 -0.044226 0.283315 +v 0.040286 -0.064905 0.294636 +v 0.072632 -0.074036 0.283315 +v 0.104979 -0.064905 0.294636 +v 0.116300 -0.041487 0.283315 +v 0.072632 -0.041487 0.385206 +v 0.072632 -0.074036 0.370650 +v 0.040286 -0.064905 0.359329 +v 0.028964 -0.044226 0.370650 +v 0.116300 -0.041487 0.370650 +v 0.104979 -0.064905 0.359329 +v 0.072632 -0.093342 0.326982 +v 0.072632 -0.093345 0.309482 +v 0.061270 -0.093326 0.315621 +v 0.055131 -0.093345 0.326982 +v 0.090133 -0.093345 0.326982 +v 0.083993 -0.093326 0.315621 +v 0.072632 -0.093345 0.344483 +v 0.083993 -0.093326 0.338344 +v 0.061270 -0.093326 0.338344 +v 0.130856 -0.041487 0.326982 +v 0.116300 -0.074036 0.326982 +v 0.028964 -0.074036 0.326982 +v 0.014408 -0.044226 0.326982 +v 0.072632 0.072347 0.283315 +v 0.040286 0.063216 0.294636 +v 0.028964 0.042407 0.283315 +v 0.072632 0.042407 0.268759 +v 0.116300 0.042407 0.283315 +v 0.104979 0.063216 0.294636 +v 0.072632 0.042407 0.385206 +v 0.072632 0.072347 0.370650 +v 0.104979 0.063216 0.359329 +v 0.116300 0.042407 0.370650 +v 0.028964 0.042407 0.370650 +v 0.040286 0.063216 0.359329 +v 0.116300 0.072347 0.326982 +v 0.130856 0.042407 0.326982 +v 0.072632 0.084088 0.326982 +v 0.028964 0.072347 0.326982 +v 0.014408 0.042407 0.326982 +v 0.058852 -0.083154 0.313203 +v 0.072632 -0.084081 0.305757 +v 0.086412 -0.083154 0.313203 +v 0.093858 -0.084081 0.326982 +v 0.086412 -0.083154 0.340762 +v 0.072632 -0.084081 0.348208 +v 0.058852 -0.083154 0.340762 +v 0.051407 -0.084081 0.326982 +v 0.057663 0.116821 0.622486 +v 0.057663 -0.023463 0.622486 +v 0.040486 -0.023463 0.663955 +v 0.040486 0.116821 0.663955 +v -0.000983 -0.023463 0.681133 +v -0.000983 0.116821 0.681132 +v -0.042452 -0.023463 0.663955 +v -0.042452 0.116821 0.663955 +v -0.059629 -0.023463 0.622486 +v -0.059629 0.116821 0.622486 +v -0.042452 -0.023463 0.581017 +v -0.042452 0.116821 0.581017 +v -0.000983 -0.023463 0.563840 +v -0.000983 0.116821 0.563840 +v 0.040486 -0.023463 0.581017 +v 0.040486 0.116821 0.581017 +v 0.066440 -0.037911 0.622486 +v 0.046692 -0.037911 0.670161 +v -0.000983 -0.037911 0.689909 +v -0.048658 -0.037911 0.670161 +v -0.068406 -0.037911 0.622486 +v -0.048658 -0.037910 0.574811 +v -0.000983 -0.037910 0.555063 +v 0.046692 -0.037910 0.574811 +v 0.066440 -0.046038 0.622486 +v 0.046692 -0.046038 0.670161 +v -0.000983 -0.046038 0.689909 +v -0.048658 -0.046038 0.670161 +v -0.068406 -0.046038 0.622486 +v -0.048658 -0.046037 0.574811 +v -0.000983 -0.046037 0.555063 +v 0.046692 -0.046037 0.574811 +v 0.057339 -0.059261 0.622486 +v 0.040257 -0.059261 0.663726 +v -0.000983 -0.059261 0.680808 +v -0.042223 -0.059261 0.663726 +v -0.059304 -0.059261 0.622486 +v -0.042223 -0.059261 0.581247 +v -0.000983 -0.059261 0.564165 +v 0.040257 -0.059261 0.581247 +v 0.057339 -0.117883 0.622486 +v 0.040257 -0.117883 0.663726 +v -0.000983 -0.117883 0.680808 +v -0.042223 -0.117883 0.663726 +v -0.059304 -0.117883 0.622486 +v -0.042223 -0.117883 0.581247 +v -0.000983 -0.117883 0.564165 +v 0.040257 -0.117883 0.581247 +v 0.034295 0.048997 0.704593 +v 0.034295 -0.116433 0.704594 +v 0.052038 -0.116433 0.716897 +v 0.052038 0.048997 0.716897 +v 0.018607 -0.116433 0.758164 +v 0.000864 -0.116433 0.745861 +v 0.000864 0.048997 0.745861 +v 0.018607 0.048997 0.758164 +v 0.052038 0.113331 0.716896 +v 0.018607 0.113331 0.758164 +v 0.000864 0.113331 0.745861 +v 0.034295 0.113331 0.704593 +v 0.068196 0.048997 0.728953 +v 0.068196 0.113331 0.728953 +v 0.034765 0.113331 0.770221 +v 0.034765 0.048997 0.770221 +v 0.070388 -0.079316 0.153054 +v -0.053478 -0.079316 0.153054 +v -0.053478 -0.056167 0.208939 +v 0.070388 -0.056167 0.208939 +v -0.053478 -0.000281 0.232088 +v 0.070388 -0.000281 0.232088 +v -0.053478 0.055605 0.208939 +v 0.070388 0.055605 0.208939 +v -0.053478 0.078754 0.153054 +v 0.070388 0.078754 0.153054 +v -0.053478 0.055605 0.097168 +v 0.070388 0.055605 0.097168 +v -0.053478 -0.000281 0.074019 +v 0.070388 -0.000281 0.074019 +v -0.053478 -0.056167 0.097168 +v 0.070388 -0.056167 0.097168 +v 0.168199 -0.032409 0.139321 +v 0.077862 -0.032409 0.139321 +v 0.077862 -0.032409 0.187271 +v 0.168199 -0.032409 0.187271 +v 0.077862 -0.008164 0.200137 +v 0.168199 -0.008164 0.200137 +v 0.077862 0.007601 0.200137 +v 0.168199 0.007601 0.200137 +v 0.077862 0.031847 0.187271 +v 0.168199 0.031847 0.187271 +v 0.077862 0.031847 0.139321 +v 0.168199 0.031847 0.139321 +v 0.077862 0.007601 0.126455 +v 0.168199 0.007601 0.126455 +v 0.077862 -0.008164 0.126455 +v 0.168199 -0.008164 0.126455 +v 0.274144 -0.118863 0.654226 +v 0.286462 -0.118863 0.641651 +v 0.241805 -0.118863 0.659209 +v 0.222535 -0.118863 0.659696 +v 0.222536 -0.118863 0.587388 +v 0.254625 -0.118863 0.588890 +v 0.277234 -0.118863 0.593954 +v 0.286645 -0.118863 0.607658 +v 0.274144 -0.102694 0.654226 +v 0.286462 -0.102694 0.641651 +v 0.241805 -0.102694 0.659209 +v 0.222535 -0.102694 0.659696 +v 0.222536 -0.102694 0.587388 +v 0.254625 -0.102694 0.588890 +v 0.277234 -0.102694 0.593954 +v 0.286645 -0.102694 0.607658 +v 0.228049 -0.149485 0.638532 +v 0.228049 -0.119005 0.638532 +v 0.228049 -0.119005 0.607701 +v 0.228049 -0.149485 0.607701 +v 0.275061 0.093689 0.631936 +v 0.264476 0.093689 0.627552 +v 0.258701 0.093689 0.633327 +v 0.263085 0.093689 0.643912 +v 0.250533 0.093689 0.633327 +v 0.246149 0.093689 0.643912 +v 0.244757 0.093689 0.627552 +v 0.234172 0.093689 0.631936 +v 0.244757 0.093689 0.619384 +v 0.234172 0.093689 0.614999 +v 0.250533 0.093689 0.613608 +v 0.246149 0.093689 0.603023 +v 0.258701 0.093689 0.613608 +v 0.263085 0.093689 0.603023 +v 0.264476 0.093689 0.619384 +v 0.275061 0.093689 0.614999 +v 0.264476 0.103476 0.627552 +v 0.258701 0.103476 0.633327 +v 0.250533 0.103476 0.633327 +v 0.244757 0.103476 0.627551 +v 0.244757 0.103476 0.619384 +v 0.250533 0.103476 0.613608 +v 0.258701 0.103476 0.613608 +v 0.264476 0.103476 0.619384 +v 0.268656 0.103476 0.629283 +v 0.260432 0.103476 0.637507 +v 0.248802 0.103476 0.637507 +v 0.240578 0.103476 0.629283 +v 0.240578 0.103476 0.617652 +v 0.248802 0.103476 0.609428 +v 0.260432 0.103476 0.609428 +v 0.268656 0.103476 0.617652 +v 0.270965 0.119017 0.630239 +v 0.261389 0.119017 0.639816 +v 0.247845 0.119017 0.639816 +v 0.238269 0.119017 0.630239 +v 0.238269 0.119017 0.616696 +v 0.247845 0.119017 0.607119 +v 0.261389 0.119017 0.607119 +v 0.270965 0.119017 0.616696 +v 0.246149 0.118772 0.643912 +v 0.234172 0.118772 0.631936 +v 0.234172 0.118772 0.614999 +v 0.246149 0.118772 0.603023 +v 0.246149 0.102546 0.643912 +v 0.234172 0.102546 0.631936 +v 0.234172 0.102546 0.614999 +v 0.246149 0.102546 0.603023 +v 0.227750 0.105970 0.659783 +v 0.227750 0.118772 0.659783 +v 0.222535 0.118771 0.659786 +v 0.222535 0.105969 0.659786 +v 0.222536 0.118771 0.637154 +v 0.222536 0.105969 0.637154 +v 0.222536 0.118771 0.609693 +v 0.222536 0.105969 0.609693 +v 0.222536 0.118771 0.587477 +v 0.222536 0.105969 0.587477 +v 0.228753 0.118771 0.587680 +v 0.228753 0.105969 0.587680 +v 0.024113 0.033811 0.392433 +v 0.024113 -0.033307 0.392433 +v 0.233832 -0.033307 0.392433 +v 0.233832 0.033811 0.392433 +v 0.233832 0.033811 0.504209 +v 0.233832 -0.033307 0.504209 +v 0.024113 -0.033307 0.504209 +v 0.024113 0.033811 0.504209 +v 0.061036 -0.100425 0.392433 +v 0.061036 -0.100424 0.504209 +v 0.233832 -0.100424 0.504209 +v 0.233832 -0.100425 0.392433 +v 0.233832 0.100928 0.392433 +v 0.233832 0.100928 0.504209 +v 0.061036 0.100928 0.504209 +v 0.061036 0.100928 0.392433 +v 0.074921 -0.119377 0.086435 +v 0.074921 -0.119377 0.204982 +v 0.062457 -0.097788 0.204982 +v 0.062457 -0.097788 0.086435 +v 0.037528 -0.097788 0.204982 +v 0.037528 -0.097788 0.086435 +v 0.025064 -0.119377 0.204982 +v 0.025064 -0.119377 0.086435 +v 0.037528 -0.140966 0.204982 +v 0.037528 -0.140966 0.086435 +v 0.062457 -0.140966 0.204982 +v 0.062457 -0.140966 0.086435 +v 0.054017 -0.126347 0.272512 +v 0.045969 -0.126347 0.272512 +v 0.041944 -0.119377 0.272512 +v 0.054017 -0.112407 0.272512 +v 0.045969 -0.112407 0.272512 +v 0.058041 -0.119377 0.272512 +v 0.061311 -0.119377 0.204982 +v 0.055652 -0.109575 0.204982 +v 0.044333 -0.109575 0.204982 +v 0.038674 -0.119377 0.204982 +v 0.044333 -0.129179 0.204982 +v 0.055652 -0.129179 0.204982 +v 0.061311 -0.119377 0.220247 +v 0.055652 -0.109575 0.220247 +v 0.044333 -0.109575 0.220247 +v 0.038674 -0.119377 0.220247 +v 0.044333 -0.129179 0.220247 +v 0.055652 -0.129179 0.220247 +v 0.058041 -0.119377 0.223729 +v 0.054017 -0.112407 0.223729 +v 0.045969 -0.112407 0.223729 +v 0.041944 -0.119377 0.223729 +v 0.045969 -0.126347 0.223729 +v 0.054017 -0.126347 0.223729 +v 0.125232 -0.126130 0.307679 +v 0.093193 -0.126130 0.307679 +v 0.087599 -0.111677 0.307679 +v 0.125232 -0.097225 0.307679 +v 0.093193 -0.097225 0.307679 +v 0.130827 -0.111677 0.307679 +v 0.125232 -0.097225 0.222834 +v 0.130827 -0.111677 0.222834 +v 0.093193 -0.097225 0.222834 +v 0.087599 -0.111677 0.222834 +v 0.093193 -0.126130 0.222834 +v 0.125232 -0.126130 0.222834 +v 0.045983 -0.163478 0.684961 +v 0.051636 -0.119039 0.792339 +v 0.072029 -0.119705 0.791474 +v 0.072029 -0.163478 0.685171 +v -0.077256 -0.163478 0.685624 +v -0.079694 -0.162891 0.685669 +v -0.089845 -0.156107 0.686149 +v 0.045666 -0.112332 0.792713 +v -0.089845 -0.063070 0.686149 +v 0.045666 -0.029058 0.792713 +v 0.050633 -0.112332 0.796889 +v 0.050633 -0.029058 0.796889 +v 0.039626 -0.112332 0.811325 +v 0.039626 -0.029058 0.811325 +v 0.045666 0.028728 0.792713 +v -0.089845 0.033171 0.686149 +v 0.050633 0.028728 0.796889 +v 0.039626 0.028728 0.811325 +v -0.101391 -0.063070 0.686149 +v -0.094011 -0.156107 0.686149 +v -0.109927 -0.156107 0.686149 +v -0.109927 -0.070366 0.686149 +v -0.109927 -0.156107 0.693597 +v -0.109927 -0.070366 0.693598 +v -0.094011 -0.162251 0.686149 +v -0.109927 -0.162251 0.686149 +v -0.109927 -0.162251 0.693597 +v -0.026014 0.096918 0.256709 +v -0.047621 0.096918 0.256709 +v -0.047621 -0.097242 0.256709 +v -0.026014 -0.097242 0.256709 +v -0.026014 0.096918 0.364696 +v -0.026014 -0.097242 0.364696 +v -0.047621 -0.097242 0.364696 +v -0.047621 0.096918 0.364696 +v -0.047621 -0.139179 0.066557 +v -0.047621 0.138854 0.066557 +v -0.047621 0.138855 0.365534 +v -0.047621 -0.139179 0.365534 +v -0.100829 -0.139179 0.066347 +v -0.100829 0.138854 0.066347 +v -0.100829 0.138855 0.365323 +v -0.100829 -0.139179 0.365323 +v 0.092505 0.068521 0.039938 +v 0.092505 0.068521 0.123622 +v 0.092505 -0.068346 0.123622 +v 0.092505 -0.068346 0.039938 +v 0.120965 -0.068346 0.039938 +v 0.120965 -0.068346 0.123622 +v 0.120965 0.068521 0.123622 +v 0.120965 0.068521 0.039938 +v 0.045983 0.163149 0.684961 +v 0.072029 0.163149 0.685171 +v 0.072029 0.119374 0.791474 +v 0.051636 0.118709 0.792338 +v -0.079694 0.162561 0.685669 +v -0.077256 0.163149 0.685624 +v -0.089845 0.155777 0.686149 +v 0.045666 0.112003 0.792713 +v 0.050633 0.112003 0.796889 +v 0.039626 0.112002 0.811325 +v -0.101391 0.033171 0.686149 +v -0.094011 0.155777 0.686149 +v -0.109927 0.155777 0.686149 +v -0.109927 0.042840 0.686149 +v -0.109927 0.155777 0.693597 +v -0.109927 0.042840 0.693597 +v -0.094011 0.161921 0.686149 +v -0.109927 0.161921 0.686149 +v -0.109927 0.161921 0.693597 +v 0.072063 -0.117173 0.790425 +v 0.052121 -0.116810 0.790821 +v 0.045986 -0.160946 0.683915 +v 0.072037 -0.160945 0.684128 +v -0.076872 -0.161170 0.684199 +v -0.078818 -0.161052 0.683835 +v 0.047267 -0.111881 0.790536 +v -0.088927 -0.155622 0.683613 +v 0.047395 -0.029058 0.790588 +v -0.088949 -0.063070 0.683560 +v 0.053356 -0.112332 0.796588 +v 0.053356 -0.029058 0.796588 +v 0.041805 -0.112332 0.812986 +v 0.041805 -0.029058 0.812986 +v 0.047395 0.028728 0.790588 +v -0.088949 0.033171 0.683560 +v 0.053356 0.028728 0.796588 +v 0.041805 0.028728 0.812986 +v -0.101391 -0.063070 0.683409 +v -0.094011 -0.156107 0.683409 +v -0.111865 -0.070366 0.684211 +v -0.111865 -0.156107 0.684211 +v -0.112667 -0.070366 0.693598 +v -0.112667 -0.156107 0.693597 +v -0.111865 -0.162251 0.684211 +v -0.094011 -0.162251 0.683409 +v -0.112667 -0.162251 0.693597 +v -0.050224 -0.096291 0.363859 +v -0.050224 0.096216 0.363859 +v -0.049325 0.137398 0.363937 +v -0.049325 -0.137473 0.363937 +v 0.093957 -0.066889 0.122039 +v 0.093957 0.066814 0.122039 +v 0.093957 0.066814 0.041520 +v 0.093957 -0.066889 0.041520 +v 0.119253 -0.066889 0.041520 +v 0.119253 -0.066889 0.122039 +v 0.119253 0.066814 0.122039 +v 0.119253 0.066814 0.041520 +v 0.072063 0.116843 0.790425 +v 0.072037 0.160615 0.684128 +v 0.045986 0.160616 0.683915 +v 0.052121 0.116480 0.790821 +v -0.076872 0.160840 0.684199 +v -0.078818 0.160722 0.683835 +v -0.088927 0.155292 0.683613 +v 0.047267 0.111551 0.790536 +v 0.053356 0.112003 0.796588 +v 0.041805 0.112002 0.812986 +v -0.101391 0.033171 0.683409 +v -0.094011 0.155777 0.683409 +v -0.111865 0.155777 0.684211 +v -0.111865 0.042840 0.684211 +v -0.112667 0.155777 0.693597 +v -0.112667 0.042840 0.693597 +v -0.094011 0.161921 0.683409 +v -0.111864 0.161921 0.684211 +v -0.112667 0.161921 0.693597 +v -0.089568 0.103639 0.643895 +v -0.089568 0.103639 0.657225 +v -0.089568 -0.134279 0.657225 +v -0.089568 -0.134279 0.643895 +v -0.089568 -0.109149 0.682844 +v -0.089568 0.078562 0.682844 +v -0.087478 -0.134279 0.657225 +v -0.087478 0.103639 0.657225 +v -0.087478 0.103639 0.643895 +v -0.087478 -0.134279 0.643895 +v -0.087478 -0.109149 0.682844 +v -0.087478 0.078562 0.682844 +v -0.018973 -0.078431 0.073318 +v -0.018973 -0.078431 0.231654 +v -0.018973 0.078357 0.231654 +v -0.018973 0.078357 0.073318 +v -0.024980 0.078357 0.231654 +v -0.024980 0.078357 0.073318 +v -0.024980 -0.078431 0.073318 +v -0.024980 -0.078431 0.231654 +v 0.045130 0.147351 0.718184 +v 0.055983 0.140267 0.735595 +v 0.023424 0.147351 0.718184 +v 0.012572 0.140267 0.735595 +v 0.023424 0.133183 0.753006 +v 0.045130 0.133183 0.753006 +v 0.045902 0.137738 0.712869 +v 0.057528 0.130149 0.731520 +v 0.022651 0.137738 0.712869 +v 0.011026 0.130149 0.731520 +v 0.022651 0.122562 0.750170 +v 0.045902 0.122562 0.750170 +v -0.100829 0.017752 0.389536 +v -0.087071 0.017752 0.389746 +v -0.087071 -0.018076 0.389746 +v -0.100829 -0.018076 0.389536 +v -0.087071 -0.039930 0.382997 +v -0.100829 -0.039930 0.382787 +v -0.100829 0.039606 0.382787 +v -0.087071 0.039606 0.382997 +v -0.087071 -0.051703 0.364155 +v -0.100829 -0.051703 0.363944 +v -0.100829 0.051379 0.363944 +v -0.087071 0.051379 0.364154 +v -0.249123 -0.025754 0.548246 +v -0.249123 -0.010765 0.557316 +v -0.249123 -0.009940 0.555993 +v -0.249123 -0.018537 0.542937 +v -0.249123 0.006373 0.559004 +v -0.249123 0.005833 0.557546 +v -0.249123 0.024978 0.546921 +v -0.249123 0.016905 0.546427 +v -0.249124 0.024968 0.533235 +v -0.249124 0.014941 0.531008 +v -0.249123 0.001417 0.522900 +v -0.249123 0.007587 0.518279 +v -0.249123 0.001575 0.518120 +v -0.249123 -0.013482 0.528209 +v -0.249123 -0.007474 0.518182 +v -0.249123 -0.025737 0.532243 +v -0.277777 0.027547 0.546921 +v -0.277776 0.027537 0.533235 +v -0.277777 -0.028304 0.532243 +v -0.277777 -0.028323 0.548246 +v -0.277776 0.042966 0.546921 +v -0.277776 0.042950 0.533235 +v -0.277777 -0.043714 0.532243 +v -0.277777 -0.043744 0.548246 +v -0.252963 0.001575 0.513579 +v -0.252963 -0.007473 0.513641 +v -0.275112 0.007588 0.513738 +v -0.275112 0.001575 0.513579 +v -0.252963 0.007588 0.513738 +v -0.275112 -0.007473 0.513641 +v -0.275112 -0.014389 0.516336 +v -0.254549 -0.014389 0.516336 +v -0.275112 -0.029575 0.532001 +v -0.259819 -0.029575 0.532001 +v -0.275112 -0.029575 0.548019 +v -0.259819 -0.029575 0.548019 +v -0.255123 0.013767 0.515858 +v -0.275112 0.013767 0.515858 +v -0.260353 0.028948 0.532140 +v -0.275112 0.028948 0.532140 +v -0.260353 0.028948 0.548483 +v -0.275112 0.028948 0.548483 +v -0.251670 -0.009940 0.555993 +v -0.251670 -0.010765 0.557316 +v -0.251215 -0.024302 0.548247 +v -0.251670 -0.018537 0.542937 +v -0.251670 0.005833 0.557546 +v -0.251670 0.006373 0.559004 +v -0.251670 0.016905 0.546427 +v -0.251225 0.023540 0.546923 +v -0.251670 0.014941 0.531008 +v -0.251262 0.023587 0.533236 +v -0.251670 0.001417 0.522900 +v -0.251670 0.007587 0.518279 +v -0.251602 0.001579 0.518705 +v -0.251670 -0.013482 0.528209 +v -0.251579 -0.007469 0.518855 +v -0.251248 -0.024333 0.532244 +v -0.279655 0.025818 0.533236 +v -0.279656 0.025830 0.546923 +v -0.279656 -0.026606 0.548248 +v -0.279655 -0.026585 0.532245 +v -0.280323 0.042950 0.533235 +v -0.280323 0.042966 0.546921 +v -0.280323 -0.043744 0.548246 +v -0.280323 -0.043714 0.532243 +v -0.253716 -0.007153 0.516052 +v -0.253667 0.001561 0.516025 +v -0.275112 0.001550 0.516125 +v -0.275112 0.007136 0.516244 +v -0.252963 0.007179 0.516251 +v -0.275112 -0.006994 0.516142 +v -0.254549 -0.013048 0.518500 +v -0.275112 -0.012981 0.518457 +v -0.259819 -0.027244 0.533024 +v -0.275112 -0.027216 0.532957 +v -0.259819 -0.027029 0.548019 +v -0.275112 -0.027029 0.548019 +v -0.275112 0.012382 0.517994 +v -0.255123 0.012474 0.518051 +v -0.275112 0.026579 0.533073 +v -0.260353 0.026605 0.533137 +v -0.275112 0.026403 0.548483 +v -0.260353 0.026403 0.548483 +v -0.310666 -0.012361 0.238998 +v -0.310666 0.012564 0.266048 +v -0.310666 -0.012163 0.266048 +v -0.249508 -0.018232 0.542842 +v -0.249508 -0.009791 0.555662 +v -0.249508 0.005694 0.557187 +v -0.249508 0.016566 0.546269 +v -0.249508 0.014637 0.531130 +v -0.249508 0.001359 0.523170 +v -0.249508 -0.013270 0.528382 +v -0.212202 -0.017413 0.542742 +v -0.212202 -0.009360 0.554971 +v -0.212202 0.005413 0.556426 +v -0.212202 0.015784 0.546011 +v -0.212202 0.013944 0.531569 +v -0.212202 0.001277 0.523975 +v -0.212202 -0.012678 0.528948 +v 0.241103 -0.118944 0.635893 +v 0.257284 -0.093458 0.643680 +v 0.241103 -0.093458 0.635893 +v 0.257284 -0.118944 0.643680 +v 0.237057 -0.118944 0.618295 +v 0.237057 -0.093458 0.618295 +v 0.248283 -0.118944 0.604237 +v 0.248283 -0.093458 0.604237 +v 0.266285 -0.118944 0.604237 +v 0.266285 -0.093458 0.604237 +v 0.277512 -0.118944 0.618295 +v 0.277512 -0.093458 0.618295 +v 0.266285 -0.118944 0.604237 +v 0.273567 -0.118944 0.635893 +v 0.273567 -0.093458 0.635893 +v 0.277511 -0.093333 0.618170 +v 0.257284 -0.093333 0.643555 +v 0.273567 -0.093333 0.635768 +v 0.266285 -0.093333 0.604112 +v 0.241103 -0.093333 0.635768 +v 0.248283 -0.093333 0.604112 +v 0.237057 -0.093333 0.618170 +v 0.243125 -0.100513 0.634399 +v 0.271443 -0.100513 0.634399 +v 0.257284 -0.100513 0.641175 +v 0.239687 -0.100513 0.619027 +v 0.274983 -0.100513 0.619027 +v 0.249497 -0.100513 0.606789 +v 0.265173 -0.100513 0.606789 +v 0.257284 -0.118819 0.641175 +v 0.273567 -0.118819 0.636018 +v 0.257284 -0.118819 0.643805 +v 0.271443 -0.118819 0.634399 +v 0.277511 -0.118819 0.618420 +v 0.274983 -0.118819 0.619027 +v 0.266285 -0.118819 0.604362 +v 0.265173 -0.118819 0.606789 +v 0.248283 -0.118819 0.604362 +v 0.249497 -0.118819 0.606789 +v 0.237057 -0.118819 0.618420 +v 0.239687 -0.118819 0.619027 +v 0.243125 -0.118819 0.634399 +v 0.241103 -0.118819 0.636018 +v 0.243238 -0.100513 0.634328 +v 0.257397 -0.118819 0.641104 +v 0.243238 -0.118819 0.634328 +v 0.257397 -0.100513 0.641104 +v 0.239687 -0.100638 0.618902 +v 0.243125 -0.118944 0.634274 +v 0.239687 -0.118944 0.618902 +v 0.243125 -0.100638 0.634274 +v 0.249497 -0.100638 0.606664 +v 0.239687 -0.118944 0.618902 +v 0.249497 -0.118944 0.606664 +v 0.239687 -0.100638 0.618902 +v 0.265048 -0.100513 0.606664 +v 0.249372 -0.118819 0.606664 +v 0.265048 -0.118819 0.606664 +v 0.249372 -0.100513 0.606664 +v 0.274983 -0.100388 0.618902 +v 0.265173 -0.118694 0.606664 +v 0.274983 -0.118694 0.618902 +v 0.265173 -0.100388 0.606664 +v 0.271443 -0.100388 0.634274 +v 0.274983 -0.118694 0.618902 +v 0.271443 -0.118694 0.634274 +v 0.274983 -0.100388 0.618902 +v 0.257397 -0.100513 0.640996 +v 0.271556 -0.118819 0.634220 +v 0.257397 -0.118819 0.640996 +v 0.271556 -0.100513 0.634220 +v 0.266285 -0.093458 0.604237 +v 0.004561 0.013520 0.011191 +v 0.004561 0.000017 0.017825 +v -0.033039 0.000018 0.017825 +v -0.033039 0.013521 0.011191 +v 0.004561 0.016854 -0.003716 +v -0.033039 0.016855 -0.003716 +v 0.004561 0.007509 -0.015670 +v -0.033039 0.007513 -0.015670 +v 0.004561 -0.007477 -0.015670 +v -0.033039 -0.007475 -0.015670 +v 0.004561 -0.016821 -0.003716 +v -0.033039 -0.016818 -0.003716 +v 0.004561 -0.013486 0.011191 +v -0.033039 -0.013484 0.011191 +v 0.211464 -0.256311 0.480069 +v 0.232961 -0.242442 0.467683 +v 0.235327 -0.224987 0.488867 +v 0.217360 -0.238456 0.499775 +v 0.208352 -0.263195 0.426514 +v 0.232955 -0.243338 0.421617 +v 0.215398 -0.241444 0.393901 +v 0.234489 -0.226118 0.397178 +v 0.217642 -0.222329 0.376958 +v 0.236613 -0.204451 0.375152 +v 0.206400 -0.186031 0.326815 +v 0.233092 -0.164828 0.324466 +v 0.221847 -0.208029 0.515935 +v 0.239730 -0.190649 0.502544 +v 0.223848 -0.170766 0.523822 +v 0.242944 -0.162196 0.508734 +v 0.225672 -0.141090 0.529561 +v 0.245072 -0.137265 0.514249 +v 0.225861 -0.066095 0.525723 +v 0.246611 -0.057305 0.510650 +v 0.243052 -0.222025 0.456918 +v 0.243690 -0.210325 0.474368 +v 0.248713 -0.178039 0.486632 +v 0.253139 -0.150163 0.489993 +v 0.257091 -0.121875 0.491006 +v 0.260286 -0.052931 0.492696 +v 0.244970 -0.221176 0.419725 +v 0.247631 -0.205762 0.400044 +v 0.251885 -0.185484 0.380700 +v 0.253990 -0.149641 0.331637 +v 0.193750 -0.172083 0.295549 +v 0.224817 -0.147654 0.290653 +v 0.250586 -0.128485 0.291217 +v 0.212342 -0.135810 0.256526 +v 0.246353 -0.110819 0.252141 +v 0.199134 -0.124981 0.217215 +v 0.236434 -0.099185 0.217426 +v 0.178560 -0.159819 0.259570 +v 0.152494 -0.151596 0.210976 +v 0.157336 -0.136104 0.180218 +v 0.191194 -0.119688 0.191523 +v 0.230626 -0.094495 0.188636 +v 0.185472 -0.114917 0.168045 +v 0.169875 -0.116489 0.141881 +v 0.221776 -0.090865 0.161456 +v 0.208949 -0.090137 0.133869 +v 0.123473 -0.153257 0.170219 +v 0.134506 -0.139532 0.148166 +v 0.158005 -0.118338 0.120474 +v 0.197776 -0.090385 0.104815 +v 0.082867 -0.160648 0.129879 +v 0.111494 -0.142859 0.110622 +v 0.143184 -0.119193 0.086700 +v 0.177942 -0.090286 0.064424 +v 0.032116 -0.169461 0.085433 +v 0.075116 -0.151163 0.063472 +v 0.119509 -0.123829 0.046080 +v 0.162697 -0.088695 0.029479 +v -0.011897 -0.174273 0.048290 +v 0.057538 -0.156450 0.047296 +v 0.107981 -0.125094 0.022548 +v 0.146652 -0.087616 0.007384 +v 0.121172 -0.088321 -0.010394 +v 0.099178 -0.123271 0.003157 +v 0.051428 -0.156002 0.019496 +v -0.003931 -0.173638 0.028106 +v -0.028352 -0.174521 0.032143 +v -0.031310 -0.174536 0.023231 +v -0.027212 -0.174545 0.011411 +v 0.067688 -0.101139 -0.028265 +v 0.081547 -0.124277 -0.011278 +v 0.049480 -0.155357 0.003687 +v 0.046642 -0.152319 -0.008902 +v 0.014555 -0.170696 0.002907 +v 0.009701 -0.171974 0.014527 +v -0.016123 -0.174629 0.005117 +v 0.257810 -0.070748 0.220855 +v 0.263381 -0.086308 0.257520 +v 0.264708 -0.110246 0.302780 +v 0.264793 -0.129373 0.342557 +v 0.261213 -0.154125 0.386585 +v 0.257858 -0.171575 0.388365 +v 0.254231 -0.188003 0.408596 +v 0.251965 -0.063622 0.188122 +v 0.242917 -0.061035 0.161599 +v 0.255028 -0.180709 0.417616 +v 0.250638 -0.182325 0.465483 +v 0.253986 -0.161369 0.467918 +v 0.249104 -0.193925 0.458061 +v 0.267021 -0.047397 0.465477 +v 0.261412 -0.112766 0.465092 +v 0.258184 -0.137707 0.464758 +v 0.257381 -0.166593 0.422578 +v 0.260764 -0.149712 0.411115 +v 0.263655 -0.127758 0.418436 +v 0.266957 -0.098592 0.419810 +v 0.271606 -0.038308 0.416746 +v 0.267851 -0.108436 0.350708 +v 0.270481 -0.082126 0.360208 +v 0.273553 -0.029073 0.358756 +v 0.268069 -0.093834 0.308223 +v 0.269501 -0.073552 0.304386 +v 0.272199 -0.024689 0.306710 +v 0.268970 -0.030183 0.262888 +v 0.264035 -0.034067 0.224147 +v 0.258087 -0.034356 0.188059 +v 0.251370 -0.033058 0.161566 +v 0.068474 -0.066812 -0.028677 +v 0.120859 -0.062087 -0.014621 +v 0.120026 -0.020149 -0.014868 +v 0.067589 -0.017488 -0.028908 +v 0.156080 -0.060778 0.000506 +v 0.157069 -0.023522 -0.001561 +v 0.267809 -0.000000 0.467378 +v 0.272458 -0.000000 0.308918 +v 0.264204 -0.000000 0.224782 +v 0.120026 -0.000000 -0.014868 +v 0.273813 -0.000000 0.358421 +v 0.269321 -0.000000 0.265975 +v 0.258140 -0.000000 0.188211 +v 0.230315 -0.059840 0.133173 +v 0.241544 -0.033885 0.133015 +v 0.216023 -0.060519 0.102675 +v 0.229009 -0.031268 0.102675 +v 0.197188 -0.060352 0.060443 +v 0.206922 -0.029852 0.060443 +v 0.177728 -0.059718 0.025085 +v 0.185434 -0.025725 0.024886 +v 0.251186 -0.000000 0.161451 +v 0.240386 -0.000000 0.132983 +v 0.229009 -0.000000 0.102675 +v 0.206922 -0.000000 0.060443 +v 0.185434 -0.000000 0.024886 +v 0.232961 0.242442 0.467683 +v 0.211464 0.256311 0.480069 +v 0.217360 0.238455 0.499775 +v 0.235327 0.224986 0.488867 +v 0.221847 0.208029 0.515935 +v 0.239730 0.190649 0.502544 +v 0.223848 0.170766 0.523822 +v 0.242944 0.162196 0.508734 +v 0.245072 0.137265 0.514249 +v 0.225672 0.141090 0.529561 +v 0.246611 0.057305 0.510650 +v 0.225861 0.066095 0.525723 +v 0.232955 0.243338 0.421617 +v 0.208352 0.263195 0.426514 +v 0.234489 0.226118 0.397178 +v 0.215398 0.241444 0.393901 +v 0.236613 0.204451 0.375152 +v 0.217642 0.222329 0.376958 +v 0.233092 0.164828 0.324466 +v 0.206400 0.186031 0.326815 +v 0.224817 0.147654 0.290653 +v 0.193750 0.172083 0.295549 +v 0.212342 0.135810 0.256526 +v 0.178560 0.159819 0.259570 +v 0.199134 0.124981 0.217215 +v 0.152494 0.151596 0.210976 +v 0.191194 0.119688 0.191523 +v 0.157336 0.136104 0.180218 +v 0.185472 0.114917 0.168045 +v 0.169875 0.116489 0.141881 +v 0.134506 0.139532 0.148166 +v 0.123473 0.153257 0.170219 +v 0.158005 0.118338 0.120474 +v 0.208949 0.090137 0.133869 +v 0.197776 0.090385 0.104815 +v 0.111494 0.142859 0.110622 +v 0.082867 0.160648 0.129879 +v 0.143184 0.119193 0.086700 +v 0.177942 0.090286 0.064424 +v 0.075116 0.151163 0.063472 +v 0.032116 0.169461 0.085433 +v 0.119509 0.123829 0.046080 +v 0.162697 0.088694 0.029479 +v 0.107981 0.125094 0.022548 +v 0.057538 0.156450 0.047296 +v -0.011897 0.174272 0.048290 +v 0.051428 0.156002 0.019496 +v 0.099178 0.123271 0.003157 +v 0.081547 0.124277 -0.011278 +v 0.049480 0.155357 0.003687 +v -0.003931 0.173638 0.028106 +v 0.009701 0.171974 0.014527 +v -0.028352 0.174521 0.032143 +v -0.031310 0.174536 0.023231 +v 0.014555 0.170696 0.002907 +v 0.046642 0.152319 -0.008902 +v -0.027212 0.174545 0.011411 +v -0.016123 0.174629 0.005117 +v 0.246353 0.110819 0.252141 +v 0.236434 0.099184 0.217426 +v 0.250586 0.128485 0.291217 +v 0.253990 0.149641 0.331637 +v 0.251885 0.185484 0.380700 +v 0.247631 0.205762 0.400044 +v 0.230626 0.094495 0.188636 +v 0.221776 0.090865 0.161456 +v 0.244970 0.221176 0.419725 +v 0.257858 0.171575 0.388365 +v 0.254231 0.188003 0.408596 +v 0.243690 0.210325 0.474368 +v 0.248713 0.178039 0.486632 +v 0.243052 0.222025 0.456918 +v 0.260286 0.052931 0.492696 +v 0.257091 0.121875 0.491006 +v 0.253139 0.150162 0.489993 +v 0.249104 0.193925 0.458061 +v 0.250638 0.182325 0.465483 +v 0.253986 0.161369 0.467918 +v 0.258184 0.137707 0.464758 +v 0.261412 0.112766 0.465092 +v 0.267021 0.047397 0.465477 +v 0.255028 0.180709 0.417616 +v 0.257381 0.166593 0.422578 +v 0.261213 0.154125 0.386585 +v 0.260764 0.149712 0.411115 +v 0.263655 0.127758 0.418436 +v 0.266957 0.098592 0.419810 +v 0.271606 0.038308 0.416746 +v 0.264793 0.129373 0.342557 +v 0.264708 0.110246 0.302780 +v 0.267851 0.108436 0.350708 +v 0.268069 0.093834 0.308223 +v 0.270481 0.082126 0.360208 +v 0.273553 0.029073 0.358756 +v 0.269501 0.073552 0.304386 +v 0.263381 0.086308 0.257520 +v 0.272199 0.024689 0.306710 +v 0.257810 0.070748 0.220855 +v 0.268970 0.030183 0.262888 +v 0.251965 0.063622 0.188122 +v 0.264035 0.034067 0.224147 +v 0.242917 0.061035 0.161599 +v 0.258087 0.034356 0.188059 +v 0.251370 0.033058 0.161566 +v 0.067688 0.101139 -0.028265 +v 0.121172 0.088321 -0.010394 +v 0.146652 0.087616 0.007384 +v 0.120859 0.062087 -0.014621 +v 0.068474 0.066812 -0.028677 +v 0.156080 0.060778 0.000506 +v 0.067589 0.017488 -0.028908 +v 0.120026 0.020149 -0.014868 +v 0.157069 0.023522 -0.001561 +v 0.157090 -0.000000 -0.001548 +v 0.067589 -0.000000 -0.028908 +v 0.224251 -0.000000 0.521646 +v 0.247960 -0.000000 0.506863 +v 0.261160 -0.000000 0.490681 +v 0.271949 -0.000000 0.417485 +v 0.216023 0.060519 0.102675 +v 0.230315 0.059840 0.133173 +v 0.197188 0.060352 0.060443 +v 0.177728 0.059717 0.025085 +v 0.229009 0.031268 0.102675 +v 0.241544 0.033885 0.133015 +v 0.206922 0.029852 0.060443 +v 0.185434 0.025725 0.024886 +v 0.205276 -0.249058 0.477801 +v 0.225489 -0.236304 0.466092 +v 0.227299 -0.220985 0.484919 +v 0.210685 -0.233108 0.494989 +v 0.202247 -0.255614 0.427651 +v 0.225945 -0.236784 0.423606 +v 0.209489 -0.234828 0.398066 +v 0.227572 -0.220452 0.401190 +v 0.212589 -0.216261 0.382762 +v 0.229980 -0.198941 0.379808 +v 0.201647 -0.179335 0.332164 +v 0.227410 -0.158435 0.329250 +v 0.214802 -0.205059 0.509805 +v 0.231649 -0.188292 0.497525 +v 0.217320 -0.168752 0.516797 +v 0.235047 -0.160222 0.503278 +v 0.219555 -0.140223 0.521954 +v 0.237394 -0.136287 0.508238 +v 0.220244 -0.066582 0.517707 +v 0.239857 -0.057637 0.503556 +v 0.233838 -0.218800 0.456058 +v 0.234414 -0.207805 0.472460 +v 0.239405 -0.176074 0.484279 +v 0.243804 -0.148607 0.487444 +v 0.247728 -0.120885 0.488289 +v 0.251420 -0.052826 0.488520 +v 0.235983 -0.217366 0.420596 +v 0.238888 -0.201844 0.402103 +v 0.243375 -0.181490 0.383472 +v 0.246209 -0.144628 0.334857 +v 0.188959 -0.164961 0.300278 +v 0.219601 -0.140659 0.295115 +v 0.243609 -0.122555 0.294708 +v 0.207326 -0.128412 0.260543 +v 0.239638 -0.104690 0.255798 +v 0.194077 -0.117361 0.220737 +v 0.229887 -0.092633 0.220628 +v 0.173703 -0.152379 0.263705 +v 0.147588 -0.143804 0.214330 +v 0.152280 -0.128227 0.183121 +v 0.186234 -0.111764 0.194466 +v 0.224149 -0.087667 0.191368 +v 0.180557 -0.106853 0.170663 +v 0.164903 -0.108362 0.144177 +v 0.215387 -0.084096 0.164523 +v 0.202544 -0.083293 0.136729 +v 0.118965 -0.144974 0.172883 +v 0.129575 -0.131431 0.150635 +v 0.153065 -0.110120 0.122497 +v 0.191219 -0.083645 0.107575 +v 0.079073 -0.151827 0.131833 +v 0.107007 -0.134396 0.112694 +v 0.138255 -0.110976 0.088755 +v 0.171531 -0.083539 0.067493 +v 0.029311 -0.160192 0.086938 +v 0.071103 -0.142375 0.065114 +v 0.114537 -0.115628 0.048096 +v 0.156230 -0.082508 0.033472 +v -0.013534 -0.164612 0.048482 +v 0.053929 -0.147411 0.048436 +v 0.102891 -0.117127 0.025130 +v 0.140861 -0.082260 0.013200 +v 0.116835 -0.084836 -0.002326 +v 0.094171 -0.116152 0.007660 +v 0.047189 -0.147240 0.020641 +v -0.005432 -0.163959 0.027793 +v -0.028686 -0.164728 0.032268 +v -0.031627 -0.164741 0.023209 +v -0.027432 -0.164750 0.011185 +v 0.064494 -0.098114 -0.019508 +v 0.078012 -0.118195 -0.004455 +v 0.044183 -0.147439 0.005986 +v 0.039883 -0.145920 -0.005833 +v 0.011475 -0.161394 0.003013 +v 0.007242 -0.162509 0.013890 +v -0.016670 -0.164844 0.005039 +v 0.248884 -0.067471 0.223227 +v 0.254306 -0.083403 0.259807 +v 0.255611 -0.107066 0.304564 +v 0.255404 -0.126778 0.343629 +v 0.251606 -0.152231 0.386981 +v 0.248424 -0.169351 0.389814 +v 0.245073 -0.184698 0.407475 +v 0.243247 -0.060058 0.190831 +v 0.234604 -0.057003 0.164868 +v 0.245467 -0.178638 0.417037 +v 0.241094 -0.180559 0.464131 +v 0.244382 -0.159755 0.466828 +v 0.239566 -0.191882 0.457118 +v 0.257353 -0.046977 0.463925 +v 0.251728 -0.111717 0.464011 +v 0.248543 -0.136291 0.463714 +v 0.247733 -0.165039 0.421833 +v 0.251103 -0.148177 0.410524 +v 0.253957 -0.126471 0.417863 +v 0.257220 -0.097648 0.419218 +v 0.261830 -0.037909 0.416186 +v 0.258125 -0.107237 0.350798 +v 0.260713 -0.081336 0.360156 +v 0.263758 -0.028756 0.358753 +v 0.258422 -0.092653 0.309480 +v 0.259756 -0.072828 0.305137 +v 0.262418 -0.024368 0.307240 +v 0.259234 -0.029661 0.263875 +v 0.254374 -0.033229 0.225561 +v 0.248581 -0.033248 0.190171 +v 0.242069 -0.031732 0.164353 +v 0.065928 -0.066721 -0.019214 +v 0.117583 -0.061429 -0.005408 +v 0.117101 -0.020152 -0.005515 +v 0.065054 -0.017488 -0.019442 +v 0.150172 -0.058792 0.008069 +v 0.151823 -0.023188 0.006710 +v 0.258176 -0.000000 0.465578 +v 0.262670 -0.000000 0.309397 +v 0.254506 -0.000000 0.226191 +v 0.117099 -0.000000 -0.005515 +v 0.264013 -0.000000 0.358400 +v 0.259566 -0.000000 0.266921 +v 0.248551 -0.000000 0.190233 +v 0.222400 -0.055374 0.136840 +v 0.232591 -0.032221 0.136636 +v 0.208015 -0.056117 0.106213 +v 0.220240 -0.029567 0.106705 +v 0.189216 -0.056478 0.064625 +v 0.198496 -0.028513 0.065265 +v 0.170131 -0.056797 0.030543 +v 0.177824 -0.024794 0.030989 +v 0.241827 -0.000000 0.164360 +v 0.231245 -0.000000 0.136515 +v 0.220063 -0.000000 0.106675 +v 0.198382 -0.000000 0.065250 +v 0.177826 -0.000000 0.031062 +v 0.225489 0.236304 0.466092 +v 0.205276 0.249058 0.477801 +v 0.210685 0.233108 0.494989 +v 0.227299 0.220985 0.484919 +v 0.214802 0.205059 0.509805 +v 0.231649 0.188292 0.497525 +v 0.217320 0.168751 0.516797 +v 0.235047 0.160221 0.503278 +v 0.237394 0.136287 0.508238 +v 0.219555 0.140223 0.521954 +v 0.239857 0.057637 0.503556 +v 0.220244 0.066582 0.517707 +v 0.225945 0.236784 0.423606 +v 0.202247 0.255614 0.427651 +v 0.227572 0.220452 0.401190 +v 0.209489 0.234828 0.398066 +v 0.229980 0.198941 0.379808 +v 0.212589 0.216261 0.382762 +v 0.227410 0.158435 0.329250 +v 0.201647 0.179335 0.332164 +v 0.219601 0.140659 0.295115 +v 0.188959 0.164961 0.300278 +v 0.207326 0.128412 0.260543 +v 0.173703 0.152379 0.263705 +v 0.194077 0.117361 0.220737 +v 0.147588 0.143804 0.214330 +v 0.186234 0.111764 0.194466 +v 0.152280 0.128227 0.183121 +v 0.180557 0.106853 0.170663 +v 0.164903 0.108362 0.144177 +v 0.129575 0.131431 0.150635 +v 0.118965 0.144974 0.172883 +v 0.153065 0.110119 0.122497 +v 0.202544 0.083293 0.136729 +v 0.191219 0.083645 0.107575 +v 0.107007 0.134396 0.112694 +v 0.079073 0.151826 0.131833 +v 0.138255 0.110976 0.088755 +v 0.171531 0.083539 0.067493 +v 0.071103 0.142375 0.065114 +v 0.029311 0.160192 0.086938 +v 0.114537 0.115628 0.048096 +v 0.156230 0.082508 0.033472 +v 0.102891 0.117127 0.025130 +v 0.053929 0.147411 0.048436 +v -0.013534 0.164612 0.048482 +v 0.047189 0.147240 0.020641 +v 0.094171 0.116151 0.007660 +v 0.078012 0.118195 -0.004455 +v 0.044183 0.147439 0.005986 +v -0.005432 0.163958 0.027793 +v 0.007242 0.162509 0.013890 +v -0.028686 0.164728 0.032268 +v -0.031627 0.164741 0.023209 +v 0.011475 0.161394 0.003013 +v 0.039883 0.145920 -0.005833 +v -0.027432 0.164750 0.011185 +v -0.016670 0.164844 0.005039 +v 0.239638 0.104690 0.255798 +v 0.229887 0.092633 0.220628 +v 0.243609 0.122555 0.294708 +v 0.246209 0.144628 0.334857 +v 0.243375 0.181490 0.383472 +v 0.238888 0.201844 0.402103 +v 0.224149 0.087667 0.191368 +v 0.215387 0.084096 0.164523 +v 0.235983 0.217366 0.420596 +v 0.248424 0.169351 0.389814 +v 0.245073 0.184698 0.407475 +v 0.234414 0.207805 0.472460 +v 0.239405 0.176074 0.484279 +v 0.233838 0.218800 0.456058 +v 0.251420 0.052826 0.488520 +v 0.247728 0.120885 0.488289 +v 0.243804 0.148607 0.487444 +v 0.239566 0.191882 0.457118 +v 0.241094 0.180559 0.464131 +v 0.244382 0.159755 0.466828 +v 0.248543 0.136291 0.463714 +v 0.251728 0.111717 0.464011 +v 0.257353 0.046977 0.463925 +v 0.245467 0.178638 0.417037 +v 0.247733 0.165039 0.421833 +v 0.251606 0.152231 0.386981 +v 0.251103 0.148177 0.410524 +v 0.253957 0.126471 0.417863 +v 0.257220 0.097648 0.419218 +v 0.261830 0.037909 0.416186 +v 0.255404 0.126778 0.343629 +v 0.255611 0.107066 0.304564 +v 0.258125 0.107237 0.350798 +v 0.258422 0.092653 0.309480 +v 0.260713 0.081336 0.360156 +v 0.263758 0.028756 0.358753 +v 0.259756 0.072828 0.305137 +v 0.254306 0.083403 0.259807 +v 0.262418 0.024368 0.307240 +v 0.248884 0.067471 0.223227 +v 0.259234 0.029661 0.263875 +v 0.243247 0.060058 0.190831 +v 0.254374 0.033229 0.225561 +v 0.234604 0.057003 0.164868 +v 0.248581 0.033247 0.190171 +v 0.242069 0.031732 0.164353 +v 0.064494 0.098114 -0.019508 +v 0.116835 0.084836 -0.002326 +v 0.140861 0.082260 0.013200 +v 0.117583 0.061429 -0.005408 +v 0.065928 0.066721 -0.019214 +v 0.150172 0.058792 0.008069 +v 0.065054 0.017488 -0.019442 +v 0.117101 0.020152 -0.005515 +v 0.151823 0.023188 0.006710 +v 0.151986 -0.000000 0.006818 +v 0.065054 -0.000000 -0.019442 +v 0.218959 -0.000000 0.513398 +v 0.241408 -0.000000 0.499575 +v 0.252420 -0.000000 0.486247 +v 0.262165 -0.000000 0.416920 +v 0.208015 0.056117 0.106213 +v 0.222400 0.055374 0.136840 +v 0.189216 0.056478 0.064625 +v 0.170131 0.056797 0.030543 +v 0.220240 0.029567 0.106705 +v 0.232591 0.032221 0.136636 +v 0.198496 0.028513 0.065265 +v 0.177824 0.024794 0.030989 +v 0.123418 -0.269771 0.367109 +v 0.123418 -0.250426 0.367109 +v 0.159663 -0.269771 0.367109 +v 0.159663 -0.250426 0.367109 +v 0.120734 -0.269771 0.351418 +v 0.162347 -0.269771 0.351418 +v 0.162347 -0.250426 0.357539 +v 0.159663 -0.250266 0.357539 +v 0.123418 -0.250266 0.357539 +v 0.120734 -0.250426 0.357539 +v 0.159663 -0.250426 0.332333 +v 0.159663 -0.257587 0.332333 +v 0.123418 -0.250426 0.332333 +v 0.123418 -0.257587 0.332332 +v 0.182083 -0.225181 0.357586 +v 0.172104 -0.199550 0.357586 +v 0.146837 -0.185912 0.357586 +v 0.118104 -0.190648 0.357586 +v 0.099350 -0.211543 0.357586 +v 0.099350 -0.238820 0.357586 +v 0.118104 -0.259715 0.357586 +v 0.146837 -0.264451 0.357586 +v 0.172104 -0.250813 0.357586 +v 0.182083 -0.225181 0.418669 +v 0.172104 -0.199550 0.418669 +v 0.146837 -0.185912 0.418669 +v 0.118104 -0.190648 0.418669 +v 0.099350 -0.211543 0.418669 +v 0.099350 -0.238820 0.418669 +v 0.118104 -0.259715 0.418669 +v 0.146837 -0.264451 0.418669 +v 0.172104 -0.250813 0.418669 +v 0.160822 -0.269420 0.356369 +v 0.175693 -0.257117 0.356369 +v 0.180379 -0.248593 0.356369 +v 0.182798 -0.242449 0.356445 +v 0.160822 -0.269420 0.367357 +v 0.175693 -0.257117 0.367356 +v 0.180379 -0.248593 0.367335 +v 0.182798 -0.242449 0.367326 +v 0.168257 -0.264157 0.356369 +v 0.168257 -0.264157 0.367356 +v 0.155845 -0.262389 0.356369 +v 0.168876 -0.251851 0.356369 +v 0.172582 -0.244931 0.356369 +v 0.174783 -0.239294 0.356445 +v 0.155845 -0.262389 0.367356 +v 0.168877 -0.251851 0.367357 +v 0.172582 -0.244933 0.367335 +v 0.174783 -0.239293 0.367326 +v 0.162794 -0.257497 0.356369 +v 0.162794 -0.257497 0.367356 +v 0.182083 0.225181 0.357586 +v 0.172104 0.199550 0.357586 +v 0.146837 0.185911 0.357586 +v 0.118104 0.190648 0.357586 +v 0.099350 0.211543 0.357586 +v 0.099350 0.238820 0.357586 +v 0.118104 0.259715 0.357586 +v 0.146837 0.264451 0.357586 +v 0.172104 0.250813 0.357586 +v 0.182083 0.225181 0.418669 +v 0.172104 0.199550 0.418669 +v 0.146837 0.185911 0.418669 +v 0.118104 0.190648 0.418669 +v 0.099350 0.211543 0.418669 +v 0.099350 0.238820 0.418669 +v 0.118104 0.259715 0.418669 +v 0.146837 0.264451 0.418669 +v 0.172104 0.250813 0.418669 +v 0.160822 0.269420 0.356369 +v 0.175693 0.257117 0.356369 +v 0.180379 0.248593 0.356369 +v 0.182798 0.242449 0.356445 +v 0.160822 0.269420 0.367357 +v 0.175693 0.257117 0.367356 +v 0.180379 0.248593 0.367335 +v 0.182798 0.242449 0.367326 +v 0.168257 0.264157 0.356369 +v 0.168257 0.264157 0.367356 +v 0.155845 0.262389 0.356369 +v 0.168876 0.251851 0.356369 +v 0.172582 0.244931 0.356369 +v 0.174783 0.239294 0.356445 +v 0.155845 0.262389 0.367356 +v 0.168877 0.251851 0.367357 +v 0.172582 0.244933 0.367335 +v 0.174783 0.239293 0.367326 +v 0.162794 0.257497 0.356369 +v 0.162794 0.257497 0.367356 +v 0.149420 0.202775 0.526073 +v 0.149420 0.249526 0.526073 +v 0.149420 0.249526 0.503214 +v 0.149420 0.202775 0.503214 +v 0.148685 0.196829 0.526073 +v 0.148684 0.202775 0.526152 +v 0.148684 0.249526 0.526152 +v 0.148685 0.255472 0.526073 +v 0.148684 0.255472 0.503214 +v 0.148684 0.249526 0.503046 +v 0.148685 0.202775 0.503046 +v 0.148684 0.196829 0.503214 +v 0.092273 0.196829 0.526073 +v 0.092273 0.202775 0.526152 +v 0.092273 0.249526 0.526152 +v 0.092273 0.255472 0.526073 +v 0.092273 0.255472 0.503214 +v 0.092273 0.249526 0.503046 +v 0.092273 0.202775 0.503046 +v 0.092273 0.196829 0.503214 +v 0.085892 0.202775 0.526073 +v 0.085892 0.249526 0.526073 +v 0.085892 0.249526 0.503214 +v 0.085892 0.202775 0.503214 +v 0.149351 0.202775 0.502676 +v 0.149351 0.249526 0.502676 +v 0.149351 0.249526 0.480371 +v 0.149351 0.202775 0.480371 +v 0.148844 0.196829 0.502676 +v 0.148844 0.202775 0.502735 +v 0.148844 0.249526 0.502735 +v 0.148844 0.255472 0.502676 +v 0.148844 0.255472 0.480371 +v 0.148844 0.249526 0.480246 +v 0.148844 0.202775 0.480246 +v 0.148844 0.196829 0.480371 +v 0.109915 0.196829 0.502676 +v 0.109915 0.202775 0.502735 +v 0.109915 0.249526 0.502735 +v 0.109915 0.255472 0.502676 +v 0.109915 0.255472 0.480371 +v 0.109915 0.249526 0.480246 +v 0.109915 0.202775 0.480246 +v 0.109915 0.196829 0.480371 +v 0.105511 0.202775 0.502676 +v 0.105511 0.249526 0.502676 +v 0.105511 0.249526 0.480371 +v 0.105511 0.202775 0.480371 +v 0.186952 -0.225181 0.411718 +v 0.175523 -0.195823 0.411718 +v 0.146582 -0.180202 0.411718 +v 0.113671 -0.185627 0.411718 +v 0.092190 -0.209560 0.411718 +v 0.092190 -0.240803 0.411718 +v 0.113671 -0.264736 0.411718 +v 0.146582 -0.270161 0.411718 +v 0.175523 -0.254540 0.411718 +v 0.186952 -0.225181 0.481682 +v 0.175523 -0.195823 0.481682 +v 0.146582 -0.180202 0.481682 +v 0.113671 -0.185627 0.481682 +v 0.092190 -0.209560 0.481682 +v 0.092190 -0.240803 0.481682 +v 0.113671 -0.264736 0.481682 +v 0.146582 -0.270161 0.481682 +v 0.175523 -0.254540 0.481682 +v 0.181818 -0.195845 0.385221 +v 0.180061 -0.192900 0.377451 +v 0.175663 -0.187584 0.375259 +v 0.152587 -0.172939 0.375259 +v 0.125311 -0.171223 0.375259 +v 0.095551 -0.187584 0.375259 +v 0.088921 -0.196065 0.375259 +v 0.087818 -0.197142 0.375259 +v 0.081092 -0.218312 0.375259 +v 0.081092 -0.232085 0.375259 +v 0.087424 -0.251709 0.375259 +v 0.087858 -0.253143 0.375259 +v 0.095551 -0.262813 0.375259 +v 0.106164 -0.271593 0.375259 +v 0.132157 -0.280038 0.375259 +v 0.159003 -0.274917 0.375259 +v 0.180061 -0.257496 0.375259 +v 0.183759 -0.251670 0.375259 +v 0.186697 -0.245426 0.375259 +v 0.188829 -0.238863 0.378465 +v 0.190122 -0.236726 0.381461 +v 0.181818 -0.195845 0.420292 +v 0.180061 -0.192901 0.423227 +v 0.175663 -0.187584 0.427701 +v 0.152587 -0.172939 0.427701 +v 0.125311 -0.171223 0.427701 +v 0.095551 -0.187584 0.427701 +v 0.088921 -0.196065 0.419834 +v 0.087818 -0.197142 0.404530 +v 0.081092 -0.218312 0.404539 +v 0.081092 -0.232085 0.404848 +v 0.087424 -0.251709 0.404911 +v 0.087858 -0.253143 0.420068 +v 0.095551 -0.262813 0.427701 +v 0.106164 -0.271593 0.427701 +v 0.132157 -0.280039 0.427701 +v 0.159003 -0.274917 0.427701 +v 0.180062 -0.257496 0.427701 +v 0.183759 -0.251670 0.405106 +v 0.186697 -0.245426 0.398309 +v 0.188829 -0.238863 0.391662 +v 0.190122 -0.236726 0.387353 +v 0.173771 -0.200645 0.385221 +v 0.172676 -0.198668 0.377450 +v 0.169586 -0.194716 0.375259 +v 0.149692 -0.181851 0.375259 +v 0.127355 -0.180368 0.375259 +v 0.101524 -0.194803 0.375259 +v 0.096052 -0.202143 0.375259 +v 0.095793 -0.202060 0.375259 +v 0.090351 -0.219747 0.375259 +v 0.090348 -0.230629 0.375259 +v 0.096368 -0.248915 0.375259 +v 0.096157 -0.248793 0.375259 +v 0.102240 -0.256251 0.375259 +v 0.110678 -0.263382 0.375259 +v 0.132745 -0.270687 0.375259 +v 0.155014 -0.266439 0.375259 +v 0.173033 -0.251300 0.375259 +v 0.175548 -0.247156 0.375259 +v 0.178020 -0.241891 0.375259 +v 0.180107 -0.235442 0.378465 +v 0.182105 -0.231876 0.381461 +v 0.173771 -0.200645 0.420292 +v 0.172584 -0.198547 0.423227 +v 0.169715 -0.194824 0.427701 +v 0.149692 -0.181851 0.427701 +v 0.127355 -0.180368 0.427701 +v 0.101230 -0.195037 0.427701 +v 0.096537 -0.201524 0.419834 +v 0.095378 -0.202678 0.404530 +v 0.090353 -0.219737 0.404539 +v 0.090346 -0.230617 0.404848 +v 0.096376 -0.248941 0.404911 +v 0.095287 -0.247433 0.420068 +v 0.102095 -0.256107 0.427701 +v 0.110678 -0.263382 0.427701 +v 0.132745 -0.270687 0.427701 +v 0.155014 -0.266439 0.427701 +v 0.173735 -0.250585 0.427701 +v 0.175712 -0.246870 0.405106 +v 0.178094 -0.241713 0.398309 +v 0.180049 -0.235591 0.391662 +v 0.182105 -0.231876 0.387353 +v 0.149420 -0.202775 0.526073 +v 0.149420 -0.249526 0.526073 +v 0.149420 -0.249526 0.503214 +v 0.149420 -0.202775 0.503214 +v 0.148685 -0.196829 0.526073 +v 0.148685 -0.202775 0.526152 +v 0.148684 -0.249526 0.526152 +v 0.148685 -0.255472 0.526073 +v 0.148685 -0.255472 0.503214 +v 0.148685 -0.249526 0.503046 +v 0.148685 -0.202775 0.503046 +v 0.148685 -0.196829 0.503214 +v 0.092273 -0.196829 0.526073 +v 0.092273 -0.202775 0.526152 +v 0.092273 -0.249526 0.526152 +v 0.092273 -0.255472 0.526073 +v 0.092273 -0.255472 0.503214 +v 0.092273 -0.249526 0.503046 +v 0.092273 -0.202775 0.503046 +v 0.092273 -0.196829 0.503214 +v 0.085892 -0.202775 0.526073 +v 0.085892 -0.249526 0.526073 +v 0.085892 -0.249526 0.503214 +v 0.085892 -0.202775 0.503214 +v 0.149351 -0.202775 0.502676 +v 0.149351 -0.249526 0.502676 +v 0.149351 -0.249526 0.480371 +v 0.149351 -0.202775 0.480371 +v 0.148844 -0.196829 0.502676 +v 0.148844 -0.202775 0.502735 +v 0.148844 -0.249526 0.502735 +v 0.148844 -0.255472 0.502676 +v 0.148844 -0.255472 0.480371 +v 0.148844 -0.249526 0.480246 +v 0.148844 -0.202775 0.480246 +v 0.148844 -0.196829 0.480371 +v 0.109915 -0.196829 0.502676 +v 0.109915 -0.202775 0.502735 +v 0.109915 -0.249526 0.502735 +v 0.109915 -0.255472 0.502676 +v 0.109915 -0.255472 0.480371 +v 0.109915 -0.249526 0.480246 +v 0.109915 -0.202775 0.480246 +v 0.109915 -0.196829 0.480371 +v 0.105511 -0.202775 0.502676 +v 0.105511 -0.249526 0.502676 +v 0.105511 -0.249526 0.480371 +v 0.105511 -0.202775 0.480371 +v 0.123418 0.269771 0.367109 +v 0.123418 0.250426 0.367109 +v 0.159663 0.269771 0.367109 +v 0.159663 0.250426 0.367109 +v 0.120734 0.269771 0.351418 +v 0.162347 0.269771 0.351418 +v 0.162347 0.250426 0.357539 +v 0.159663 0.250266 0.357539 +v 0.123418 0.250266 0.357539 +v 0.120734 0.250426 0.357539 +v 0.159663 0.250426 0.332333 +v 0.159663 0.257587 0.332333 +v 0.123418 0.250426 0.332333 +v 0.123418 0.257587 0.332332 +v 0.186952 0.225181 0.411718 +v 0.175523 0.195823 0.411718 +v 0.146582 0.180202 0.411718 +v 0.113671 0.185627 0.411718 +v 0.092190 0.209560 0.411718 +v 0.092190 0.240803 0.411718 +v 0.113671 0.264736 0.411718 +v 0.146582 0.270161 0.411718 +v 0.175523 0.254540 0.411718 +v 0.186952 0.225181 0.481682 +v 0.175523 0.195823 0.481682 +v 0.146582 0.180202 0.481682 +v 0.113671 0.185627 0.481682 +v 0.092190 0.209560 0.481682 +v 0.092190 0.240803 0.481682 +v 0.113671 0.264736 0.481682 +v 0.146582 0.270161 0.481682 +v 0.175523 0.254540 0.481682 +v 0.181818 0.195845 0.385221 +v 0.180061 0.192900 0.377451 +v 0.175663 0.187583 0.375259 +v 0.152587 0.172939 0.375259 +v 0.125311 0.171223 0.375259 +v 0.095551 0.187584 0.375259 +v 0.088921 0.196065 0.375259 +v 0.087818 0.197142 0.375259 +v 0.081092 0.218312 0.375259 +v 0.081092 0.232085 0.375259 +v 0.087424 0.251709 0.375259 +v 0.087858 0.253143 0.375259 +v 0.095551 0.262813 0.375259 +v 0.106164 0.271593 0.375259 +v 0.132157 0.280038 0.375259 +v 0.159003 0.274917 0.375259 +v 0.180061 0.257496 0.375259 +v 0.183759 0.251670 0.375259 +v 0.186697 0.245426 0.375259 +v 0.188829 0.238863 0.378465 +v 0.190122 0.236726 0.381461 +v 0.181818 0.195845 0.420292 +v 0.180061 0.192901 0.423227 +v 0.175663 0.187584 0.427701 +v 0.152587 0.172939 0.427701 +v 0.125311 0.171223 0.427701 +v 0.095551 0.187584 0.427701 +v 0.088921 0.196065 0.419834 +v 0.087818 0.197142 0.404530 +v 0.081092 0.218311 0.404539 +v 0.081092 0.232085 0.404848 +v 0.087424 0.251709 0.404911 +v 0.087858 0.253143 0.420068 +v 0.095551 0.262813 0.427701 +v 0.106164 0.271593 0.427701 +v 0.132157 0.280039 0.427701 +v 0.159003 0.274917 0.427701 +v 0.180062 0.257496 0.427701 +v 0.183759 0.251670 0.405106 +v 0.186697 0.245426 0.398309 +v 0.188829 0.238863 0.391662 +v 0.190122 0.236726 0.387353 +v 0.173771 0.200645 0.385221 +v 0.172676 0.198668 0.377450 +v 0.169586 0.194716 0.375259 +v 0.149692 0.181851 0.375259 +v 0.127355 0.180367 0.375259 +v 0.101524 0.194803 0.375259 +v 0.096052 0.202143 0.375259 +v 0.095793 0.202060 0.375259 +v 0.090351 0.219747 0.375259 +v 0.090348 0.230629 0.375259 +v 0.096368 0.248914 0.375259 +v 0.096157 0.248793 0.375259 +v 0.102240 0.256251 0.375259 +v 0.110678 0.263382 0.375259 +v 0.132745 0.270687 0.375259 +v 0.155014 0.266439 0.375259 +v 0.173033 0.251300 0.375259 +v 0.175548 0.247156 0.375259 +v 0.178020 0.241891 0.375259 +v 0.180106 0.235442 0.378465 +v 0.182105 0.231876 0.381461 +v 0.173771 0.200645 0.420292 +v 0.172584 0.198547 0.423227 +v 0.169715 0.194824 0.427701 +v 0.149692 0.181851 0.427701 +v 0.127355 0.180367 0.427701 +v 0.101230 0.195037 0.427701 +v 0.096537 0.201524 0.419834 +v 0.095378 0.202678 0.404530 +v 0.090353 0.219737 0.404539 +v 0.090346 0.230617 0.404848 +v 0.096376 0.248941 0.404911 +v 0.095287 0.247433 0.420068 +v 0.102095 0.256107 0.427701 +v 0.110678 0.263382 0.427701 +v 0.132745 0.270687 0.427701 +v 0.155014 0.266439 0.427701 +v 0.173735 0.250585 0.427701 +v 0.175712 0.246870 0.405106 +v 0.178094 0.241713 0.398309 +v 0.180049 0.235591 0.391662 +v 0.182105 0.231876 0.387353 +# 3894 vertices, 0 vertices normals + +f 4 3 2 +f 2 1 4 +f 1 2 6 +f 6 5 1 +f 5 6 8 +f 8 7 5 +f 7 8 10 +f 10 9 7 +f 9 10 12 +f 12 11 9 +f 11 12 14 +f 14 13 11 +f 13 14 3 +f 3 4 13 +f 16 15 4 +f 4 1 16 +f 17 16 1 +f 1 5 17 +f 18 17 5 +f 5 7 18 +f 19 18 7 +f 7 9 19 +f 20 19 9 +f 9 11 20 +f 21 20 11 +f 11 13 21 +f 15 21 13 +f 13 4 15 +f 14 10 8 +f 8 6 14 +f 14 12 10 +f 2 3 14 +f 14 6 2 +f 25 24 23 +f 23 22 25 +f 22 23 27 +f 27 26 22 +f 26 27 29 +f 29 28 26 +f 28 29 31 +f 31 30 28 +f 30 31 33 +f 33 32 30 +f 32 33 35 +f 35 34 32 +f 34 35 24 +f 24 25 34 +f 35 31 29 +f 29 27 35 +f 35 33 31 +f 23 24 35 +f 35 27 23 +f 39 38 37 +f 37 36 39 +f 36 37 41 +f 41 40 36 +f 40 41 43 +f 43 42 40 +f 42 43 45 +f 45 44 42 +f 44 45 47 +f 47 46 44 +f 46 47 49 +f 49 48 46 +f 48 49 38 +f 38 39 48 +f 53 52 51 +f 51 50 53 +f 50 51 55 +f 55 54 50 +f 54 55 57 +f 57 56 54 +f 56 57 59 +f 59 58 56 +f 58 59 61 +f 61 60 58 +f 60 61 63 +f 63 62 60 +f 62 63 52 +f 52 53 62 +f 65 53 50 +f 50 64 65 +f 64 50 54 +f 54 66 64 +f 66 54 56 +f 56 67 66 +f 67 56 58 +f 58 68 67 +f 68 58 60 +f 60 69 68 +f 69 60 62 +f 62 70 69 +f 70 62 53 +f 53 65 70 +f 72 65 64 +f 64 71 72 +f 71 64 66 +f 66 73 71 +f 73 66 67 +f 67 74 73 +f 74 67 68 +f 68 75 74 +f 75 68 69 +f 69 76 75 +f 76 69 70 +f 70 77 76 +f 77 70 65 +f 65 72 77 +f 79 72 71 +f 71 78 79 +f 78 71 73 +f 73 80 78 +f 80 73 74 +f 74 81 80 +f 81 74 75 +f 75 82 81 +f 82 75 76 +f 76 83 82 +f 83 76 77 +f 77 84 83 +f 84 77 72 +f 72 79 84 +f 86 85 51 +f 51 52 86 +f 85 87 55 +f 55 51 85 +f 87 88 57 +f 57 55 87 +f 88 89 59 +f 59 57 88 +f 89 90 61 +f 61 59 89 +f 90 91 63 +f 63 61 90 +f 91 86 52 +f 52 63 91 +f 93 92 79 +f 79 78 93 +f 94 93 78 +f 78 80 94 +f 95 94 80 +f 80 81 95 +f 96 95 81 +f 81 82 96 +f 97 96 82 +f 82 83 97 +f 98 97 83 +f 83 84 98 +f 92 98 84 +f 84 79 92 +f 102 101 100 +f 100 99 102 +f 99 100 104 +f 104 103 99 +f 103 104 106 +f 106 105 103 +f 105 106 108 +f 108 107 105 +f 107 108 110 +f 110 109 107 +f 109 110 112 +f 112 111 109 +f 111 112 101 +f 101 102 111 +f 114 102 99 +f 99 113 114 +f 113 99 103 +f 103 115 113 +f 115 103 105 +f 105 116 115 +f 116 105 107 +f 107 117 116 +f 117 107 109 +f 109 118 117 +f 118 109 111 +f 111 119 118 +f 119 111 102 +f 102 114 119 +f 121 114 113 +f 113 120 121 +f 120 113 115 +f 115 122 120 +f 122 115 116 +f 116 123 122 +f 123 116 117 +f 117 124 123 +f 124 117 118 +f 118 125 124 +f 125 118 119 +f 119 126 125 +f 126 119 114 +f 114 121 126 +f 128 121 120 +f 120 127 128 +f 127 120 122 +f 122 129 127 +f 129 122 123 +f 123 130 129 +f 130 123 124 +f 124 131 130 +f 131 124 125 +f 125 132 131 +f 132 125 126 +f 126 133 132 +f 133 126 121 +f 121 128 133 +f 135 134 100 +f 100 101 135 +f 134 136 104 +f 104 100 134 +f 136 137 106 +f 106 104 136 +f 137 138 108 +f 108 106 137 +f 138 139 110 +f 110 108 138 +f 139 140 112 +f 112 110 139 +f 140 135 101 +f 101 112 140 +f 98 92 128 +f 128 127 98 +f 97 98 127 +f 127 129 97 +f 96 97 129 +f 129 130 96 +f 95 96 130 +f 130 131 95 +f 94 95 131 +f 131 132 94 +f 93 94 132 +f 132 133 93 +f 92 93 133 +f 133 128 92 +f 144 143 142 +f 142 141 144 +f 141 142 146 +f 146 145 141 +f 145 146 148 +f 148 147 145 +f 147 148 150 +f 150 149 147 +f 149 150 152 +f 152 151 149 +f 151 152 154 +f 154 153 151 +f 153 154 143 +f 143 144 153 +f 156 144 141 +f 141 155 156 +f 155 141 145 +f 145 157 155 +f 157 145 147 +f 147 158 157 +f 158 147 149 +f 149 159 158 +f 159 149 151 +f 151 160 159 +f 160 151 153 +f 153 161 160 +f 161 153 144 +f 144 156 161 +f 163 156 155 +f 155 162 163 +f 162 155 157 +f 157 164 162 +f 164 157 158 +f 158 165 164 +f 165 158 159 +f 159 166 165 +f 166 159 160 +f 160 167 166 +f 167 160 161 +f 161 168 167 +f 168 161 156 +f 156 163 168 +f 170 163 162 +f 162 169 170 +f 169 162 164 +f 164 171 169 +f 171 164 165 +f 165 172 171 +f 172 165 166 +f 166 173 172 +f 173 166 167 +f 167 174 173 +f 174 167 168 +f 168 175 174 +f 175 168 163 +f 163 170 175 +f 177 176 142 +f 142 143 177 +f 176 178 146 +f 146 142 176 +f 178 179 148 +f 148 146 178 +f 179 180 150 +f 150 148 179 +f 180 181 152 +f 152 150 180 +f 181 182 154 +f 154 152 181 +f 182 177 143 +f 143 154 182 +f 186 185 184 +f 184 183 186 +f 183 184 188 +f 188 187 183 +f 187 188 190 +f 190 189 187 +f 189 190 192 +f 192 191 189 +f 191 192 194 +f 194 193 191 +f 193 194 196 +f 196 195 193 +f 195 196 185 +f 185 186 195 +f 198 186 183 +f 183 197 198 +f 197 183 187 +f 187 199 197 +f 199 187 189 +f 189 200 199 +f 200 189 191 +f 191 201 200 +f 201 191 193 +f 193 202 201 +f 202 193 195 +f 195 203 202 +f 203 195 186 +f 186 198 203 +f 205 198 197 +f 197 204 205 +f 204 197 199 +f 199 206 204 +f 206 199 200 +f 200 207 206 +f 207 200 201 +f 201 208 207 +f 208 201 202 +f 202 209 208 +f 209 202 203 +f 203 210 209 +f 210 203 198 +f 198 205 210 +f 212 205 204 +f 204 211 212 +f 211 204 206 +f 206 213 211 +f 213 206 207 +f 207 214 213 +f 214 207 208 +f 208 215 214 +f 215 208 209 +f 209 216 215 +f 216 209 210 +f 210 217 216 +f 217 210 205 +f 205 212 217 +f 219 218 184 +f 184 185 219 +f 218 220 188 +f 188 184 218 +f 220 221 190 +f 190 188 220 +f 221 222 192 +f 192 190 221 +f 222 223 194 +f 194 192 222 +f 223 224 196 +f 196 194 223 +f 224 219 185 +f 185 196 224 +f 175 170 212 +f 212 211 175 +f 174 175 211 +f 211 213 174 +f 173 174 213 +f 213 214 173 +f 172 173 214 +f 214 215 172 +f 171 172 215 +f 215 216 171 +f 169 171 216 +f 216 217 169 +f 170 169 217 +f 217 212 170 +f 228 227 226 +f 226 225 228 +f 230 228 225 +f 225 229 230 +f 232 230 229 +f 229 231 232 +f 234 232 231 +f 231 233 234 +f 236 234 233 +f 233 235 236 +f 238 236 235 +f 235 237 238 +f 227 238 237 +f 237 226 227 +f 225 226 240 +f 240 239 225 +f 229 225 239 +f 239 241 229 +f 231 229 241 +f 241 242 231 +f 233 231 242 +f 242 243 233 +f 235 233 243 +f 243 244 235 +f 237 235 244 +f 244 245 237 +f 226 237 245 +f 245 240 226 +f 239 240 247 +f 247 246 239 +f 241 239 246 +f 246 248 241 +f 242 241 248 +f 248 249 242 +f 243 242 249 +f 249 250 243 +f 244 243 250 +f 250 251 244 +f 245 244 251 +f 251 252 245 +f 240 245 252 +f 252 247 240 +f 246 247 254 +f 254 253 246 +f 248 246 253 +f 253 255 248 +f 249 248 255 +f 255 256 249 +f 250 249 256 +f 256 257 250 +f 251 250 257 +f 257 258 251 +f 252 251 258 +f 258 259 252 +f 247 252 259 +f 259 254 247 +f 228 261 260 +f 260 227 228 +f 230 262 261 +f 261 228 230 +f 232 263 262 +f 262 230 232 +f 234 264 263 +f 263 232 234 +f 236 265 264 +f 264 234 236 +f 238 266 265 +f 265 236 238 +f 227 260 266 +f 266 238 227 +f 254 268 267 +f 267 253 254 +f 253 267 269 +f 269 255 253 +f 255 269 270 +f 270 256 255 +f 256 270 271 +f 271 257 256 +f 257 271 272 +f 272 258 257 +f 258 272 273 +f 273 259 258 +f 259 273 268 +f 268 254 259 +f 277 276 275 +f 275 274 277 +f 279 277 274 +f 274 278 279 +f 281 279 278 +f 278 280 281 +f 283 281 280 +f 280 282 283 +f 285 283 282 +f 282 284 285 +f 287 285 284 +f 284 286 287 +f 276 287 286 +f 286 275 276 +f 274 275 289 +f 289 288 274 +f 278 274 288 +f 288 290 278 +f 280 278 290 +f 290 291 280 +f 282 280 291 +f 291 292 282 +f 284 282 292 +f 292 293 284 +f 286 284 293 +f 293 294 286 +f 275 286 294 +f 294 289 275 +f 288 289 296 +f 296 295 288 +f 290 288 295 +f 295 297 290 +f 291 290 297 +f 297 298 291 +f 292 291 298 +f 298 299 292 +f 293 292 299 +f 299 300 293 +f 294 293 300 +f 300 301 294 +f 289 294 301 +f 301 296 289 +f 295 296 303 +f 303 302 295 +f 297 295 302 +f 302 304 297 +f 298 297 304 +f 304 305 298 +f 299 298 305 +f 305 306 299 +f 300 299 306 +f 306 307 300 +f 301 300 307 +f 307 308 301 +f 296 301 308 +f 308 303 296 +f 277 310 309 +f 309 276 277 +f 279 311 310 +f 310 277 279 +f 281 312 311 +f 311 279 281 +f 283 313 312 +f 312 281 283 +f 285 314 313 +f 313 283 285 +f 287 315 314 +f 314 285 287 +f 276 309 315 +f 315 287 276 +f 303 268 273 +f 273 302 303 +f 302 273 272 +f 272 304 302 +f 304 272 271 +f 271 305 304 +f 305 271 270 +f 270 306 305 +f 306 270 269 +f 269 307 306 +f 307 269 267 +f 267 308 307 +f 308 267 268 +f 268 303 308 +f 319 318 317 +f 317 316 319 +f 321 320 318 +f 318 319 321 +f 323 322 320 +f 320 321 323 +f 325 324 322 +f 322 323 325 +f 327 326 324 +f 324 325 327 +f 316 317 326 +f 326 327 316 +f 325 321 319 +f 319 316 325 +f 325 323 321 +f 325 316 327 +f 318 322 324 +f 324 326 318 +f 318 320 322 +f 318 326 317 +f 331 330 329 +f 329 328 331 +f 333 332 330 +f 330 331 333 +f 335 334 332 +f 332 333 335 +f 337 336 334 +f 334 335 337 +f 339 338 336 +f 336 337 339 +f 328 329 338 +f 338 339 328 +f 337 333 331 +f 331 328 337 +f 337 335 333 +f 337 328 339 +f 330 334 336 +f 336 338 330 +f 330 332 334 +f 330 338 329 +f 343 342 341 +f 341 340 343 +f 345 343 340 +f 340 344 345 +f 347 345 344 +f 344 346 347 +f 349 347 346 +f 346 348 349 +f 351 349 348 +f 348 350 351 +f 353 351 350 +f 350 352 353 +f 342 353 352 +f 352 341 342 +f 340 341 355 +f 355 354 340 +f 344 340 354 +f 354 356 344 +f 346 344 356 +f 356 357 346 +f 348 346 357 +f 357 358 348 +f 350 348 358 +f 358 359 350 +f 352 350 359 +f 359 360 352 +f 341 352 360 +f 360 355 341 +f 354 355 362 +f 362 361 354 +f 356 354 361 +f 361 363 356 +f 357 356 363 +f 363 364 357 +f 358 357 364 +f 364 365 358 +f 359 358 365 +f 365 366 359 +f 360 359 366 +f 366 367 360 +f 355 360 367 +f 367 362 355 +f 361 362 369 +f 369 368 361 +f 363 361 368 +f 368 370 363 +f 364 363 370 +f 370 371 364 +f 365 364 371 +f 371 372 365 +f 366 365 372 +f 372 373 366 +f 367 366 373 +f 373 374 367 +f 362 367 374 +f 374 369 362 +f 368 369 376 +f 376 375 368 +f 370 368 375 +f 375 377 370 +f 371 370 377 +f 377 378 371 +f 372 371 378 +f 378 379 372 +f 373 372 379 +f 379 380 373 +f 374 373 380 +f 380 381 374 +f 369 374 381 +f 381 376 369 +f 375 376 383 +f 383 382 375 +f 377 375 382 +f 382 384 377 +f 378 377 384 +f 384 385 378 +f 379 378 385 +f 385 386 379 +f 380 379 386 +f 386 387 380 +f 381 380 387 +f 387 388 381 +f 376 381 388 +f 388 383 376 +f 382 383 390 +f 390 389 382 +f 384 382 389 +f 389 391 384 +f 385 384 391 +f 391 392 385 +f 386 385 392 +f 392 393 386 +f 387 386 393 +f 393 394 387 +f 388 387 394 +f 394 395 388 +f 383 388 395 +f 395 390 383 +f 389 390 397 +f 397 396 389 +f 391 389 396 +f 396 398 391 +f 392 391 398 +f 398 399 392 +f 393 392 399 +f 399 400 393 +f 394 393 400 +f 400 401 394 +f 395 394 401 +f 401 402 395 +f 390 395 402 +f 402 397 390 +f 343 404 403 +f 403 342 343 +f 345 405 404 +f 404 343 345 +f 347 406 405 +f 405 345 347 +f 349 407 406 +f 406 347 349 +f 351 408 407 +f 407 349 351 +f 353 409 408 +f 408 351 353 +f 342 403 409 +f 409 353 342 +f 397 411 410 +f 410 396 397 +f 396 410 412 +f 412 398 396 +f 398 412 413 +f 413 399 398 +f 399 413 414 +f 414 400 399 +f 400 414 415 +f 415 401 400 +f 401 415 416 +f 416 402 401 +f 402 416 411 +f 411 397 402 +f 420 419 418 +f 418 417 420 +f 422 420 417 +f 417 421 422 +f 424 422 421 +f 421 423 424 +f 426 424 423 +f 423 425 426 +f 428 426 425 +f 425 427 428 +f 430 428 427 +f 427 429 430 +f 419 430 429 +f 429 418 419 +f 417 418 432 +f 432 431 417 +f 421 417 431 +f 431 433 421 +f 423 421 433 +f 433 434 423 +f 425 423 434 +f 434 435 425 +f 427 425 435 +f 435 436 427 +f 429 427 436 +f 436 437 429 +f 418 429 437 +f 437 432 418 +f 431 432 439 +f 439 438 431 +f 433 431 438 +f 438 440 433 +f 434 433 440 +f 440 441 434 +f 435 434 441 +f 441 442 435 +f 436 435 442 +f 442 443 436 +f 437 436 443 +f 443 444 437 +f 432 437 444 +f 444 439 432 +f 438 439 446 +f 446 445 438 +f 440 438 445 +f 445 447 440 +f 441 440 447 +f 447 448 441 +f 442 441 448 +f 448 449 442 +f 443 442 449 +f 449 450 443 +f 444 443 450 +f 450 451 444 +f 439 444 451 +f 451 446 439 +f 420 453 452 +f 452 419 420 +f 422 454 453 +f 453 420 422 +f 424 455 454 +f 454 422 424 +f 426 456 455 +f 455 424 426 +f 428 457 456 +f 456 426 428 +f 430 458 457 +f 457 428 430 +f 419 452 458 +f 458 430 419 +f 462 461 460 +f 460 459 462 +f 464 462 459 +f 459 463 464 +f 466 464 463 +f 463 465 466 +f 468 466 465 +f 465 467 468 +f 470 468 467 +f 467 469 470 +f 472 470 469 +f 469 471 472 +f 461 472 471 +f 471 460 461 +f 459 460 474 +f 474 473 459 +f 463 459 473 +f 473 475 463 +f 465 463 475 +f 475 476 465 +f 467 465 476 +f 476 477 467 +f 469 467 477 +f 477 478 469 +f 471 469 478 +f 478 479 471 +f 460 471 479 +f 479 474 460 +f 473 474 481 +f 481 480 473 +f 475 473 480 +f 480 482 475 +f 476 475 482 +f 482 483 476 +f 477 476 483 +f 483 484 477 +f 478 477 484 +f 484 485 478 +f 479 478 485 +f 485 486 479 +f 474 479 486 +f 486 481 474 +f 480 481 488 +f 488 487 480 +f 482 480 487 +f 487 489 482 +f 483 482 489 +f 489 490 483 +f 484 483 490 +f 490 491 484 +f 485 484 491 +f 491 492 485 +f 486 485 492 +f 492 493 486 +f 481 486 493 +f 493 488 481 +f 462 495 494 +f 494 461 462 +f 464 496 495 +f 495 462 464 +f 466 497 496 +f 496 464 466 +f 468 498 497 +f 497 466 468 +f 470 499 498 +f 498 468 470 +f 472 500 499 +f 499 470 472 +f 461 494 500 +f 500 472 461 +f 488 446 451 +f 451 487 488 +f 487 451 450 +f 450 489 487 +f 489 450 449 +f 449 490 489 +f 490 449 448 +f 448 491 490 +f 491 448 447 +f 447 492 491 +f 492 447 445 +f 445 493 492 +f 493 445 446 +f 446 488 493 +f 504 503 502 +f 502 501 504 +f 506 504 501 +f 501 505 506 +f 508 506 505 +f 505 507 508 +f 510 508 507 +f 507 509 510 +f 512 510 509 +f 509 511 512 +f 514 512 511 +f 511 513 514 +f 503 514 513 +f 513 502 503 +f 501 502 516 +f 516 515 501 +f 505 501 515 +f 515 517 505 +f 507 505 517 +f 517 518 507 +f 509 507 518 +f 518 519 509 +f 511 509 519 +f 519 520 511 +f 513 511 520 +f 520 521 513 +f 502 513 521 +f 521 516 502 +f 515 516 523 +f 523 522 515 +f 517 515 522 +f 522 524 517 +f 518 517 524 +f 524 525 518 +f 519 518 525 +f 525 526 519 +f 520 519 526 +f 526 527 520 +f 521 520 527 +f 527 528 521 +f 516 521 528 +f 528 523 516 +f 522 523 530 +f 530 529 522 +f 524 522 529 +f 529 531 524 +f 525 524 531 +f 531 532 525 +f 526 525 532 +f 532 533 526 +f 527 526 533 +f 533 534 527 +f 528 527 534 +f 534 535 528 +f 523 528 535 +f 535 530 523 +f 539 538 537 +f 537 536 539 +f 541 539 536 +f 536 540 541 +f 543 541 540 +f 540 542 543 +f 545 543 542 +f 542 544 545 +f 547 545 544 +f 544 546 547 +f 549 547 546 +f 546 548 549 +f 538 549 548 +f 548 537 538 +f 536 537 551 +f 551 550 536 +f 540 536 550 +f 550 552 540 +f 542 540 552 +f 552 553 542 +f 544 542 553 +f 553 554 544 +f 546 544 554 +f 554 555 546 +f 548 546 555 +f 555 556 548 +f 537 548 556 +f 556 551 537 +f 550 551 558 +f 558 557 550 +f 552 550 557 +f 557 559 552 +f 553 552 559 +f 559 560 553 +f 554 553 560 +f 560 561 554 +f 555 554 561 +f 561 562 555 +f 556 555 562 +f 562 563 556 +f 551 556 563 +f 563 558 551 +f 557 558 565 +f 565 564 557 +f 559 557 564 +f 564 566 559 +f 560 559 566 +f 566 567 560 +f 561 560 567 +f 567 568 561 +f 562 561 568 +f 568 569 562 +f 563 562 569 +f 569 570 563 +f 558 563 570 +f 570 565 558 +f 539 510 512 +f 512 538 539 +f 541 508 510 +f 510 539 541 +f 543 506 508 +f 508 541 543 +f 545 504 506 +f 506 543 545 +f 547 503 504 +f 504 545 547 +f 549 514 503 +f 503 547 549 +f 538 512 514 +f 514 549 538 +f 574 573 572 +f 572 571 574 +f 571 572 576 +f 576 575 571 +f 575 576 578 +f 578 577 575 +f 577 578 580 +f 580 579 577 +f 579 580 582 +f 582 581 579 +f 581 582 584 +f 584 583 581 +f 583 584 573 +f 573 574 583 +f 586 574 571 +f 571 585 586 +f 585 571 575 +f 575 587 585 +f 587 575 577 +f 577 588 587 +f 588 577 579 +f 579 589 588 +f 589 579 581 +f 581 590 589 +f 590 581 583 +f 583 591 590 +f 591 583 574 +f 574 586 591 +f 593 586 585 +f 585 592 593 +f 592 585 587 +f 587 594 592 +f 594 587 588 +f 588 595 594 +f 595 588 589 +f 589 596 595 +f 596 589 590 +f 590 597 596 +f 597 590 591 +f 591 598 597 +f 598 591 586 +f 586 593 598 +f 600 593 592 +f 592 599 600 +f 599 592 594 +f 594 601 599 +f 601 594 595 +f 595 602 601 +f 602 595 596 +f 596 603 602 +f 603 596 597 +f 597 604 603 +f 604 597 598 +f 598 605 604 +f 605 598 593 +f 593 600 605 +f 609 608 607 +f 607 606 609 +f 606 607 611 +f 611 610 606 +f 610 611 613 +f 613 612 610 +f 612 613 615 +f 615 614 612 +f 614 615 617 +f 617 616 614 +f 616 617 619 +f 619 618 616 +f 618 619 608 +f 608 609 618 +f 621 609 606 +f 606 620 621 +f 620 606 610 +f 610 622 620 +f 622 610 612 +f 612 623 622 +f 623 612 614 +f 614 624 623 +f 624 614 616 +f 616 625 624 +f 625 616 618 +f 618 626 625 +f 626 618 609 +f 609 621 626 +f 628 621 620 +f 620 627 628 +f 627 620 622 +f 622 629 627 +f 629 622 623 +f 623 630 629 +f 630 623 624 +f 624 631 630 +f 631 624 625 +f 625 632 631 +f 632 625 626 +f 626 633 632 +f 633 626 621 +f 621 628 633 +f 565 628 627 +f 627 564 565 +f 564 627 629 +f 629 566 564 +f 566 629 630 +f 630 567 566 +f 567 630 631 +f 631 568 567 +f 568 631 632 +f 632 569 568 +f 569 632 633 +f 633 570 569 +f 570 633 628 +f 628 565 570 +f 582 580 607 +f 607 608 582 +f 580 578 611 +f 611 607 580 +f 578 576 613 +f 613 611 578 +f 576 572 615 +f 615 613 576 +f 572 573 617 +f 617 615 572 +f 573 584 619 +f 619 617 573 +f 584 582 608 +f 608 619 584 +f 637 636 635 +f 635 634 637 +f 634 635 639 +f 639 638 634 +f 638 639 641 +f 641 640 638 +f 640 641 643 +f 643 642 640 +f 642 643 645 +f 645 644 642 +f 644 645 647 +f 647 646 644 +f 646 647 636 +f 636 637 646 +f 649 637 634 +f 634 648 649 +f 648 634 638 +f 638 650 648 +f 650 638 640 +f 640 651 650 +f 651 640 642 +f 642 652 651 +f 652 642 644 +f 644 653 652 +f 653 644 646 +f 646 654 653 +f 654 646 637 +f 637 649 654 +f 656 649 648 +f 648 655 656 +f 655 648 650 +f 650 657 655 +f 657 650 651 +f 651 658 657 +f 658 651 652 +f 652 659 658 +f 659 652 653 +f 653 660 659 +f 660 653 654 +f 654 661 660 +f 661 654 649 +f 649 656 661 +f 663 656 655 +f 655 662 663 +f 662 655 657 +f 657 664 662 +f 664 657 658 +f 658 665 664 +f 665 658 659 +f 659 666 665 +f 666 659 660 +f 660 667 666 +f 667 660 661 +f 661 668 667 +f 668 661 656 +f 656 663 668 +f 672 671 670 +f 670 669 672 +f 669 670 674 +f 674 673 669 +f 673 674 676 +f 676 675 673 +f 675 676 678 +f 678 677 675 +f 677 678 680 +f 680 679 677 +f 679 680 682 +f 682 681 679 +f 681 682 671 +f 671 672 681 +f 684 672 669 +f 669 683 684 +f 683 669 673 +f 673 685 683 +f 685 673 675 +f 675 686 685 +f 686 675 677 +f 677 687 686 +f 687 677 679 +f 679 688 687 +f 688 679 681 +f 681 689 688 +f 689 681 672 +f 672 684 689 +f 691 684 683 +f 683 690 691 +f 690 683 685 +f 685 692 690 +f 692 685 686 +f 686 693 692 +f 693 686 687 +f 687 694 693 +f 694 687 688 +f 688 695 694 +f 695 688 689 +f 689 696 695 +f 696 689 684 +f 684 691 696 +f 698 691 690 +f 690 697 698 +f 697 690 692 +f 692 699 697 +f 699 692 693 +f 693 700 699 +f 700 693 694 +f 694 701 700 +f 701 694 695 +f 695 702 701 +f 702 695 696 +f 696 703 702 +f 703 696 691 +f 691 698 703 +f 645 643 670 +f 670 671 645 +f 643 641 674 +f 674 670 643 +f 641 639 676 +f 676 674 641 +f 639 635 678 +f 678 676 639 +f 635 636 680 +f 680 678 635 +f 636 647 682 +f 682 680 636 +f 647 645 671 +f 671 682 647 +f 529 530 663 +f 663 662 529 +f 531 529 662 +f 662 664 531 +f 532 531 664 +f 664 665 532 +f 533 532 665 +f 665 666 533 +f 534 533 666 +f 666 667 534 +f 535 534 667 +f 667 668 535 +f 530 535 668 +f 668 663 530 +f 707 706 705 +f 705 704 707 +f 709 707 704 +f 704 708 709 +f 711 709 708 +f 708 710 711 +f 713 711 710 +f 710 712 713 +f 715 713 712 +f 712 714 715 +f 717 715 714 +f 714 716 717 +f 706 717 716 +f 716 705 706 +f 704 705 719 +f 719 718 704 +f 708 704 718 +f 718 720 708 +f 710 708 720 +f 720 721 710 +f 712 710 721 +f 721 722 712 +f 714 712 722 +f 722 723 714 +f 716 714 723 +f 723 724 716 +f 705 716 724 +f 724 719 705 +f 718 719 726 +f 726 725 718 +f 720 718 725 +f 725 727 720 +f 721 720 727 +f 727 728 721 +f 722 721 728 +f 728 729 722 +f 723 722 729 +f 729 730 723 +f 724 723 730 +f 730 731 724 +f 719 724 731 +f 731 726 719 +f 725 726 733 +f 733 732 725 +f 727 725 732 +f 732 734 727 +f 728 727 734 +f 734 735 728 +f 729 728 735 +f 735 736 729 +f 730 729 736 +f 736 737 730 +f 731 730 737 +f 737 738 731 +f 726 731 738 +f 738 733 726 +f 742 741 740 +f 740 739 742 +f 744 742 739 +f 739 743 744 +f 746 744 743 +f 743 745 746 +f 748 746 745 +f 745 747 748 +f 750 748 747 +f 747 749 750 +f 752 750 749 +f 749 751 752 +f 741 752 751 +f 751 740 741 +f 739 740 754 +f 754 753 739 +f 743 739 753 +f 753 755 743 +f 745 743 755 +f 755 756 745 +f 747 745 756 +f 756 757 747 +f 749 747 757 +f 757 758 749 +f 751 749 758 +f 758 759 751 +f 740 751 759 +f 759 754 740 +f 753 754 761 +f 761 760 753 +f 755 753 760 +f 760 762 755 +f 756 755 762 +f 762 763 756 +f 757 756 763 +f 763 764 757 +f 758 757 764 +f 764 765 758 +f 759 758 765 +f 765 766 759 +f 754 759 766 +f 766 761 754 +f 760 761 698 +f 698 697 760 +f 762 760 697 +f 697 699 762 +f 763 762 699 +f 699 700 763 +f 764 763 700 +f 700 701 764 +f 765 764 701 +f 701 702 765 +f 766 765 702 +f 702 703 766 +f 761 766 703 +f 703 698 761 +f 742 713 715 +f 715 741 742 +f 744 711 713 +f 713 742 744 +f 746 709 711 +f 711 744 746 +f 748 707 709 +f 709 746 748 +f 750 706 707 +f 707 748 750 +f 752 717 706 +f 706 750 752 +f 741 715 717 +f 717 752 741 +f 733 600 599 +f 599 732 733 +f 732 599 601 +f 601 734 732 +f 734 601 602 +f 602 735 734 +f 735 602 603 +f 603 736 735 +f 736 603 604 +f 604 737 736 +f 737 604 605 +f 605 738 737 +f 738 605 600 +f 600 733 738 +f 770 769 768 +f 768 767 770 +f 767 768 772 +f 772 771 767 +f 771 772 774 +f 774 773 771 +f 773 774 776 +f 776 775 773 +f 775 776 778 +f 778 777 775 +f 777 778 780 +f 780 779 777 +f 779 780 769 +f 769 770 779 +f 782 770 767 +f 767 781 782 +f 781 767 771 +f 771 783 781 +f 783 771 773 +f 773 784 783 +f 784 773 775 +f 775 785 784 +f 785 775 777 +f 777 786 785 +f 786 777 779 +f 779 787 786 +f 787 779 770 +f 770 782 787 +f 789 782 781 +f 781 788 789 +f 788 781 783 +f 783 790 788 +f 790 783 784 +f 784 791 790 +f 791 784 785 +f 785 792 791 +f 792 785 786 +f 786 793 792 +f 793 786 787 +f 787 794 793 +f 794 787 782 +f 782 789 794 +f 796 795 789 +f 789 788 796 +f 797 796 788 +f 788 790 797 +f 798 797 790 +f 790 791 798 +f 799 798 791 +f 791 792 799 +f 800 799 792 +f 792 793 800 +f 801 800 793 +f 793 794 801 +f 795 801 794 +f 794 789 795 +f 803 802 768 +f 768 769 803 +f 802 804 772 +f 772 768 802 +f 804 805 774 +f 774 772 804 +f 805 806 776 +f 776 774 805 +f 806 807 778 +f 778 776 806 +f 807 808 780 +f 780 778 807 +f 808 803 769 +f 769 780 808 +f 812 811 810 +f 810 809 812 +f 814 812 809 +f 809 813 814 +f 816 814 813 +f 813 815 816 +f 818 816 815 +f 815 817 818 +f 820 818 817 +f 817 819 820 +f 822 820 819 +f 819 821 822 +f 811 822 821 +f 821 810 811 +f 809 810 824 +f 824 823 809 +f 813 809 823 +f 823 825 813 +f 815 813 825 +f 825 826 815 +f 817 815 826 +f 826 827 817 +f 819 817 827 +f 827 828 819 +f 821 819 828 +f 828 829 821 +f 810 821 829 +f 829 824 810 +f 823 824 795 +f 795 796 823 +f 825 823 796 +f 796 797 825 +f 826 825 797 +f 797 798 826 +f 827 826 798 +f 798 799 827 +f 828 827 799 +f 799 800 828 +f 829 828 800 +f 800 801 829 +f 824 829 801 +f 801 795 824 +f 812 831 830 +f 830 811 812 +f 814 832 831 +f 831 812 814 +f 816 833 832 +f 832 814 816 +f 818 834 833 +f 833 816 818 +f 820 835 834 +f 834 818 820 +f 822 836 835 +f 835 820 822 +f 811 830 836 +f 836 822 811 +f 840 839 838 +f 838 837 840 +f 837 838 842 +f 842 841 837 +f 841 842 844 +f 844 843 841 +f 843 844 846 +f 846 845 843 +f 845 846 848 +f 848 847 845 +f 847 848 850 +f 850 849 847 +f 849 850 839 +f 839 840 849 +f 852 840 837 +f 837 851 852 +f 851 837 841 +f 841 853 851 +f 853 841 843 +f 843 854 853 +f 854 843 845 +f 845 855 854 +f 855 845 847 +f 847 856 855 +f 856 847 849 +f 849 857 856 +f 857 849 840 +f 840 852 857 +f 859 852 851 +f 851 858 859 +f 858 851 853 +f 853 860 858 +f 860 853 854 +f 854 861 860 +f 861 854 855 +f 855 862 861 +f 862 855 856 +f 856 863 862 +f 863 856 857 +f 857 864 863 +f 864 857 852 +f 852 859 864 +f 866 865 859 +f 859 858 866 +f 867 866 858 +f 858 860 867 +f 868 867 860 +f 860 861 868 +f 869 868 861 +f 861 862 869 +f 870 869 862 +f 862 863 870 +f 871 870 863 +f 863 864 871 +f 865 871 864 +f 864 859 865 +f 873 872 838 +f 838 839 873 +f 872 874 842 +f 842 838 872 +f 874 875 844 +f 844 842 874 +f 875 876 846 +f 846 844 875 +f 876 877 848 +f 848 846 876 +f 877 878 850 +f 850 848 877 +f 878 873 839 +f 839 850 878 +f 882 881 880 +f 880 879 882 +f 884 882 879 +f 879 883 884 +f 886 884 883 +f 883 885 886 +f 888 886 885 +f 885 887 888 +f 890 888 887 +f 887 889 890 +f 892 890 889 +f 889 891 892 +f 881 892 891 +f 891 880 881 +f 879 880 894 +f 894 893 879 +f 883 879 893 +f 893 895 883 +f 885 883 895 +f 895 896 885 +f 887 885 896 +f 896 897 887 +f 889 887 897 +f 897 898 889 +f 891 889 898 +f 898 899 891 +f 880 891 899 +f 899 894 880 +f 893 894 865 +f 865 866 893 +f 895 893 866 +f 866 867 895 +f 896 895 867 +f 867 868 896 +f 897 896 868 +f 868 869 897 +f 898 897 869 +f 869 870 898 +f 899 898 870 +f 870 871 899 +f 894 899 871 +f 871 865 894 +f 882 901 900 +f 900 881 882 +f 884 902 901 +f 901 882 884 +f 886 903 902 +f 902 884 886 +f 888 904 903 +f 903 886 888 +f 890 905 904 +f 904 888 890 +f 892 906 905 +f 905 890 892 +f 881 900 906 +f 906 892 881 +f 910 909 908 +f 908 907 910 +f 912 910 907 +f 907 911 912 +f 914 912 911 +f 911 913 914 +f 916 914 913 +f 913 915 916 +f 918 916 915 +f 915 917 918 +f 920 918 917 +f 917 919 920 +f 909 920 919 +f 919 908 909 +f 907 908 922 +f 922 921 907 +f 911 907 921 +f 921 923 911 +f 913 911 923 +f 923 924 913 +f 915 913 924 +f 924 925 915 +f 917 915 925 +f 925 926 917 +f 919 917 926 +f 926 927 919 +f 908 919 927 +f 927 922 908 +f 921 922 929 +f 929 928 921 +f 923 921 928 +f 928 930 923 +f 924 923 930 +f 930 931 924 +f 925 924 931 +f 931 932 925 +f 926 925 932 +f 932 933 926 +f 927 926 933 +f 933 934 927 +f 922 927 934 +f 934 929 922 +f 928 929 936 +f 936 935 928 +f 930 928 935 +f 935 937 930 +f 931 930 937 +f 937 938 931 +f 932 931 938 +f 938 939 932 +f 933 932 939 +f 939 940 933 +f 934 933 940 +f 940 941 934 +f 929 934 941 +f 941 936 929 +f 910 943 942 +f 942 909 910 +f 912 944 943 +f 943 910 912 +f 914 945 944 +f 944 912 914 +f 916 946 945 +f 945 914 916 +f 918 947 946 +f 946 916 918 +f 920 948 947 +f 947 918 920 +f 909 942 948 +f 948 920 909 +f 936 950 949 +f 949 935 936 +f 935 949 951 +f 951 937 935 +f 937 951 952 +f 952 938 937 +f 938 952 953 +f 953 939 938 +f 939 953 954 +f 954 940 939 +f 940 954 955 +f 955 941 940 +f 941 955 950 +f 950 936 941 +f 959 958 957 +f 957 956 959 +f 961 959 956 +f 956 960 961 +f 963 961 960 +f 960 962 963 +f 965 963 962 +f 962 964 965 +f 967 965 964 +f 964 966 967 +f 969 967 966 +f 966 968 969 +f 958 969 968 +f 968 957 958 +f 956 957 971 +f 971 970 956 +f 960 956 970 +f 970 972 960 +f 962 960 972 +f 972 973 962 +f 964 962 973 +f 973 974 964 +f 966 964 974 +f 974 975 966 +f 968 966 975 +f 975 976 968 +f 957 968 976 +f 976 971 957 +f 970 971 978 +f 978 977 970 +f 972 970 977 +f 977 979 972 +f 973 972 979 +f 979 980 973 +f 974 973 980 +f 980 981 974 +f 975 974 981 +f 981 982 975 +f 976 975 982 +f 982 983 976 +f 971 976 983 +f 983 978 971 +f 977 978 985 +f 985 984 977 +f 979 977 984 +f 984 986 979 +f 980 979 986 +f 986 987 980 +f 981 980 987 +f 987 988 981 +f 982 981 988 +f 988 989 982 +f 983 982 989 +f 989 990 983 +f 978 983 990 +f 990 985 978 +f 985 992 991 +f 991 984 985 +f 984 991 993 +f 993 986 984 +f 986 993 994 +f 994 987 986 +f 987 994 995 +f 995 988 987 +f 988 995 996 +f 996 989 988 +f 989 996 997 +f 997 990 989 +f 990 997 992 +f 992 985 990 +f 1001 1000 999 +f 999 998 1001 +f 1003 1001 998 +f 998 1002 1003 +f 1005 1003 1002 +f 1002 1004 1005 +f 1007 1005 1004 +f 1004 1006 1007 +f 1009 1007 1006 +f 1006 1008 1009 +f 1011 1009 1008 +f 1008 1010 1011 +f 1000 1011 1010 +f 1010 999 1000 +f 998 999 1013 +f 1013 1012 998 +f 1002 998 1012 +f 1012 1014 1002 +f 1004 1002 1014 +f 1014 1015 1004 +f 1006 1004 1015 +f 1015 1016 1006 +f 1008 1006 1016 +f 1016 1017 1008 +f 1010 1008 1017 +f 1017 1018 1010 +f 999 1010 1018 +f 1018 1013 999 +f 1012 1013 1020 +f 1020 1019 1012 +f 1014 1012 1019 +f 1019 1021 1014 +f 1015 1014 1021 +f 1021 1022 1015 +f 1016 1015 1022 +f 1022 1023 1016 +f 1017 1016 1023 +f 1023 1024 1017 +f 1018 1017 1024 +f 1024 1025 1018 +f 1013 1018 1025 +f 1025 1020 1013 +f 1019 1020 1027 +f 1027 1026 1019 +f 1021 1019 1026 +f 1026 1028 1021 +f 1022 1021 1028 +f 1028 1029 1022 +f 1023 1022 1029 +f 1029 1030 1023 +f 1024 1023 1030 +f 1030 1031 1024 +f 1025 1024 1031 +f 1031 1032 1025 +f 1020 1025 1032 +f 1032 1027 1020 +f 1001 969 958 +f 958 1000 1001 +f 1003 967 969 +f 969 1001 1003 +f 1005 965 967 +f 967 1003 1005 +f 1007 963 965 +f 965 1005 1007 +f 1009 961 963 +f 963 1007 1009 +f 1011 959 961 +f 961 1009 1011 +f 1000 958 959 +f 959 1011 1000 +f 1027 1034 1033 +f 1033 1026 1027 +f 1026 1033 1035 +f 1035 1028 1026 +f 1028 1035 1036 +f 1036 1029 1028 +f 1029 1036 1037 +f 1037 1030 1029 +f 1030 1037 1038 +f 1038 1031 1030 +f 1031 1038 1039 +f 1039 1032 1031 +f 1032 1039 1034 +f 1034 1027 1032 +f 1043 1042 1041 +f 1041 1040 1043 +f 1045 1043 1040 +f 1040 1044 1045 +f 1047 1045 1044 +f 1044 1046 1047 +f 1049 1047 1046 +f 1046 1048 1049 +f 1051 1049 1048 +f 1048 1050 1051 +f 1053 1051 1050 +f 1050 1052 1053 +f 1042 1053 1052 +f 1052 1041 1042 +f 1040 1041 1055 +f 1055 1054 1040 +f 1044 1040 1054 +f 1054 1056 1044 +f 1046 1044 1056 +f 1056 1057 1046 +f 1048 1046 1057 +f 1057 1058 1048 +f 1050 1048 1058 +f 1058 1059 1050 +f 1052 1050 1059 +f 1059 1060 1052 +f 1041 1052 1060 +f 1060 1055 1041 +f 1054 1055 1062 +f 1062 1061 1054 +f 1056 1054 1061 +f 1061 1063 1056 +f 1057 1056 1063 +f 1063 1064 1057 +f 1058 1057 1064 +f 1064 1065 1058 +f 1059 1058 1065 +f 1065 1066 1059 +f 1060 1059 1066 +f 1066 1067 1060 +f 1055 1060 1067 +f 1067 1062 1055 +f 1061 1062 1069 +f 1069 1068 1061 +f 1063 1061 1068 +f 1068 1070 1063 +f 1064 1063 1070 +f 1070 1071 1064 +f 1065 1064 1071 +f 1071 1072 1065 +f 1066 1065 1072 +f 1072 1073 1066 +f 1067 1066 1073 +f 1073 1074 1067 +f 1062 1067 1074 +f 1074 1069 1062 +f 1043 1076 1075 +f 1075 1042 1043 +f 1045 1077 1076 +f 1076 1043 1045 +f 1047 1078 1077 +f 1077 1045 1047 +f 1049 1079 1078 +f 1078 1047 1049 +f 1051 1080 1079 +f 1079 1049 1051 +f 1053 1081 1080 +f 1080 1051 1053 +f 1042 1075 1081 +f 1081 1053 1042 +f 1069 1083 1082 +f 1082 1068 1069 +f 1068 1082 1084 +f 1084 1070 1068 +f 1070 1084 1085 +f 1085 1071 1070 +f 1071 1085 1086 +f 1086 1072 1071 +f 1072 1086 1087 +f 1087 1073 1072 +f 1073 1087 1088 +f 1088 1074 1073 +f 1074 1088 1083 +f 1083 1069 1074 +f 1092 1091 1090 +f 1090 1089 1092 +f 1094 1092 1089 +f 1089 1093 1094 +f 1096 1094 1093 +f 1093 1095 1096 +f 1098 1096 1095 +f 1095 1097 1098 +f 1100 1098 1097 +f 1097 1099 1100 +f 1102 1100 1099 +f 1099 1101 1102 +f 1091 1102 1101 +f 1101 1090 1091 +f 1089 1090 1104 +f 1104 1103 1089 +f 1093 1089 1103 +f 1103 1105 1093 +f 1095 1093 1105 +f 1105 1106 1095 +f 1097 1095 1106 +f 1106 1107 1097 +f 1099 1097 1107 +f 1107 1108 1099 +f 1101 1099 1108 +f 1108 1109 1101 +f 1090 1101 1109 +f 1109 1104 1090 +f 1103 1104 1111 +f 1111 1110 1103 +f 1105 1103 1110 +f 1110 1112 1105 +f 1106 1105 1112 +f 1112 1113 1106 +f 1107 1106 1113 +f 1113 1114 1107 +f 1108 1107 1114 +f 1114 1115 1108 +f 1109 1108 1115 +f 1115 1116 1109 +f 1104 1109 1116 +f 1116 1111 1104 +f 1110 1111 1118 +f 1118 1117 1110 +f 1112 1110 1117 +f 1117 1119 1112 +f 1113 1112 1119 +f 1119 1120 1113 +f 1114 1113 1120 +f 1120 1121 1114 +f 1115 1114 1121 +f 1121 1122 1115 +f 1116 1115 1122 +f 1122 1123 1116 +f 1111 1116 1123 +f 1123 1118 1111 +f 1118 1125 1124 +f 1124 1117 1118 +f 1117 1124 1126 +f 1126 1119 1117 +f 1119 1126 1127 +f 1127 1120 1119 +f 1120 1127 1128 +f 1128 1121 1120 +f 1121 1128 1129 +f 1129 1122 1121 +f 1122 1129 1130 +f 1130 1123 1122 +f 1123 1130 1125 +f 1125 1118 1123 +f 1134 1133 1132 +f 1132 1131 1134 +f 1136 1134 1131 +f 1131 1135 1136 +f 1138 1136 1135 +f 1135 1137 1138 +f 1140 1138 1137 +f 1137 1139 1140 +f 1142 1140 1139 +f 1139 1141 1142 +f 1144 1142 1141 +f 1141 1143 1144 +f 1133 1144 1143 +f 1143 1132 1133 +f 1131 1132 1146 +f 1146 1145 1131 +f 1135 1131 1145 +f 1145 1147 1135 +f 1137 1135 1147 +f 1147 1148 1137 +f 1139 1137 1148 +f 1148 1149 1139 +f 1141 1139 1149 +f 1149 1150 1141 +f 1143 1141 1150 +f 1150 1151 1143 +f 1132 1143 1151 +f 1151 1146 1132 +f 1145 1146 1153 +f 1153 1152 1145 +f 1147 1145 1152 +f 1152 1154 1147 +f 1148 1147 1154 +f 1154 1155 1148 +f 1149 1148 1155 +f 1155 1156 1149 +f 1150 1149 1156 +f 1156 1157 1150 +f 1151 1150 1157 +f 1157 1158 1151 +f 1146 1151 1158 +f 1158 1153 1146 +f 1152 1153 1160 +f 1160 1159 1152 +f 1154 1152 1159 +f 1159 1161 1154 +f 1155 1154 1161 +f 1161 1162 1155 +f 1156 1155 1162 +f 1162 1163 1156 +f 1157 1156 1163 +f 1163 1164 1157 +f 1158 1157 1164 +f 1164 1165 1158 +f 1153 1158 1165 +f 1165 1160 1153 +f 1134 1102 1091 +f 1091 1133 1134 +f 1136 1100 1102 +f 1102 1134 1136 +f 1138 1098 1100 +f 1100 1136 1138 +f 1140 1096 1098 +f 1098 1138 1140 +f 1142 1094 1096 +f 1096 1140 1142 +f 1144 1092 1094 +f 1094 1142 1144 +f 1133 1091 1092 +f 1092 1144 1133 +f 1160 1167 1166 +f 1166 1159 1160 +f 1159 1166 1168 +f 1168 1161 1159 +f 1161 1168 1169 +f 1169 1162 1161 +f 1162 1169 1170 +f 1170 1163 1162 +f 1163 1170 1171 +f 1171 1164 1163 +f 1164 1171 1172 +f 1172 1165 1164 +f 1165 1172 1167 +f 1167 1160 1165 +f 1176 1175 1174 +f 1174 1173 1176 +f 1175 1178 1177 +f 1177 1174 1175 +f 1178 1180 1179 +f 1179 1177 1178 +f 1180 1176 1173 +f 1173 1179 1180 +f 1182 1181 1175 +f 1175 1176 1182 +f 1181 1183 1178 +f 1178 1175 1181 +f 1183 1184 1180 +f 1180 1178 1183 +f 1184 1182 1176 +f 1176 1180 1184 +f 1186 1185 1181 +f 1181 1182 1186 +f 1185 1187 1183 +f 1183 1181 1185 +f 1187 1188 1184 +f 1184 1183 1187 +f 1190 1189 1185 +f 1185 1186 1190 +f 1189 1191 1187 +f 1187 1185 1189 +f 1191 1192 1188 +f 1188 1187 1191 +f 1194 1193 1189 +f 1189 1190 1194 +f 1193 1195 1191 +f 1191 1189 1193 +f 1195 1196 1192 +f 1192 1191 1195 +f 1174 1198 1197 +f 1197 1173 1174 +f 1177 1199 1198 +f 1198 1174 1177 +f 1179 1200 1199 +f 1199 1177 1179 +f 1173 1197 1200 +f 1200 1179 1173 +f 1202 1193 1194 +f 1194 1201 1202 +f 1203 1195 1193 +f 1193 1202 1203 +f 1204 1196 1195 +f 1195 1203 1204 +f 1201 1194 1196 +f 1196 1204 1201 +f 1184 1206 1205 +f 1205 1182 1184 +f 1182 1205 1207 +f 1207 1186 1182 +f 1188 1208 1206 +f 1206 1184 1188 +f 1186 1207 1209 +f 1209 1190 1186 +f 1192 1210 1208 +f 1208 1188 1192 +f 1190 1209 1211 +f 1211 1194 1190 +f 1196 1212 1210 +f 1210 1192 1196 +f 1194 1211 1212 +f 1212 1196 1194 +f 1209 1207 1205 +f 1205 1206 1209 +f 1208 1211 1209 +f 1209 1206 1208 +f 1212 1211 1208 +f 1208 1210 1212 +f 1216 1215 1214 +f 1214 1213 1216 +f 1218 1216 1213 +f 1213 1217 1218 +f 1220 1218 1217 +f 1217 1219 1220 +f 1222 1220 1219 +f 1219 1221 1222 +f 1224 1222 1221 +f 1221 1223 1224 +f 1226 1224 1223 +f 1223 1225 1226 +f 1215 1226 1225 +f 1225 1214 1215 +f 1213 1214 1228 +f 1228 1227 1213 +f 1217 1213 1227 +f 1227 1229 1217 +f 1219 1217 1229 +f 1229 1230 1219 +f 1221 1219 1230 +f 1230 1231 1221 +f 1223 1221 1231 +f 1231 1232 1223 +f 1225 1223 1232 +f 1232 1233 1225 +f 1214 1225 1233 +f 1233 1228 1214 +f 1227 1228 1235 +f 1235 1234 1227 +f 1229 1227 1234 +f 1234 1236 1229 +f 1230 1229 1236 +f 1236 1237 1230 +f 1231 1230 1237 +f 1237 1238 1231 +f 1232 1231 1238 +f 1238 1239 1232 +f 1233 1232 1239 +f 1239 1240 1233 +f 1228 1233 1240 +f 1240 1235 1228 +f 1234 1235 1242 +f 1242 1241 1234 +f 1236 1234 1241 +f 1241 1243 1236 +f 1237 1236 1243 +f 1243 1244 1237 +f 1238 1237 1244 +f 1244 1245 1238 +f 1239 1238 1245 +f 1245 1246 1239 +f 1240 1239 1246 +f 1246 1247 1240 +f 1235 1240 1247 +f 1247 1242 1235 +f 1216 1249 1248 +f 1248 1215 1216 +f 1218 1250 1249 +f 1249 1216 1218 +f 1220 1251 1250 +f 1250 1218 1220 +f 1222 1252 1251 +f 1251 1220 1222 +f 1224 1253 1252 +f 1252 1222 1224 +f 1226 1254 1253 +f 1253 1224 1226 +f 1215 1248 1254 +f 1254 1226 1215 +f 1242 1256 1255 +f 1255 1241 1242 +f 1241 1255 1257 +f 1257 1243 1241 +f 1243 1257 1258 +f 1258 1244 1243 +f 1244 1258 1259 +f 1259 1245 1244 +f 1245 1259 1260 +f 1260 1246 1245 +f 1246 1260 1261 +f 1261 1247 1246 +f 1247 1261 1256 +f 1256 1242 1247 +f 1265 1264 1263 +f 1263 1262 1265 +f 1267 1265 1262 +f 1262 1266 1267 +f 1269 1267 1266 +f 1266 1268 1269 +f 1271 1269 1268 +f 1268 1270 1271 +f 1273 1271 1270 +f 1270 1272 1273 +f 1275 1273 1272 +f 1272 1274 1275 +f 1264 1275 1274 +f 1274 1263 1264 +f 1262 1263 1277 +f 1277 1276 1262 +f 1266 1262 1276 +f 1276 1278 1266 +f 1268 1266 1278 +f 1278 1279 1268 +f 1270 1268 1279 +f 1279 1280 1270 +f 1272 1270 1280 +f 1280 1281 1272 +f 1274 1272 1281 +f 1281 1282 1274 +f 1263 1274 1282 +f 1282 1277 1263 +f 1276 1277 1284 +f 1284 1283 1276 +f 1278 1276 1283 +f 1283 1285 1278 +f 1279 1278 1285 +f 1285 1286 1279 +f 1280 1279 1286 +f 1286 1287 1280 +f 1281 1280 1287 +f 1287 1288 1281 +f 1282 1281 1288 +f 1288 1289 1282 +f 1277 1282 1289 +f 1289 1284 1277 +f 1283 1284 1291 +f 1291 1290 1283 +f 1285 1283 1290 +f 1290 1292 1285 +f 1286 1285 1292 +f 1292 1293 1286 +f 1287 1286 1293 +f 1293 1294 1287 +f 1288 1287 1294 +f 1294 1295 1288 +f 1289 1288 1295 +f 1295 1296 1289 +f 1284 1289 1296 +f 1296 1291 1284 +f 1265 1298 1297 +f 1297 1264 1265 +f 1267 1299 1298 +f 1298 1265 1267 +f 1269 1300 1299 +f 1299 1267 1269 +f 1271 1301 1300 +f 1300 1269 1271 +f 1273 1302 1301 +f 1301 1271 1273 +f 1275 1303 1302 +f 1302 1273 1275 +f 1264 1297 1303 +f 1303 1275 1264 +f 1291 1305 1304 +f 1304 1290 1291 +f 1290 1304 1306 +f 1306 1292 1290 +f 1292 1306 1307 +f 1307 1293 1292 +f 1293 1307 1308 +f 1308 1294 1293 +f 1294 1308 1309 +f 1309 1295 1294 +f 1295 1309 1310 +f 1310 1296 1295 +f 1296 1310 1305 +f 1305 1291 1296 +f 1314 1313 1312 +f 1312 1311 1314 +f 1316 1315 1313 +f 1313 1314 1316 +f 1318 1317 1315 +f 1315 1316 1318 +f 1320 1319 1317 +f 1317 1318 1320 +f 1322 1321 1319 +f 1319 1320 1322 +f 1311 1312 1321 +f 1321 1322 1311 +f 1320 1316 1314 +f 1314 1311 1320 +f 1320 1318 1316 +f 1320 1311 1322 +f 1313 1317 1319 +f 1319 1321 1313 +f 1313 1315 1317 +f 1313 1321 1312 +f 1326 1325 1324 +f 1324 1323 1326 +f 1328 1327 1325 +f 1325 1326 1328 +f 1330 1329 1327 +f 1327 1328 1330 +f 1332 1331 1329 +f 1329 1330 1332 +f 1334 1333 1331 +f 1331 1332 1334 +f 1323 1324 1333 +f 1333 1334 1323 +f 1332 1328 1326 +f 1326 1323 1332 +f 1332 1330 1328 +f 1332 1323 1334 +f 1325 1329 1331 +f 1331 1333 1325 +f 1325 1327 1329 +f 1325 1333 1324 +f 1338 1337 1336 +f 1336 1335 1338 +f 1337 1340 1339 +f 1339 1336 1337 +f 1340 1342 1341 +f 1341 1339 1340 +f 1342 1338 1335 +f 1335 1341 1342 +f 1344 1343 1337 +f 1337 1338 1344 +f 1343 1345 1340 +f 1340 1337 1343 +f 1345 1346 1342 +f 1342 1340 1345 +f 1346 1344 1338 +f 1338 1342 1346 +f 1348 1347 1343 +f 1343 1344 1348 +f 1347 1349 1345 +f 1345 1343 1347 +f 1349 1350 1346 +f 1346 1345 1349 +f 1352 1351 1347 +f 1347 1348 1352 +f 1351 1353 1349 +f 1349 1347 1351 +f 1353 1354 1350 +f 1350 1349 1353 +f 1356 1355 1351 +f 1351 1352 1356 +f 1355 1357 1353 +f 1353 1351 1355 +f 1357 1358 1354 +f 1354 1353 1357 +f 1336 1360 1359 +f 1359 1335 1336 +f 1339 1361 1360 +f 1360 1336 1339 +f 1341 1362 1361 +f 1361 1339 1341 +f 1335 1359 1362 +f 1362 1341 1335 +f 1364 1355 1356 +f 1356 1363 1364 +f 1365 1357 1355 +f 1355 1364 1365 +f 1366 1358 1357 +f 1357 1365 1366 +f 1363 1356 1358 +f 1358 1366 1363 +f 1346 1368 1367 +f 1367 1344 1346 +f 1344 1367 1369 +f 1369 1348 1344 +f 1350 1370 1368 +f 1368 1346 1350 +f 1348 1369 1371 +f 1371 1352 1348 +f 1354 1372 1370 +f 1370 1350 1354 +f 1352 1371 1373 +f 1373 1356 1352 +f 1358 1374 1372 +f 1372 1354 1358 +f 1356 1373 1374 +f 1374 1358 1356 +f 1371 1369 1367 +f 1367 1368 1371 +f 1370 1373 1371 +f 1371 1368 1370 +f 1374 1373 1370 +f 1370 1372 1374 +f 1378 1377 1376 +f 1376 1375 1378 +f 1380 1378 1375 +f 1375 1379 1380 +f 1382 1380 1379 +f 1379 1381 1382 +f 1384 1382 1381 +f 1381 1383 1384 +f 1386 1384 1383 +f 1383 1385 1386 +f 1388 1386 1385 +f 1385 1387 1388 +f 1377 1388 1387 +f 1387 1376 1377 +f 1392 1391 1390 +f 1390 1389 1392 +f 1394 1392 1389 +f 1389 1393 1394 +f 1396 1394 1393 +f 1393 1395 1396 +f 1398 1396 1395 +f 1395 1397 1398 +f 1400 1398 1397 +f 1397 1399 1400 +f 1402 1400 1399 +f 1399 1401 1402 +f 1391 1402 1401 +f 1401 1390 1391 +f 1406 1405 1404 +f 1404 1403 1406 +f 1408 1406 1403 +f 1403 1407 1408 +f 1410 1408 1407 +f 1407 1409 1410 +f 1412 1410 1409 +f 1409 1411 1412 +f 1414 1412 1411 +f 1411 1413 1414 +f 1416 1414 1413 +f 1413 1415 1416 +f 1405 1416 1415 +f 1415 1404 1405 +f 1420 1419 1418 +f 1418 1417 1420 +f 1422 1420 1417 +f 1417 1421 1422 +f 1424 1422 1421 +f 1421 1423 1424 +f 1426 1424 1423 +f 1423 1425 1426 +f 1428 1426 1425 +f 1425 1427 1428 +f 1430 1428 1427 +f 1427 1429 1430 +f 1419 1430 1429 +f 1429 1418 1419 +f 1434 1433 1432 +f 1432 1431 1434 +f 1436 1434 1431 +f 1431 1435 1436 +f 1438 1436 1435 +f 1435 1437 1438 +f 1440 1438 1437 +f 1437 1439 1440 +f 1442 1440 1439 +f 1439 1441 1442 +f 1444 1442 1441 +f 1441 1443 1444 +f 1433 1444 1443 +f 1443 1432 1433 +f 1448 1447 1446 +f 1446 1445 1448 +f 1450 1448 1445 +f 1445 1449 1450 +f 1452 1450 1449 +f 1449 1451 1452 +f 1454 1452 1451 +f 1451 1453 1454 +f 1456 1454 1453 +f 1453 1455 1456 +f 1458 1456 1455 +f 1455 1457 1458 +f 1447 1458 1457 +f 1457 1446 1447 +f 1462 1461 1460 +f 1460 1459 1462 +f 1464 1462 1459 +f 1459 1463 1464 +f 1466 1464 1463 +f 1463 1465 1466 +f 1468 1466 1465 +f 1465 1467 1468 +f 1470 1468 1467 +f 1467 1469 1470 +f 1472 1470 1469 +f 1469 1471 1472 +f 1461 1472 1471 +f 1471 1460 1461 +f 1476 1475 1474 +f 1474 1473 1476 +f 1478 1476 1473 +f 1473 1477 1478 +f 1480 1478 1477 +f 1477 1479 1480 +f 1482 1480 1479 +f 1479 1481 1482 +f 1484 1482 1481 +f 1481 1483 1484 +f 1486 1484 1483 +f 1483 1485 1486 +f 1475 1486 1485 +f 1485 1474 1475 +f 1490 1489 1488 +f 1488 1487 1490 +f 1492 1490 1487 +f 1487 1491 1492 +f 1494 1492 1491 +f 1491 1493 1494 +f 1496 1494 1493 +f 1493 1495 1496 +f 1498 1496 1495 +f 1495 1497 1498 +f 1500 1498 1497 +f 1497 1499 1500 +f 1489 1500 1499 +f 1499 1488 1489 +f 1504 1503 1502 +f 1502 1501 1504 +f 1506 1504 1501 +f 1501 1505 1506 +f 1508 1506 1505 +f 1505 1507 1508 +f 1510 1508 1507 +f 1507 1509 1510 +f 1512 1510 1509 +f 1509 1511 1512 +f 1514 1512 1511 +f 1511 1513 1514 +f 1503 1514 1513 +f 1513 1502 1503 +f 1518 1517 1516 +f 1516 1515 1518 +f 1520 1518 1515 +f 1515 1519 1520 +f 1522 1520 1519 +f 1519 1521 1522 +f 1524 1522 1521 +f 1521 1523 1524 +f 1526 1524 1523 +f 1523 1525 1526 +f 1528 1526 1525 +f 1525 1527 1528 +f 1517 1528 1527 +f 1527 1516 1517 +f 1532 1531 1530 +f 1530 1529 1532 +f 1534 1532 1529 +f 1529 1533 1534 +f 1536 1534 1533 +f 1533 1535 1536 +f 1538 1536 1535 +f 1535 1537 1538 +f 1540 1538 1537 +f 1537 1539 1540 +f 1542 1540 1539 +f 1539 1541 1542 +f 1531 1542 1541 +f 1541 1530 1531 +f 1546 1545 1544 +f 1544 1543 1546 +f 1548 1546 1543 +f 1543 1547 1548 +f 1550 1548 1547 +f 1547 1549 1550 +f 1552 1550 1549 +f 1549 1551 1552 +f 1554 1552 1551 +f 1551 1553 1554 +f 1556 1554 1553 +f 1553 1555 1556 +f 1545 1556 1555 +f 1555 1544 1545 +f 1555 1551 1549 +f 1549 1547 1555 +f 1555 1553 1551 +f 1544 1555 1547 +f 1547 1543 1544 +f 1560 1559 1558 +f 1558 1557 1560 +f 1562 1560 1557 +f 1557 1561 1562 +f 1564 1562 1561 +f 1561 1563 1564 +f 1566 1564 1563 +f 1563 1565 1566 +f 1568 1566 1565 +f 1565 1567 1568 +f 1570 1568 1567 +f 1567 1569 1570 +f 1559 1570 1569 +f 1569 1558 1559 +f 1569 1565 1563 +f 1563 1561 1569 +f 1569 1567 1565 +f 1558 1569 1561 +f 1561 1557 1558 +f 1574 1573 1572 +f 1572 1571 1574 +f 1576 1574 1571 +f 1571 1575 1576 +f 1578 1576 1575 +f 1575 1577 1578 +f 1580 1578 1577 +f 1577 1579 1580 +f 1582 1580 1579 +f 1579 1581 1582 +f 1584 1582 1581 +f 1581 1583 1584 +f 1573 1584 1583 +f 1583 1572 1573 +f 1588 1587 1586 +f 1586 1585 1588 +f 1588 1589 1587 +f 1591 1588 1585 +f 1585 1590 1591 +f 1572 1593 1592 +f 1592 1571 1572 +f 1583 1594 1593 +f 1593 1572 1583 +f 1581 1595 1594 +f 1594 1583 1581 +f 1579 1596 1595 +f 1595 1581 1579 +f 1577 1597 1596 +f 1596 1579 1577 +f 1575 1598 1597 +f 1597 1577 1575 +f 1571 1592 1598 +f 1598 1575 1571 +f 1593 1591 1590 +f 1590 1592 1593 +f 1594 1588 1591 +f 1591 1593 1594 +f 1595 1589 1588 +f 1588 1594 1595 +f 1596 1587 1589 +f 1589 1595 1596 +f 1597 1586 1587 +f 1587 1596 1597 +f 1598 1585 1586 +f 1586 1597 1598 +f 1592 1590 1585 +f 1585 1598 1592 +f 1574 1600 1599 +f 1599 1573 1574 +f 1576 1601 1600 +f 1600 1574 1576 +f 1578 1602 1601 +f 1601 1576 1578 +f 1580 1603 1602 +f 1602 1578 1580 +f 1582 1604 1603 +f 1603 1580 1582 +f 1584 1605 1604 +f 1604 1582 1584 +f 1573 1599 1605 +f 1605 1584 1573 +f 1600 1607 1606 +f 1606 1599 1600 +f 1601 1608 1607 +f 1607 1600 1601 +f 1602 1609 1608 +f 1608 1601 1602 +f 1603 1610 1609 +f 1609 1602 1603 +f 1604 1611 1610 +f 1610 1603 1604 +f 1605 1612 1611 +f 1611 1604 1605 +f 1599 1606 1612 +f 1612 1605 1599 +f 1608 1610 1611 +f 1611 1612 1608 +f 1608 1609 1610 +f 1607 1608 1612 +f 1612 1606 1607 +f 1616 1615 1614 +f 1614 1613 1616 +f 1618 1616 1613 +f 1613 1617 1618 +f 1620 1618 1617 +f 1617 1619 1620 +f 1622 1620 1619 +f 1619 1621 1622 +f 1624 1622 1621 +f 1621 1623 1624 +f 1626 1624 1623 +f 1623 1625 1626 +f 1615 1626 1625 +f 1625 1614 1615 +f 1630 1629 1628 +f 1628 1627 1630 +f 1630 1631 1629 +f 1633 1630 1627 +f 1627 1632 1633 +f 1614 1635 1634 +f 1634 1613 1614 +f 1625 1636 1635 +f 1635 1614 1625 +f 1623 1637 1636 +f 1636 1625 1623 +f 1621 1638 1637 +f 1637 1623 1621 +f 1619 1639 1638 +f 1638 1621 1619 +f 1617 1640 1639 +f 1639 1619 1617 +f 1613 1634 1640 +f 1640 1617 1613 +f 1635 1633 1632 +f 1632 1634 1635 +f 1636 1630 1633 +f 1633 1635 1636 +f 1637 1631 1630 +f 1630 1636 1637 +f 1638 1629 1631 +f 1631 1637 1638 +f 1639 1628 1629 +f 1629 1638 1639 +f 1640 1627 1628 +f 1628 1639 1640 +f 1634 1632 1627 +f 1627 1640 1634 +f 1618 1622 1624 +f 1624 1626 1618 +f 1618 1620 1622 +f 1616 1618 1626 +f 1626 1615 1616 +f 1644 1643 1642 +f 1642 1641 1644 +f 1646 1644 1641 +f 1641 1645 1646 +f 1648 1646 1645 +f 1645 1647 1648 +f 1650 1648 1647 +f 1647 1649 1650 +f 1652 1650 1649 +f 1649 1651 1652 +f 1654 1652 1651 +f 1651 1653 1654 +f 1643 1654 1653 +f 1653 1642 1643 +f 1646 1650 1652 +f 1652 1654 1646 +f 1646 1648 1650 +f 1644 1646 1654 +f 1654 1643 1644 +f 1653 1649 1647 +f 1647 1645 1653 +f 1653 1651 1649 +f 1642 1653 1645 +f 1645 1641 1642 +f 1658 1657 1656 +f 1656 1655 1658 +f 1660 1658 1655 +f 1655 1659 1660 +f 1662 1660 1659 +f 1659 1661 1662 +f 1664 1662 1661 +f 1661 1663 1664 +f 1666 1664 1663 +f 1663 1665 1666 +f 1668 1666 1665 +f 1665 1667 1668 +f 1657 1668 1667 +f 1667 1656 1657 +f 1667 1663 1661 +f 1661 1659 1667 +f 1667 1665 1663 +f 1656 1667 1659 +f 1659 1655 1656 +f 1672 1671 1670 +f 1670 1669 1672 +f 1674 1672 1669 +f 1669 1673 1674 +f 1676 1674 1673 +f 1673 1675 1676 +f 1678 1676 1675 +f 1675 1677 1678 +f 1680 1678 1677 +f 1677 1679 1680 +f 1682 1680 1679 +f 1679 1681 1682 +f 1671 1682 1681 +f 1681 1670 1671 +f 1681 1677 1675 +f 1675 1673 1681 +f 1681 1679 1677 +f 1670 1681 1673 +f 1673 1669 1670 +f 1686 1685 1684 +f 1684 1683 1686 +f 1688 1686 1683 +f 1683 1687 1688 +f 1690 1688 1687 +f 1687 1689 1690 +f 1692 1690 1689 +f 1689 1691 1692 +f 1694 1692 1691 +f 1691 1693 1694 +f 1696 1694 1693 +f 1693 1695 1696 +f 1685 1696 1695 +f 1695 1684 1685 +f 1695 1691 1689 +f 1689 1687 1695 +f 1695 1693 1691 +f 1684 1695 1687 +f 1687 1683 1684 +f 1700 1699 1698 +f 1698 1697 1700 +f 1702 1701 1699 +f 1699 1700 1702 +f 1704 1703 1701 +f 1701 1702 1704 +f 1706 1705 1703 +f 1703 1704 1706 +f 1708 1707 1705 +f 1705 1706 1708 +f 1710 1709 1707 +f 1707 1708 1710 +f 1697 1698 1709 +f 1709 1710 1697 +f 1697 1712 1711 +f 1711 1700 1697 +f 1700 1711 1713 +f 1713 1702 1700 +f 1702 1713 1714 +f 1714 1704 1702 +f 1704 1714 1715 +f 1715 1706 1704 +f 1706 1715 1716 +f 1716 1708 1706 +f 1708 1716 1717 +f 1717 1710 1708 +f 1710 1717 1712 +f 1712 1697 1710 +f 1712 1719 1718 +f 1718 1711 1712 +f 1711 1718 1720 +f 1720 1713 1711 +f 1713 1720 1721 +f 1721 1714 1713 +f 1714 1721 1722 +f 1722 1715 1714 +f 1715 1722 1723 +f 1723 1716 1715 +f 1716 1723 1724 +f 1724 1717 1716 +f 1717 1724 1719 +f 1719 1712 1717 +f 1724 1722 1721 +f 1721 1720 1724 +f 1724 1723 1722 +f 1719 1724 1720 +f 1720 1718 1719 +f 1728 1727 1726 +f 1726 1725 1728 +f 1730 1729 1727 +f 1727 1728 1730 +f 1732 1731 1729 +f 1729 1730 1732 +f 1734 1733 1731 +f 1731 1732 1734 +f 1736 1735 1733 +f 1733 1734 1736 +f 1738 1737 1735 +f 1735 1736 1738 +f 1725 1726 1737 +f 1737 1738 1725 +f 1725 1740 1739 +f 1739 1728 1725 +f 1728 1739 1741 +f 1741 1730 1728 +f 1730 1741 1742 +f 1742 1732 1730 +f 1732 1742 1743 +f 1743 1734 1732 +f 1734 1743 1744 +f 1744 1736 1734 +f 1736 1744 1745 +f 1745 1738 1736 +f 1738 1745 1740 +f 1740 1725 1738 +f 1740 1747 1746 +f 1746 1739 1740 +f 1739 1746 1748 +f 1748 1741 1739 +f 1741 1748 1749 +f 1749 1742 1741 +f 1742 1749 1750 +f 1750 1743 1742 +f 1743 1750 1751 +f 1751 1744 1743 +f 1744 1751 1752 +f 1752 1745 1744 +f 1745 1752 1747 +f 1747 1740 1745 +f 1752 1750 1749 +f 1749 1748 1752 +f 1752 1751 1750 +f 1747 1752 1748 +f 1748 1746 1747 +f 1756 1755 1754 +f 1754 1753 1756 +f 1758 1756 1753 +f 1753 1757 1758 +f 1760 1758 1757 +f 1757 1759 1760 +f 1762 1760 1759 +f 1759 1761 1762 +f 1764 1762 1761 +f 1761 1763 1764 +f 1766 1764 1763 +f 1763 1765 1766 +f 1755 1766 1765 +f 1765 1754 1755 +f 1660 1664 1666 +f 1666 1668 1660 +f 1660 1662 1664 +f 1658 1660 1668 +f 1668 1657 1658 +f 1688 1692 1694 +f 1694 1696 1688 +f 1688 1690 1692 +f 1686 1688 1696 +f 1696 1685 1686 +f 1674 1678 1680 +f 1680 1682 1674 +f 1674 1676 1678 +f 1672 1674 1682 +f 1682 1671 1672 +f 1754 1768 1767 +f 1767 1753 1754 +f 1753 1767 1769 +f 1769 1757 1753 +f 1757 1769 1770 +f 1770 1759 1757 +f 1759 1770 1771 +f 1771 1761 1759 +f 1761 1771 1772 +f 1772 1763 1761 +f 1763 1772 1773 +f 1773 1765 1763 +f 1765 1773 1768 +f 1768 1754 1765 +f 1768 1775 1774 +f 1774 1767 1768 +f 1767 1774 1776 +f 1776 1769 1767 +f 1769 1776 1777 +f 1777 1770 1769 +f 1770 1777 1778 +f 1778 1771 1770 +f 1771 1778 1779 +f 1779 1772 1771 +f 1772 1779 1780 +f 1780 1773 1772 +f 1773 1780 1775 +f 1775 1768 1773 +f 1780 1778 1777 +f 1777 1776 1780 +f 1780 1779 1778 +f 1775 1780 1776 +f 1776 1774 1775 +f 1784 1783 1782 +f 1782 1781 1784 +f 1786 1784 1781 +f 1781 1785 1786 +f 1788 1786 1785 +f 1785 1787 1788 +f 1790 1788 1787 +f 1787 1789 1790 +f 1792 1790 1789 +f 1789 1791 1792 +f 1794 1792 1791 +f 1791 1793 1794 +f 1783 1794 1793 +f 1793 1782 1783 +f 1784 1796 1795 +f 1795 1783 1784 +f 1782 1798 1797 +f 1797 1781 1782 +f 1786 1799 1796 +f 1796 1784 1786 +f 1781 1797 1800 +f 1800 1785 1781 +f 1788 1801 1799 +f 1799 1786 1788 +f 1785 1800 1802 +f 1802 1787 1785 +f 1790 1803 1801 +f 1801 1788 1790 +f 1787 1802 1804 +f 1804 1789 1787 +f 1792 1805 1803 +f 1803 1790 1792 +f 1789 1804 1806 +f 1806 1791 1789 +f 1794 1807 1805 +f 1805 1792 1794 +f 1791 1806 1808 +f 1808 1793 1791 +f 1783 1795 1807 +f 1807 1794 1783 +f 1793 1808 1798 +f 1798 1782 1793 +f 1812 1811 1810 +f 1810 1809 1812 +f 1814 1812 1809 +f 1809 1813 1814 +f 1816 1814 1813 +f 1813 1815 1816 +f 1818 1816 1815 +f 1815 1817 1818 +f 1820 1818 1817 +f 1817 1819 1820 +f 1822 1820 1819 +f 1819 1821 1822 +f 1811 1822 1821 +f 1821 1810 1811 +f 1810 1824 1823 +f 1823 1809 1810 +f 1809 1823 1825 +f 1825 1813 1809 +f 1813 1825 1826 +f 1826 1815 1813 +f 1815 1826 1827 +f 1827 1817 1815 +f 1817 1827 1828 +f 1828 1819 1817 +f 1819 1828 1829 +f 1829 1821 1819 +f 1821 1829 1824 +f 1824 1810 1821 +f 1814 1818 1820 +f 1820 1822 1814 +f 1814 1816 1818 +f 1812 1814 1822 +f 1822 1811 1812 +f 1833 1832 1831 +f 1831 1830 1833 +f 1835 1833 1830 +f 1830 1834 1835 +f 1837 1835 1834 +f 1834 1836 1837 +f 1839 1837 1836 +f 1836 1838 1839 +f 1841 1839 1838 +f 1838 1840 1841 +f 1843 1841 1840 +f 1840 1842 1843 +f 1832 1843 1842 +f 1842 1831 1832 +f 1835 1839 1841 +f 1841 1843 1835 +f 1835 1837 1839 +f 1833 1835 1843 +f 1843 1832 1833 +f 1847 1846 1845 +f 1845 1844 1847 +f 1849 1847 1844 +f 1844 1848 1849 +f 1851 1849 1848 +f 1848 1850 1851 +f 1853 1851 1850 +f 1850 1852 1853 +f 1855 1853 1852 +f 1852 1854 1855 +f 1857 1855 1854 +f 1854 1856 1857 +f 1846 1857 1856 +f 1856 1845 1846 +f 1842 1838 1836 +f 1836 1834 1842 +f 1842 1840 1838 +f 1830 1831 1842 +f 1842 1834 1830 +f 1861 1860 1859 +f 1859 1858 1861 +f 1863 1861 1858 +f 1858 1862 1863 +f 1865 1863 1862 +f 1862 1864 1865 +f 1867 1865 1864 +f 1864 1866 1867 +f 1869 1867 1866 +f 1866 1868 1869 +f 1871 1869 1868 +f 1868 1870 1871 +f 1860 1871 1870 +f 1870 1859 1860 +f 1873 1872 1860 +f 1860 1861 1873 +f 1874 1873 1861 +f 1861 1863 1874 +f 1875 1874 1863 +f 1863 1865 1875 +f 1876 1875 1865 +f 1865 1867 1876 +f 1877 1876 1867 +f 1867 1869 1877 +f 1878 1877 1869 +f 1869 1871 1878 +f 1872 1878 1871 +f 1871 1860 1872 +f 1880 1879 1872 +f 1872 1873 1880 +f 1881 1880 1873 +f 1873 1874 1881 +f 1882 1881 1874 +f 1874 1875 1882 +f 1883 1882 1875 +f 1875 1876 1883 +f 1884 1883 1876 +f 1876 1877 1884 +f 1885 1884 1877 +f 1877 1878 1885 +f 1879 1885 1878 +f 1878 1872 1879 +f 1870 1866 1864 +f 1864 1862 1870 +f 1870 1868 1866 +f 1858 1859 1870 +f 1870 1862 1858 +f 1889 1888 1887 +f 1887 1886 1889 +f 1893 1892 1891 +f 1891 1890 1893 +f 1897 1896 1895 +f 1895 1894 1897 +f 1901 1900 1899 +f 1899 1898 1901 +f 1905 1904 1903 +f 1903 1902 1905 +f 1909 1908 1907 +f 1907 1906 1909 +f 1913 1912 1911 +f 1911 1910 1913 +f 1917 1916 1915 +f 1915 1914 1917 +f 1921 1920 1919 +f 1919 1918 1921 +f 1906 1907 1923 +f 1923 1922 1906 +f 1910 1911 1925 +f 1925 1924 1910 +f 1916 1927 1926 +f 1926 1915 1916 +f 1920 1929 1928 +f 1928 1919 1920 +f 1921 1918 1931 +f 1931 1930 1921 +f 1912 1913 1933 +f 1933 1932 1912 +f 1908 1909 1935 +f 1935 1934 1908 +f 1917 1914 1937 +f 1937 1936 1917 +f 1939 1938 1890 +f 1890 1891 1939 +f 1941 1940 1892 +f 1892 1893 1941 +f 1943 1942 1894 +f 1894 1895 1943 +f 1945 1944 1896 +f 1896 1897 1945 +f 1912 1947 1946 +f 1946 1911 1912 +f 1908 1949 1948 +f 1948 1907 1908 +f 1921 1951 1950 +f 1950 1920 1921 +f 1917 1953 1952 +f 1952 1916 1917 +f 1911 1946 1954 +f 1954 1925 1911 +f 1906 1956 1955 +f 1955 1909 1906 +f 1907 1948 1957 +f 1957 1923 1907 +f 1910 1959 1958 +f 1958 1913 1910 +f 1920 1950 1960 +f 1960 1929 1920 +f 1915 1962 1961 +f 1961 1914 1915 +f 1916 1952 1963 +f 1963 1927 1916 +f 1919 1965 1964 +f 1964 1918 1919 +f 1967 1966 1901 +f 1901 1898 1967 +f 1922 1968 1956 +f 1956 1906 1922 +f 1970 1969 1899 +f 1899 1900 1970 +f 1924 1971 1959 +f 1959 1910 1924 +f 1973 1972 1902 +f 1902 1903 1973 +f 1926 1974 1962 +f 1962 1915 1926 +f 1976 1975 1904 +f 1904 1905 1976 +f 1928 1977 1965 +f 1965 1919 1928 +f 1930 1978 1951 +f 1951 1921 1930 +f 1918 1964 1979 +f 1979 1931 1918 +f 1932 1980 1947 +f 1947 1912 1932 +f 1913 1958 1981 +f 1981 1933 1913 +f 1934 1982 1949 +f 1949 1908 1934 +f 1909 1955 1983 +f 1983 1935 1909 +f 1936 1984 1953 +f 1953 1917 1936 +f 1914 1961 1985 +f 1985 1937 1914 +f 1987 1986 1938 +f 1938 1939 1987 +f 1989 1988 1942 +f 1942 1943 1989 +f 1947 1991 1990 +f 1990 1946 1947 +f 1953 1993 1992 +f 1992 1952 1953 +f 1946 1990 1994 +f 1994 1954 1946 +f 1956 1996 1995 +f 1995 1955 1956 +f 1952 1992 1997 +f 1997 1963 1952 +f 1965 1999 1998 +f 1998 1964 1965 +f 1967 2001 2000 +f 2000 1966 1967 +f 1968 2002 1996 +f 1996 1956 1968 +f 2004 2003 1975 +f 1975 1976 2004 +f 1977 2005 1999 +f 1999 1965 1977 +f 1964 1998 2006 +f 2006 1979 1964 +f 1980 2007 1991 +f 1991 1947 1980 +f 1955 1995 2008 +f 2008 1983 1955 +f 1984 2009 1993 +f 1993 1953 1984 +f 2011 2010 1986 +f 1986 1987 2011 +f 2013 2012 1988 +f 1988 1989 2013 +f 1991 2015 2014 +f 2014 1990 1991 +f 1993 2017 2016 +f 2016 1992 1993 +f 1990 2014 2018 +f 2018 1994 1990 +f 1996 2020 2019 +f 2019 1995 1996 +f 1992 2016 2021 +f 2021 1997 1992 +f 1999 2023 2022 +f 2022 1998 1999 +f 2025 2024 2000 +f 2000 2001 2025 +f 2002 2026 2020 +f 2020 1996 2002 +f 2028 2027 2003 +f 2003 2004 2028 +f 2005 2029 2023 +f 2023 1999 2005 +f 1998 2022 2030 +f 2030 2006 1998 +f 2007 2031 2015 +f 2015 1991 2007 +f 1995 2019 2032 +f 2032 2008 1995 +f 2009 2033 2017 +f 2017 1993 2009 +f 2037 2036 2035 +f 2035 2034 2037 +f 2039 2038 2010 +f 2010 2011 2039 +f 2022 2041 2040 +f 2040 2030 2022 +f 2023 2042 2041 +f 2041 2022 2023 +f 2029 2043 2042 +f 2042 2023 2029 +f 2045 2044 2027 +f 2027 2028 2045 +f 2016 2047 2046 +f 2046 2021 2016 +f 2017 2048 2047 +f 2047 2016 2017 +f 2033 2049 2048 +f 2048 2017 2033 +f 2051 2050 2012 +f 2012 2013 2051 +f 2019 2053 2052 +f 2052 2032 2019 +f 2020 2054 2053 +f 2053 2019 2020 +f 2026 2055 2054 +f 2054 2020 2026 +f 2057 2056 2024 +f 2024 2025 2057 +f 2014 2059 2058 +f 2058 2018 2014 +f 2015 2060 2059 +f 2059 2014 2015 +f 2031 2061 2060 +f 2060 2015 2031 +f 2063 2062 1940 +f 1940 1941 2063 +f 2065 2064 1944 +f 1944 1945 2065 +f 1949 2067 2066 +f 2066 1948 1949 +f 1951 2069 2068 +f 2068 1950 1951 +f 1948 2066 2070 +f 2070 1957 1948 +f 1959 2072 2071 +f 2071 1958 1959 +f 1950 2068 2073 +f 2073 1960 1950 +f 1962 2075 2074 +f 2074 1961 1962 +f 1970 2077 2076 +f 2076 1969 1970 +f 1971 2078 2072 +f 2072 1959 1971 +f 2080 2079 1972 +f 1972 1973 2080 +f 1974 2081 2075 +f 2075 1962 1974 +f 1978 2082 2069 +f 2069 1951 1978 +f 1958 2071 2083 +f 2083 1981 1958 +f 1982 2084 2067 +f 2067 1949 1982 +f 1961 2074 2085 +f 2085 1985 1961 +f 2087 2086 2062 +f 2062 2063 2087 +f 2089 2088 2064 +f 2064 2065 2089 +f 2067 2091 2090 +f 2090 2066 2067 +f 2069 2093 2092 +f 2092 2068 2069 +f 2066 2090 2094 +f 2094 2070 2066 +f 2072 2096 2095 +f 2095 2071 2072 +f 2068 2092 2097 +f 2097 2073 2068 +f 2075 2099 2098 +f 2098 2074 2075 +f 2101 2100 2076 +f 2076 2077 2101 +f 2078 2102 2096 +f 2096 2072 2078 +f 2104 2103 2079 +f 2079 2080 2104 +f 2081 2105 2099 +f 2099 2075 2081 +f 2082 2106 2093 +f 2093 2069 2082 +f 2071 2095 2107 +f 2107 2083 2071 +f 2084 2108 2091 +f 2091 2067 2084 +f 2074 2098 2109 +f 2109 2085 2074 +f 2111 2110 2086 +f 2086 2087 2111 +f 2095 2113 2112 +f 2112 2107 2095 +f 2096 2114 2113 +f 2113 2095 2096 +f 2102 2115 2114 +f 2114 2096 2102 +f 2117 2116 2100 +f 2100 2101 2117 +f 2090 2119 2118 +f 2118 2094 2090 +f 2091 2120 2119 +f 2119 2090 2091 +f 2108 2121 2120 +f 2120 2091 2108 +f 2123 2122 2088 +f 2088 2089 2123 +f 2098 2125 2124 +f 2124 2109 2098 +f 2099 2126 2125 +f 2125 2098 2099 +f 2105 2127 2126 +f 2126 2099 2105 +f 2129 2128 2103 +f 2103 2104 2129 +f 2092 2131 2130 +f 2130 2097 2092 +f 2093 2132 2131 +f 2131 2092 2093 +f 2106 2133 2132 +f 2132 2093 2106 +f 1922 1923 1900 +f 1900 1901 1922 +f 1924 1925 1898 +f 1898 1899 1924 +f 1927 1905 1902 +f 1902 1926 1927 +f 1929 1903 1904 +f 1904 1928 1929 +f 1954 1967 1898 +f 1898 1925 1954 +f 1922 1901 1966 +f 1966 1968 1922 +f 1957 1970 1900 +f 1900 1923 1957 +f 1924 1899 1969 +f 1969 1971 1924 +f 1960 1973 1903 +f 1903 1929 1960 +f 1926 1902 1972 +f 1972 1974 1926 +f 1963 1976 1905 +f 1905 1927 1963 +f 1928 1904 1975 +f 1975 1977 1928 +f 1994 2001 1967 +f 1967 1954 1994 +f 2002 1968 1966 +f 1966 2000 2002 +f 1997 2004 1976 +f 1976 1963 1997 +f 1977 1975 2003 +f 2003 2005 1977 +f 2018 2025 2001 +f 2001 1994 2018 +f 2002 2000 2024 +f 2024 2026 2002 +f 2021 2028 2004 +f 2004 1997 2021 +f 2005 2003 2027 +f 2027 2029 2005 +f 2035 2134 2050 +f 2050 2051 2035 +f 2034 2035 2051 +f 2036 2037 2038 +f 2038 2039 2036 +f 2046 2045 2028 +f 2028 2021 2046 +f 2043 2029 2027 +f 2027 2044 2043 +f 2058 2057 2025 +f 2025 2018 2058 +f 2055 2026 2024 +f 2024 2056 2055 +f 1957 2070 2077 +f 2077 1970 1957 +f 2076 2078 1971 +f 1971 1969 2076 +f 2073 2080 1973 +f 1973 1960 2073 +f 1974 1972 2079 +f 2079 2081 1974 +f 2094 2101 2077 +f 2077 2070 2094 +f 2078 2076 2100 +f 2100 2102 2078 +f 2097 2104 2080 +f 2080 2073 2097 +f 2081 2079 2103 +f 2103 2105 2081 +f 2118 2117 2101 +f 2101 2094 2118 +f 2115 2102 2100 +f 2100 2116 2115 +f 2130 2129 2104 +f 2104 2097 2130 +f 2127 2105 2103 +f 2103 2128 2127 +f 1933 1893 1890 +f 1890 1932 1933 +f 1931 1891 1892 +f 1892 1930 1931 +f 1937 1897 1894 +f 1894 1936 1937 +f 1935 1895 1896 +f 1896 1934 1935 +f 1931 1979 1939 +f 1939 1891 1931 +f 1932 1890 1938 +f 1938 1980 1932 +f 1933 1981 1941 +f 1941 1893 1933 +f 1930 1892 1940 +f 1940 1978 1930 +f 1935 1983 1943 +f 1943 1895 1935 +f 1936 1894 1942 +f 1942 1984 1936 +f 1937 1985 1945 +f 1945 1897 1937 +f 1934 1896 1944 +f 1944 1982 1934 +f 2006 1987 1939 +f 1939 1979 2006 +f 1980 1938 1986 +f 1986 2007 1980 +f 2008 1989 1943 +f 1943 1983 2008 +f 1984 1942 1988 +f 1988 2009 1984 +f 2006 2030 2011 +f 2011 1987 2006 +f 2007 1986 2010 +f 2010 2031 2007 +f 2008 2032 2013 +f 2013 1989 2008 +f 2009 1988 2012 +f 2012 2033 2009 +f 2057 2037 2034 +f 2034 2056 2057 +f 2045 2035 2036 +f 2036 2044 2045 +f 2030 2040 2039 +f 2039 2011 2030 +f 2031 2010 2038 +f 2038 2061 2031 +f 2032 2052 2051 +f 2051 2013 2032 +f 2033 2012 2050 +f 2050 2049 2033 +f 2083 2063 1941 +f 1941 1981 2083 +f 1978 1940 2062 +f 2062 2082 1978 +f 2085 2065 1945 +f 1945 1985 2085 +f 1982 1944 2064 +f 2064 2084 1982 +f 2083 2107 2087 +f 2087 2063 2083 +f 2082 2062 2086 +f 2086 2106 2082 +f 2085 2109 2089 +f 2089 2065 2085 +f 2084 2064 2088 +f 2088 2108 2084 +f 2107 2112 2111 +f 2111 2087 2107 +f 2106 2086 2110 +f 2110 2133 2106 +f 2109 2124 2123 +f 2123 2089 2109 +f 2108 2088 2122 +f 2122 2121 2108 +f 2055 2051 2052 +f 2052 2053 2055 +f 2034 2051 2055 +f 2055 2056 2034 +f 2054 2055 2053 +f 2035 2046 2047 +f 2047 2048 2035 +f 2035 2045 2046 +f 2134 2035 2048 +f 2048 2049 2134 +f 2050 2134 2049 +f 2043 2039 2040 +f 2040 2041 2043 +f 2036 2039 2043 +f 2043 2044 2036 +f 2042 2043 2041 +f 2060 2037 2057 +f 2057 2058 2060 +f 2038 2037 2060 +f 2060 2061 2038 +f 2059 2060 2058 +f 2138 2137 2136 +f 2136 2135 2138 +f 2138 2135 2140 +f 2140 2139 2138 +f 2139 2140 2122 +f 2122 2123 2139 +f 2131 2142 2141 +f 2141 2130 2131 +f 2132 2143 2142 +f 2142 2131 2132 +f 2144 2143 2132 +f 2132 2133 2144 +f 2110 2144 2133 +f 2125 2139 2123 +f 2123 2124 2125 +f 2125 2126 2138 +f 2138 2139 2125 +f 2126 2127 2137 +f 2137 2138 2126 +f 2119 2135 2136 +f 2136 2118 2119 +f 2120 2140 2135 +f 2135 2119 2120 +f 2120 2121 2122 +f 2122 2140 2120 +f 2146 2145 2143 +f 2143 2144 2146 +f 2110 2111 2146 +f 2146 2144 2110 +f 2147 2142 2143 +f 2143 2145 2147 +f 2148 2141 2142 +f 2142 2147 2148 +f 2145 2146 2111 +f 2111 2112 2145 +f 2113 2145 2112 +f 2114 2147 2145 +f 2145 2113 2114 +f 2114 2115 2148 +f 2148 2147 2114 +f 2116 2150 2149 +f 2149 2115 2116 +f 2128 2152 2151 +f 2151 2127 2128 +f 2117 2153 2150 +f 2150 2116 2117 +f 2118 2154 2153 +f 2153 2117 2118 +f 2129 2155 2152 +f 2152 2128 2129 +f 2130 2156 2155 +f 2155 2129 2130 +f 2127 2151 2157 +f 2157 2137 2127 +f 2115 2149 2158 +f 2158 2148 2115 +f 2137 2157 2159 +f 2159 2136 2137 +f 2136 2159 2154 +f 2154 2118 2136 +f 2141 2160 2156 +f 2156 2130 2141 +f 2148 2158 2160 +f 2160 2141 2148 +f 2161 2155 2156 +f 2156 2160 2161 +f 2165 2164 2163 +f 2163 2162 2165 +f 2162 2163 2167 +f 2167 2166 2162 +f 2166 2167 2169 +f 2169 2168 2166 +f 2168 2169 2171 +f 2171 2170 2168 +f 2170 2171 2173 +f 2173 2172 2170 +f 2172 2173 2175 +f 2175 2174 2172 +f 2174 2175 2177 +f 2177 2176 2174 +f 2176 2177 2164 +f 2164 2165 2176 +f 2169 2167 2179 +f 2179 2178 2169 +f 2173 2171 2181 +f 2181 2180 2173 +f 2179 2167 2183 +f 2183 2182 2179 +f 2169 2178 2185 +f 2185 2184 2169 +f 2178 2179 2182 +f 2182 2185 2178 +f 2187 2181 2171 +f 2171 2186 2187 +f 2173 2180 2189 +f 2189 2188 2173 +f 2180 2181 2187 +f 2187 2189 2180 +f 2193 2192 2191 +f 2191 2190 2193 +f 2192 2195 2194 +f 2194 2191 2192 +f 2195 2197 2196 +f 2196 2194 2195 +f 2197 2199 2198 +f 2198 2196 2197 +f 2199 2201 2200 +f 2200 2198 2199 +f 2201 2203 2202 +f 2202 2200 2201 +f 2203 2205 2204 +f 2204 2202 2203 +f 2205 2193 2190 +f 2190 2204 2205 +f 2196 2207 2206 +f 2206 2194 2196 +f 2200 2209 2208 +f 2208 2198 2200 +f 2206 2211 2210 +f 2210 2194 2206 +f 2196 2213 2212 +f 2212 2207 2196 +f 2207 2212 2211 +f 2211 2206 2207 +f 2198 2208 2215 +f 2215 2214 2198 +f 2200 2217 2216 +f 2216 2209 2200 +f 2209 2216 2215 +f 2215 2208 2209 +f 2163 2164 2190 +f 2190 2191 2163 +f 2167 2163 2191 +f 2191 2194 2167 +f 2171 2169 2196 +f 2196 2198 2171 +f 2175 2173 2200 +f 2200 2202 2175 +f 2177 2175 2202 +f 2202 2204 2177 +f 2164 2177 2204 +f 2204 2190 2164 +f 2182 2183 2210 +f 2210 2211 2182 +f 2183 2167 2194 +f 2194 2210 2183 +f 2169 2184 2213 +f 2213 2196 2169 +f 2184 2185 2212 +f 2212 2213 2184 +f 2185 2182 2211 +f 2211 2212 2185 +f 2187 2186 2214 +f 2214 2215 2187 +f 2186 2171 2198 +f 2198 2214 2186 +f 2173 2188 2217 +f 2217 2200 2173 +f 2188 2189 2216 +f 2216 2217 2188 +f 2189 2187 2215 +f 2215 2216 2189 +f 2221 2220 2219 +f 2219 2218 2221 +f 2223 2222 2220 +f 2220 2221 2223 +f 2218 2219 2225 +f 2225 2224 2218 +f 2220 2227 2226 +f 2226 2219 2220 +f 2222 2228 2227 +f 2227 2220 2222 +f 2219 2226 2229 +f 2229 2225 2219 +f 2229 2226 2227 +f 2227 2228 2229 +f 2233 2232 2231 +f 2231 2230 2233 +f 2232 2235 2234 +f 2234 2231 2232 +f 2235 2237 2236 +f 2236 2234 2235 +f 2237 2239 2238 +f 2238 2236 2237 +f 2239 2241 2240 +f 2240 2238 2239 +f 2241 2233 2230 +f 2230 2240 2241 +f 2241 2237 2235 +f 2235 2232 2241 +f 2241 2239 2237 +f 2241 2232 2233 +f 2243 2242 2230 +f 2230 2231 2243 +f 2244 2243 2231 +f 2231 2234 2244 +f 2245 2244 2234 +f 2234 2236 2245 +f 2246 2245 2236 +f 2236 2238 2246 +f 2247 2246 2238 +f 2238 2240 2247 +f 2242 2247 2240 +f 2240 2230 2242 +f 2249 2248 2242 +f 2242 2243 2249 +f 2250 2249 2243 +f 2243 2244 2250 +f 2251 2250 2244 +f 2244 2245 2251 +f 2252 2251 2245 +f 2245 2246 2252 +f 2253 2252 2246 +f 2246 2247 2253 +f 2248 2253 2247 +f 2247 2242 2248 +f 2249 2251 2252 +f 2252 2253 2249 +f 2249 2250 2251 +f 2249 2253 2248 +f 2257 2256 2255 +f 2255 2254 2257 +f 2259 2258 2256 +f 2256 2257 2259 +f 2261 2260 2258 +f 2258 2259 2261 +f 2263 2262 2260 +f 2260 2261 2263 +f 2265 2264 2262 +f 2262 2263 2265 +f 2254 2255 2264 +f 2264 2265 2254 +f 2256 2260 2262 +f 2262 2264 2256 +f 2256 2258 2260 +f 2256 2264 2255 +f 2269 2268 2267 +f 2267 2266 2269 +f 2271 2267 2268 +f 2268 2270 2271 +f 2275 2274 2273 +f 2273 2272 2275 +f 2277 2276 2272 +f 2272 2273 2277 +f 2274 2266 2267 +f 2267 2273 2274 +f 2275 2269 2266 +f 2266 2274 2275 +f 2272 2268 2269 +f 2269 2275 2272 +f 2276 2270 2268 +f 2268 2272 2276 +f 2277 2271 2270 +f 2270 2276 2277 +f 2273 2267 2271 +f 2271 2277 2273 +f 2281 2280 2279 +f 2279 2278 2281 +f 2283 2279 2280 +f 2280 2282 2283 +f 2285 2283 2282 +f 2282 2284 2285 +f 2289 2288 2287 +f 2287 2286 2289 +f 2291 2290 2286 +f 2286 2287 2291 +f 2293 2292 2290 +f 2290 2291 2293 +f 2288 2278 2279 +f 2279 2287 2288 +f 2289 2281 2278 +f 2278 2288 2289 +f 2286 2280 2281 +f 2281 2289 2286 +f 2290 2282 2280 +f 2280 2286 2290 +f 2287 2279 2283 +f 2283 2291 2287 +f 2292 2284 2282 +f 2282 2290 2292 +f 2293 2285 2284 +f 2284 2292 2293 +f 2291 2283 2285 +f 2285 2293 2291 +f 2297 2296 2295 +f 2295 2294 2297 +f 2301 2300 2299 +f 2299 2298 2301 +f 2296 2301 2298 +f 2298 2295 2296 +f 2305 2304 2303 +f 2303 2302 2305 +f 2307 2306 2304 +f 2304 2305 2307 +f 2309 2308 2306 +f 2306 2307 2309 +f 2313 2312 2311 +f 2311 2310 2313 +f 2317 2316 2315 +f 2315 2314 2317 +f 2319 2318 2316 +f 2316 2317 2319 +f 2321 2320 2318 +f 2318 2319 2321 +f 2302 2303 2320 +f 2320 2321 2302 +f 2308 2316 2318 +f 2318 2320 2308 +f 2308 2315 2316 +f 2306 2308 2320 +f 2320 2304 2306 +f 2304 2320 2303 +f 2325 2324 2323 +f 2323 2322 2325 +f 2322 2327 2326 +f 2326 2325 2322 +f 2331 2330 2329 +f 2329 2328 2331 +f 2328 2329 2333 +f 2333 2332 2328 +f 2337 2336 2335 +f 2335 2334 2337 +f 2334 2335 2339 +f 2339 2338 2334 +f 2338 2341 2340 +f 2340 2334 2338 +f 2334 2340 2342 +f 2342 2337 2334 +f 2344 2326 2327 +f 2327 2343 2344 +f 2343 2332 2333 +f 2333 2344 2343 +f 2346 2323 2324 +f 2324 2345 2346 +f 2345 2330 2331 +f 2331 2346 2345 +f 2350 2349 2348 +f 2348 2347 2350 +f 2347 2352 2351 +f 2351 2350 2347 +f 2356 2355 2354 +f 2354 2353 2356 +f 2353 2354 2358 +f 2358 2357 2353 +f 2360 2351 2352 +f 2352 2359 2360 +f 2359 2355 2356 +f 2356 2360 2359 +f 2359 2352 2347 +f 2347 2361 2359 +f 2361 2347 2348 +f 2348 2362 2361 +f 2362 2358 2354 +f 2354 2361 2362 +f 2361 2354 2355 +f 2355 2359 2361 +f 2362 2348 2349 +f 2349 2363 2362 +f 2363 2357 2358 +f 2358 2362 2363 +f 2323 2349 2350 +f 2350 2322 2323 +f 2322 2350 2351 +f 2351 2327 2322 +f 2328 2353 2357 +f 2357 2331 2328 +f 2332 2356 2353 +f 2353 2328 2332 +f 2327 2351 2360 +f 2360 2343 2327 +f 2343 2360 2356 +f 2356 2332 2343 +f 2346 2363 2349 +f 2349 2323 2346 +f 2331 2357 2363 +f 2363 2346 2331 +f 2325 2365 2364 +f 2364 2324 2325 +f 2326 2366 2365 +f 2365 2325 2326 +f 2344 2367 2366 +f 2366 2326 2344 +f 2333 2368 2367 +f 2367 2344 2333 +f 2329 2369 2368 +f 2368 2333 2329 +f 2330 2370 2369 +f 2369 2329 2330 +f 2345 2371 2370 +f 2370 2330 2345 +f 2324 2364 2371 +f 2371 2345 2324 +f 2365 2335 2336 +f 2336 2364 2365 +f 2366 2339 2335 +f 2335 2365 2366 +f 2367 2338 2339 +f 2339 2366 2367 +f 2368 2341 2338 +f 2338 2367 2368 +f 2369 2340 2341 +f 2341 2368 2369 +f 2370 2342 2340 +f 2340 2369 2370 +f 2371 2337 2342 +f 2342 2370 2371 +f 2364 2336 2337 +f 2337 2371 2364 +f 2375 2374 2373 +f 2373 2372 2375 +f 2377 2376 2374 +f 2374 2375 2377 +f 2379 2378 2376 +f 2376 2377 2379 +f 2381 2380 2378 +f 2378 2379 2381 +f 2383 2382 2380 +f 2380 2381 2383 +f 2385 2384 2382 +f 2382 2383 2385 +f 2387 2386 2384 +f 2384 2385 2387 +f 2372 2373 2386 +f 2386 2387 2372 +f 2381 2377 2375 +f 2375 2372 2381 +f 2381 2379 2377 +f 2383 2381 2372 +f 2372 2385 2383 +f 2385 2372 2387 +f 2374 2389 2388 +f 2388 2373 2374 +f 2376 2390 2389 +f 2389 2374 2376 +f 2378 2391 2390 +f 2390 2376 2378 +f 2380 2392 2391 +f 2391 2378 2380 +f 2382 2393 2392 +f 2392 2380 2382 +f 2384 2394 2393 +f 2393 2382 2384 +f 2386 2395 2394 +f 2394 2384 2386 +f 2373 2388 2395 +f 2395 2386 2373 +f 2389 2397 2396 +f 2396 2388 2389 +f 2390 2398 2397 +f 2397 2389 2390 +f 2391 2399 2398 +f 2398 2390 2391 +f 2392 2400 2399 +f 2399 2391 2392 +f 2393 2401 2400 +f 2400 2392 2393 +f 2394 2402 2401 +f 2401 2393 2394 +f 2395 2403 2402 +f 2402 2394 2395 +f 2388 2396 2403 +f 2403 2395 2388 +f 2397 2405 2404 +f 2404 2396 2397 +f 2398 2406 2405 +f 2405 2397 2398 +f 2399 2407 2406 +f 2406 2398 2399 +f 2400 2408 2407 +f 2407 2399 2400 +f 2401 2409 2408 +f 2408 2400 2401 +f 2402 2410 2409 +f 2409 2401 2402 +f 2403 2411 2410 +f 2410 2402 2403 +f 2396 2404 2411 +f 2411 2403 2396 +f 2405 2413 2412 +f 2412 2404 2405 +f 2406 2414 2413 +f 2413 2405 2406 +f 2407 2415 2414 +f 2414 2406 2407 +f 2408 2416 2415 +f 2415 2407 2408 +f 2409 2417 2416 +f 2416 2408 2409 +f 2410 2418 2417 +f 2417 2409 2410 +f 2411 2419 2418 +f 2418 2410 2411 +f 2404 2412 2419 +f 2419 2411 2404 +f 2416 2418 2419 +f 2419 2412 2416 +f 2416 2417 2418 +f 2415 2416 2412 +f 2412 2414 2415 +f 2414 2412 2413 +f 2423 2422 2421 +f 2421 2420 2423 +f 2427 2426 2425 +f 2425 2424 2427 +f 2422 2424 2425 +f 2425 2421 2422 +f 2427 2424 2422 +f 2422 2423 2427 +f 2431 2430 2429 +f 2429 2428 2431 +f 2426 2430 2431 +f 2431 2420 2426 +f 2428 2423 2420 +f 2420 2431 2428 +f 2430 2426 2427 +f 2427 2429 2430 +f 2425 2426 2420 +f 2420 2421 2425 +f 2428 2433 2432 +f 2432 2423 2428 +f 2429 2434 2433 +f 2433 2428 2429 +f 2427 2435 2434 +f 2434 2429 2427 +f 2423 2432 2435 +f 2435 2427 2423 +f 2435 2432 2433 +f 2433 2434 2435 +f 2439 2438 2437 +f 2437 2436 2439 +f 2441 2440 2438 +f 2438 2439 2441 +f 2443 2442 2440 +f 2440 2441 2443 +f 2445 2444 2442 +f 2442 2443 2445 +f 2447 2446 2444 +f 2444 2445 2447 +f 2449 2448 2446 +f 2446 2447 2449 +f 2451 2450 2448 +f 2448 2449 2451 +f 2436 2437 2450 +f 2450 2451 2436 +f 2447 2443 2441 +f 2441 2439 2447 +f 2447 2445 2443 +f 2449 2447 2439 +f 2439 2451 2449 +f 2451 2439 2436 +f 2455 2454 2453 +f 2453 2452 2455 +f 2457 2456 2454 +f 2454 2455 2457 +f 2459 2458 2456 +f 2456 2457 2459 +f 2461 2460 2458 +f 2458 2459 2461 +f 2463 2462 2460 +f 2460 2461 2463 +f 2465 2464 2462 +f 2462 2463 2465 +f 2467 2466 2464 +f 2464 2465 2467 +f 2452 2453 2466 +f 2466 2467 2452 +f 2467 2459 2457 +f 2457 2455 2467 +f 2461 2459 2467 +f 2467 2463 2461 +f 2467 2465 2463 +f 2467 2455 2452 +f 2302 2469 2468 +f 2468 2305 2302 +f 2305 2468 2470 +f 2470 2307 2305 +f 2307 2470 2471 +f 2471 2309 2307 +f 2309 2471 2472 +f 2472 2314 2309 +f 2314 2472 2473 +f 2473 2317 2314 +f 2317 2473 2474 +f 2474 2319 2317 +f 2319 2474 2475 +f 2475 2321 2319 +f 2321 2475 2469 +f 2469 2302 2321 +f 2469 2477 2476 +f 2476 2468 2469 +f 2468 2476 2478 +f 2478 2470 2468 +f 2470 2478 2479 +f 2479 2471 2470 +f 2471 2479 2480 +f 2480 2472 2471 +f 2472 2480 2481 +f 2481 2473 2472 +f 2473 2481 2482 +f 2482 2474 2473 +f 2474 2482 2483 +f 2483 2475 2474 +f 2475 2483 2477 +f 2477 2469 2475 +f 2481 2479 2478 +f 2478 2476 2481 +f 2481 2480 2479 +f 2482 2481 2476 +f 2476 2483 2482 +f 2483 2476 2477 +f 2309 2485 2484 +f 2484 2308 2309 +f 2314 2486 2485 +f 2485 2309 2314 +f 2315 2487 2486 +f 2486 2314 2315 +f 2308 2484 2487 +f 2487 2315 2308 +f 2485 2310 2311 +f 2311 2484 2485 +f 2486 2313 2310 +f 2310 2485 2486 +f 2487 2312 2313 +f 2313 2486 2487 +f 2484 2311 2312 +f 2312 2487 2484 +f 2491 2490 2489 +f 2489 2488 2491 +f 2493 2492 2490 +f 2490 2491 2493 +f 2495 2494 2492 +f 2492 2493 2495 +f 2497 2496 2494 +f 2494 2495 2497 +f 2499 2498 2496 +f 2496 2497 2499 +f 2501 2500 2498 +f 2498 2499 2501 +f 2503 2502 2500 +f 2500 2501 2503 +f 2488 2489 2502 +f 2502 2503 2488 +f 2490 2505 2504 +f 2504 2489 2490 +f 2492 2506 2505 +f 2505 2490 2492 +f 2494 2507 2506 +f 2506 2492 2494 +f 2496 2508 2507 +f 2507 2494 2496 +f 2498 2509 2508 +f 2508 2496 2498 +f 2500 2510 2509 +f 2509 2498 2500 +f 2502 2511 2510 +f 2510 2500 2502 +f 2489 2504 2511 +f 2511 2502 2489 +f 2505 2513 2512 +f 2512 2504 2505 +f 2506 2514 2513 +f 2513 2505 2506 +f 2507 2515 2514 +f 2514 2506 2507 +f 2508 2516 2515 +f 2515 2507 2508 +f 2509 2517 2516 +f 2516 2508 2509 +f 2510 2518 2517 +f 2517 2509 2510 +f 2511 2519 2518 +f 2518 2510 2511 +f 2504 2512 2519 +f 2519 2511 2504 +f 2513 2521 2520 +f 2520 2512 2513 +f 2514 2522 2521 +f 2521 2513 2514 +f 2515 2523 2522 +f 2522 2514 2515 +f 2516 2524 2523 +f 2523 2515 2516 +f 2517 2525 2524 +f 2524 2516 2517 +f 2518 2526 2525 +f 2525 2517 2518 +f 2519 2527 2526 +f 2526 2518 2519 +f 2512 2520 2527 +f 2527 2519 2512 +f 2522 2528 2294 +f 2294 2521 2522 +f 2523 2529 2528 +f 2528 2522 2523 +f 2524 2530 2529 +f 2529 2523 2524 +f 2525 2531 2530 +f 2530 2524 2525 +f 2526 2299 2531 +f 2531 2525 2526 +f 2527 2298 2299 +f 2299 2526 2527 +f 2520 2295 2298 +f 2298 2527 2520 +f 2521 2294 2295 +f 2295 2520 2521 +f 2488 2296 2297 +f 2297 2491 2488 +f 2491 2297 2532 +f 2532 2493 2491 +f 2493 2532 2533 +f 2533 2495 2493 +f 2495 2533 2534 +f 2534 2497 2495 +f 2497 2534 2535 +f 2535 2499 2497 +f 2499 2535 2300 +f 2300 2501 2499 +f 2501 2300 2301 +f 2301 2503 2501 +f 2503 2301 2296 +f 2296 2488 2503 +f 2294 2537 2536 +f 2536 2297 2294 +f 2528 2538 2537 +f 2537 2294 2528 +f 2297 2536 2539 +f 2539 2532 2297 +f 2529 2540 2538 +f 2538 2528 2529 +f 2532 2539 2541 +f 2541 2533 2532 +f 2530 2542 2540 +f 2540 2529 2530 +f 2533 2541 2543 +f 2543 2534 2533 +f 2531 2544 2542 +f 2542 2530 2531 +f 2534 2543 2545 +f 2545 2535 2534 +f 2299 2546 2544 +f 2544 2531 2299 +f 2300 2547 2546 +f 2546 2299 2300 +f 2535 2545 2547 +f 2547 2300 2535 +f 2538 2540 2541 +f 2541 2539 2538 +f 2542 2544 2545 +f 2545 2543 2542 +f 2539 2536 2537 +f 2537 2538 2539 +f 2541 2540 2542 +f 2542 2543 2541 +f 2545 2544 2546 +f 2546 2547 2545 +f 2551 2550 2549 +f 2549 2548 2551 +f 2555 2554 2553 +f 2553 2552 2555 +f 2559 2558 2557 +f 2557 2556 2559 +f 2552 2553 2550 +f 2550 2551 2552 +f 2563 2562 2561 +f 2561 2560 2563 +f 2554 2555 2548 +f 2548 2549 2554 +f 2560 2551 2548 +f 2548 2563 2560 +f 2556 2549 2550 +f 2550 2559 2556 +f 2562 2555 2552 +f 2552 2561 2562 +f 2558 2553 2554 +f 2554 2557 2558 +f 2561 2552 2551 +f 2551 2560 2561 +f 2559 2550 2553 +f 2553 2558 2559 +f 2557 2554 2549 +f 2549 2556 2557 +f 2563 2548 2555 +f 2555 2562 2563 +f 2567 2566 2565 +f 2565 2564 2567 +f 2569 2568 2566 +f 2566 2567 2569 +f 2571 2570 2568 +f 2568 2569 2571 +f 2573 2572 2570 +f 2570 2571 2573 +f 2575 2574 2572 +f 2572 2573 2575 +f 2564 2565 2574 +f 2574 2575 2564 +f 2573 2569 2567 +f 2567 2564 2573 +f 2573 2571 2569 +f 2573 2564 2575 +f 2579 2578 2577 +f 2577 2576 2579 +f 2579 2580 2578 +f 2579 2576 2581 +f 2566 2583 2582 +f 2582 2565 2566 +f 2568 2584 2583 +f 2583 2566 2568 +f 2570 2585 2584 +f 2584 2568 2570 +f 2572 2586 2585 +f 2585 2570 2572 +f 2574 2587 2586 +f 2586 2572 2574 +f 2565 2582 2587 +f 2587 2574 2565 +f 2583 2589 2588 +f 2588 2582 2583 +f 2584 2590 2589 +f 2589 2583 2584 +f 2585 2591 2590 +f 2590 2584 2585 +f 2586 2592 2591 +f 2591 2585 2586 +f 2587 2593 2592 +f 2592 2586 2587 +f 2582 2588 2593 +f 2593 2587 2582 +f 2589 2595 2594 +f 2594 2588 2589 +f 2590 2596 2595 +f 2595 2589 2590 +f 2591 2597 2596 +f 2596 2590 2591 +f 2592 2598 2597 +f 2597 2591 2592 +f 2593 2599 2598 +f 2598 2592 2593 +f 2588 2594 2599 +f 2599 2593 2588 +f 2595 2579 2581 +f 2581 2594 2595 +f 2596 2580 2579 +f 2579 2595 2596 +f 2597 2578 2580 +f 2580 2596 2597 +f 2598 2577 2578 +f 2578 2597 2598 +f 2599 2576 2577 +f 2577 2598 2599 +f 2594 2581 2576 +f 2576 2599 2594 +f 2603 2602 2601 +f 2601 2600 2603 +f 2603 2604 2602 +f 2603 2600 2605 +f 2605 2607 2606 +f 2606 2603 2605 +f 2603 2606 2608 +f 2608 2604 2603 +f 2604 2608 2609 +f 2609 2602 2604 +f 2602 2609 2610 +f 2610 2601 2602 +f 2601 2610 2611 +f 2611 2600 2601 +f 2600 2611 2607 +f 2607 2605 2600 +f 2611 2609 2608 +f 2608 2606 2611 +f 2611 2610 2609 +f 2611 2606 2607 +f 2615 2614 2613 +f 2613 2612 2615 +f 2617 2616 2612 +f 2612 2613 2617 +f 2617 2613 2619 +f 2619 2618 2617 +f 2618 2619 2621 +f 2621 2620 2618 +f 2623 2621 2619 +f 2619 2622 2623 +f 2625 2623 2622 +f 2622 2624 2625 +f 2627 2620 2621 +f 2621 2626 2627 +f 2628 2626 2621 +f 2621 2623 2628 +f 2629 2628 2623 +f 2623 2625 2629 +f 2631 2618 2620 +f 2620 2630 2631 +f 2631 2630 2633 +f 2633 2632 2631 +f 2632 2633 2635 +f 2635 2634 2632 +f 2631 2632 2637 +f 2637 2636 2631 +f 2632 2634 2638 +f 2638 2637 2632 +f 2642 2641 2640 +f 2640 2639 2642 +f 2646 2645 2644 +f 2644 2643 2646 +f 2645 2641 2642 +f 2642 2644 2645 +f 2644 2642 2639 +f 2639 2643 2644 +f 2643 2639 2640 +f 2640 2646 2643 +f 2648 2640 2641 +f 2641 2647 2648 +f 2650 2645 2646 +f 2646 2649 2650 +f 2647 2641 2645 +f 2645 2650 2647 +f 2649 2646 2640 +f 2640 2648 2649 +f 2652 2648 2647 +f 2647 2651 2652 +f 2654 2650 2649 +f 2649 2653 2654 +f 2651 2647 2650 +f 2650 2654 2651 +f 2653 2649 2648 +f 2648 2652 2653 +f 2658 2657 2656 +f 2656 2655 2658 +f 2660 2657 2658 +f 2658 2659 2660 +f 2661 2656 2657 +f 2657 2660 2661 +f 2662 2655 2656 +f 2656 2661 2662 +f 2659 2658 2655 +f 2655 2662 2659 +f 2659 2662 2661 +f 2661 2660 2659 +f 2666 2665 2664 +f 2664 2663 2666 +f 2663 2668 2667 +f 2667 2666 2663 +f 2670 2666 2667 +f 2667 2669 2670 +f 2626 2670 2669 +f 2669 2627 2626 +f 2670 2626 2628 +f 2628 2671 2670 +f 2671 2628 2629 +f 2629 2672 2671 +f 2630 2620 2627 +f 2627 2673 2630 +f 2627 2669 2674 +f 2674 2673 2627 +f 2676 2673 2674 +f 2674 2675 2676 +f 2678 2676 2675 +f 2675 2677 2678 +f 2680 2675 2674 +f 2674 2679 2680 +f 2681 2677 2675 +f 2675 2680 2681 +f 2685 2684 2683 +f 2683 2682 2685 +f 2687 2683 2684 +f 2684 2686 2687 +f 2687 2689 2688 +f 2688 2683 2687 +f 2689 2691 2690 +f 2690 2688 2689 +f 2693 2692 2688 +f 2688 2690 2693 +f 2695 2694 2692 +f 2692 2693 2695 +f 2697 2696 2690 +f 2690 2691 2697 +f 2698 2693 2690 +f 2690 2696 2698 +f 2699 2695 2693 +f 2693 2698 2699 +f 2701 2700 2691 +f 2691 2689 2701 +f 2701 2703 2702 +f 2702 2700 2701 +f 2703 2705 2704 +f 2704 2702 2703 +f 2701 2707 2706 +f 2706 2703 2701 +f 2703 2706 2708 +f 2708 2705 2703 +f 2712 2711 2710 +f 2710 2709 2712 +f 2716 2715 2714 +f 2714 2713 2716 +f 2718 2717 2716 +f 2716 2713 2718 +f 2719 2718 2713 +f 2713 2714 2719 +f 2720 2719 2714 +f 2714 2715 2720 +f 2717 2720 2715 +f 2715 2716 2717 +f 2717 2718 2719 +f 2719 2720 2717 +f 2724 2723 2722 +f 2722 2721 2724 +f 2723 2724 2726 +f 2726 2725 2723 +f 2728 2727 2726 +f 2726 2724 2728 +f 2696 2697 2727 +f 2727 2728 2696 +f 2728 2729 2698 +f 2698 2696 2728 +f 2729 2730 2699 +f 2699 2698 2729 +f 2700 2731 2697 +f 2697 2691 2700 +f 2697 2731 2732 +f 2732 2727 2697 +f 2734 2733 2732 +f 2732 2731 2734 +f 2736 2735 2733 +f 2733 2734 2736 +f 2738 2737 2732 +f 2732 2733 2738 +f 2739 2738 2733 +f 2733 2735 2739 +f 2614 2615 2685 +f 2685 2682 2614 +f 2615 2612 2684 +f 2684 2685 2615 +f 2613 2614 2682 +f 2682 2683 2613 +f 2616 2617 2687 +f 2687 2686 2616 +f 2612 2616 2686 +f 2686 2684 2612 +f 2617 2618 2689 +f 2689 2687 2617 +f 2619 2613 2683 +f 2683 2688 2619 +f 2622 2619 2688 +f 2688 2692 2622 +f 2625 2624 2694 +f 2694 2695 2625 +f 2624 2622 2692 +f 2692 2694 2624 +f 2629 2625 2695 +f 2695 2699 2629 +f 2618 2631 2701 +f 2701 2689 2618 +f 2633 2630 2700 +f 2700 2702 2633 +f 2634 2635 2704 +f 2704 2705 2634 +f 2635 2633 2702 +f 2702 2704 2635 +f 2631 2636 2707 +f 2707 2701 2631 +f 2636 2637 2706 +f 2706 2707 2636 +f 2637 2638 2708 +f 2708 2706 2637 +f 2638 2634 2705 +f 2705 2708 2638 +f 2665 2666 2724 +f 2724 2721 2665 +f 2663 2664 2722 +f 2722 2723 2663 +f 2664 2665 2721 +f 2721 2722 2664 +f 2668 2663 2723 +f 2723 2725 2668 +f 2667 2668 2725 +f 2725 2726 2667 +f 2666 2670 2728 +f 2728 2724 2666 +f 2669 2667 2726 +f 2726 2727 2669 +f 2670 2671 2729 +f 2729 2728 2670 +f 2671 2672 2730 +f 2730 2729 2671 +f 2672 2629 2699 +f 2699 2730 2672 +f 2630 2673 2731 +f 2731 2700 2630 +f 2674 2669 2727 +f 2727 2732 2674 +f 2673 2676 2734 +f 2734 2731 2673 +f 2676 2678 2736 +f 2736 2734 2676 +f 2678 2677 2735 +f 2735 2736 2678 +f 2680 2679 2737 +f 2737 2738 2680 +f 2679 2674 2732 +f 2732 2737 2679 +f 2677 2681 2739 +f 2739 2735 2677 +f 2681 2680 2738 +f 2738 2739 2681 +f 2743 2742 2741 +f 2741 2740 2743 +f 2745 2741 2742 +f 2742 2744 2745 +f 2749 2748 2747 +f 2747 2746 2749 +f 2751 2750 2746 +f 2746 2747 2751 +f 2748 2740 2741 +f 2741 2747 2748 +f 2749 2743 2740 +f 2740 2748 2749 +f 2746 2742 2743 +f 2743 2749 2746 +f 2750 2744 2742 +f 2742 2746 2750 +f 2751 2745 2744 +f 2744 2750 2751 +f 2747 2741 2745 +f 2745 2751 2747 +f 2755 2754 2753 +f 2753 2752 2755 +f 2757 2756 2754 +f 2754 2755 2757 +f 2758 2757 2755 +f 2755 2752 2758 +f 2759 2758 2752 +f 2752 2753 2759 +f 2756 2759 2753 +f 2753 2754 2756 +f 2756 2757 2758 +f 2758 2759 2756 +f 2254 2761 2760 +f 2760 2257 2254 +f 2257 2760 2762 +f 2762 2259 2257 +f 2259 2762 2763 +f 2763 2261 2259 +f 2261 2763 2764 +f 2764 2263 2261 +f 2263 2764 2765 +f 2765 2265 2263 +f 2265 2765 2761 +f 2761 2254 2265 +f 2761 2767 2766 +f 2766 2760 2761 +f 2760 2766 2768 +f 2768 2762 2760 +f 2762 2768 2769 +f 2769 2763 2762 +f 2763 2769 2770 +f 2770 2764 2763 +f 2764 2770 2771 +f 2771 2765 2764 +f 2765 2771 2767 +f 2767 2761 2765 +f 2771 2769 2768 +f 2768 2766 2771 +f 2771 2770 2769 +f 2771 2766 2767 +f 2775 2774 2773 +f 2773 2772 2775 +f 2777 2776 2774 +f 2774 2775 2777 +f 2779 2778 2772 +f 2772 2773 2779 +f 2776 2779 2773 +f 2773 2774 2776 +f 2781 2780 2776 +f 2776 2777 2781 +f 2783 2782 2778 +f 2778 2779 2783 +f 2780 2783 2779 +f 2779 2776 2780 +f 2787 2786 2785 +f 2785 2784 2787 +f 2786 2789 2788 +f 2788 2785 2786 +f 2789 2791 2790 +f 2790 2788 2789 +f 2791 2793 2792 +f 2792 2790 2791 +f 2795 2792 2793 +f 2793 2794 2795 +f 2796 2795 2794 +f 2798 2796 2794 +f 2794 2797 2798 +f 2799 2798 2797 +f 2797 2787 2784 +f 2784 2799 2797 +f 2790 2792 2801 +f 2801 2800 2790 +f 2799 2784 2803 +f 2803 2802 2799 +f 2800 2801 2805 +f 2805 2804 2800 +f 2802 2803 2807 +f 2807 2806 2802 +f 2796 2798 2809 +f 2809 2808 2796 +f 2812 2808 2811 +f 2811 2810 2812 +f 2808 2809 2813 +f 2813 2811 2808 +f 2813 2809 2815 +f 2815 2814 2813 +f 2814 2815 2817 +f 2817 2816 2814 +f 2816 2817 2819 +f 2819 2818 2816 +f 2812 2810 2821 +f 2821 2820 2812 +f 2820 2821 2823 +f 2823 2822 2820 +f 2822 2823 2825 +f 2825 2824 2822 +f 2829 2828 2827 +f 2827 2826 2829 +f 2826 2827 2831 +f 2831 2830 2826 +f 2830 2831 2833 +f 2833 2832 2830 +f 2832 2833 2835 +f 2835 2834 2832 +f 2837 2836 2834 +f 2834 2835 2837 +f 2837 2838 2836 +f 2840 2839 2836 +f 2836 2838 2840 +f 2840 2841 2839 +f 2839 2841 2828 +f 2828 2829 2839 +f 2833 2843 2842 +f 2842 2835 2833 +f 2841 2845 2844 +f 2844 2828 2841 +f 2843 2847 2846 +f 2846 2842 2843 +f 2845 2849 2848 +f 2848 2844 2845 +f 2838 2851 2850 +f 2850 2840 2838 +f 2854 2853 2852 +f 2852 2851 2854 +f 2851 2852 2855 +f 2855 2850 2851 +f 2855 2857 2856 +f 2856 2850 2855 +f 2857 2859 2858 +f 2858 2856 2857 +f 2859 2861 2860 +f 2860 2858 2859 +f 2854 2863 2862 +f 2862 2853 2854 +f 2863 2865 2864 +f 2864 2862 2863 +f 2865 2867 2866 +f 2866 2864 2865 +f 2786 2787 2829 +f 2829 2826 2786 +f 2784 2785 2827 +f 2827 2828 2784 +f 2789 2786 2826 +f 2826 2830 2789 +f 2785 2788 2831 +f 2831 2827 2785 +f 2791 2789 2830 +f 2830 2832 2791 +f 2788 2790 2833 +f 2833 2831 2788 +f 2793 2791 2832 +f 2832 2834 2793 +f 2794 2793 2834 +f 2834 2836 2794 +f 2792 2795 2837 +f 2837 2835 2792 +f 2797 2794 2836 +f 2836 2839 2797 +f 2798 2799 2841 +f 2841 2840 2798 +f 2787 2797 2839 +f 2839 2829 2787 +f 2790 2800 2843 +f 2843 2833 2790 +f 2801 2792 2835 +f 2835 2842 2801 +f 2799 2802 2845 +f 2845 2841 2799 +f 2803 2784 2828 +f 2828 2844 2803 +f 2800 2804 2847 +f 2847 2843 2800 +f 2804 2805 2846 +f 2846 2847 2804 +f 2805 2801 2842 +f 2842 2846 2805 +f 2802 2806 2849 +f 2849 2845 2802 +f 2806 2807 2848 +f 2848 2849 2806 +f 2807 2803 2844 +f 2844 2848 2807 +f 2809 2798 2840 +f 2840 2850 2809 +f 2810 2811 2852 +f 2852 2853 2810 +f 2811 2813 2855 +f 2855 2852 2811 +f 2813 2814 2857 +f 2857 2855 2813 +f 2815 2809 2850 +f 2850 2856 2815 +f 2814 2816 2859 +f 2859 2857 2814 +f 2817 2815 2856 +f 2856 2858 2817 +f 2816 2818 2861 +f 2861 2859 2816 +f 2818 2819 2860 +f 2860 2861 2818 +f 2819 2817 2858 +f 2858 2860 2819 +f 2812 2820 2863 +f 2863 2854 2812 +f 2821 2810 2853 +f 2853 2862 2821 +f 2820 2822 2865 +f 2865 2863 2820 +f 2823 2821 2862 +f 2862 2864 2823 +f 2822 2824 2867 +f 2867 2865 2822 +f 2824 2825 2866 +f 2866 2867 2824 +f 2825 2823 2864 +f 2864 2866 2825 +f 2795 2796 2808 +f 2808 2812 2795 +f 2837 2795 2812 +f 2812 2854 2837 +f 2851 2838 2837 +f 2837 2854 2851 +f 2150 2868 2158 +f 2158 2149 2150 +f 2158 2868 2161 +f 2161 2160 2158 +f 2152 2869 2157 +f 2157 2151 2152 +f 2869 2870 2159 +f 2159 2157 2869 +f 2870 2153 2154 +f 2154 2159 2870 +f 2155 2161 2869 +f 2869 2152 2155 +f 2161 2868 2870 +f 2870 2869 2161 +f 2868 2150 2153 +f 2153 2870 2868 +f 2872 2871 1879 +f 1879 1880 2872 +f 2873 2872 1880 +f 1880 1881 2873 +f 2874 2873 1881 +f 1881 1882 2874 +f 2875 2874 1882 +f 1882 1883 2875 +f 2876 2875 1883 +f 1883 1884 2876 +f 2877 2876 1884 +f 1884 1885 2877 +f 2871 2877 1885 +f 1885 1879 2871 +f 2879 2878 2871 +f 2871 2872 2879 +f 2880 2879 2872 +f 2872 2873 2880 +f 2881 2880 2873 +f 2873 2874 2881 +f 2882 2881 2874 +f 2874 2875 2882 +f 2883 2882 2875 +f 2875 2876 2883 +f 2884 2883 2876 +f 2876 2877 2884 +f 2878 2884 2877 +f 2877 2871 2878 +f 2879 2882 2883 +f 2883 2884 2879 +f 2881 2882 2879 +f 2879 2880 2881 +f 2879 2884 2878 +f 2652 2651 2654 +f 2654 2653 2652 +f 2885 2886 2887 +f 2885 2888 2886 +f 2889 2887 2890 +f 2889 2885 2887 +f 2891 2890 2892 +f 2891 2889 2890 +f 2893 2892 2894 +f 2893 2891 2892 +f 2895 2956 2896 +f 2895 2897 2956 +f 2898 2896 2899 +f 2898 2895 2896 +f 2888 2899 2886 +f 2888 2898 2899 +f 2900 2901 2902 +f 2903 2901 2900 +f 2903 2904 2901 +f 2905 2904 2903 +f 2905 2906 2904 +f 2907 2908 2909 +f 2910 2908 2907 +f 2910 2911 2908 +f 2912 2911 2910 +f 2912 2913 2911 +f 2914 2915 2916 +f 2915 2914 2917 +f 2918 2917 2919 +f 2918 2915 2917 +f 2920 2919 2921 +f 2920 2918 2919 +f 2922 2921 2923 +f 2922 2920 2921 +f 2924 2923 2925 +f 2924 2922 2923 +f 2926 2914 2927 +f 2927 2914 2916 +f 2926 2924 2925 +f 2926 2927 2924 +f 2928 2929 2930 +f 2928 2931 2929 +f 2932 2933 2934 +f 2932 2935 2933 +f 2936 2937 2938 +f 2936 2939 2937 +f 2940 2941 2942 +f 2940 2943 2941 +f 2944 2945 2946 +f 2944 2947 2945 +f 2948 2949 2950 +f 2948 2951 2949 +f 2952 2953 2954 +f 2952 2955 2953 +f 2960 2959 2958 +f 2958 2957 2960 +f 2962 2960 2957 +f 2957 2961 2962 +f 2964 2962 2961 +f 2961 2963 2964 +f 2966 2964 2963 +f 2963 2965 2966 +f 2968 2966 2965 +f 2965 2967 2968 +f 2970 2968 2967 +f 2967 2969 2970 +f 2959 2970 2969 +f 2969 2958 2959 +f 2962 2966 2968 +f 2968 2970 2962 +f 2962 2964 2966 +f 2959 2960 2962 +f 2962 2970 2959 +f 2969 2965 2963 +f 2963 2961 2969 +f 2969 2967 2965 +f 2957 2958 2969 +f 2969 2961 2957 +f 2971 2975 2976 +f 2976 2972 2971 +f 2972 2973 2974 +f 2974 2971 2972 +f 2973 2984 2983 +f 2983 2974 2973 +f 2984 2986 2985 +f 2985 2983 2984 +f 2985 2986 2988 +f 2988 2987 2985 +f 2987 2988 2990 +f 2990 2989 2987 +f 2975 2977 2978 +f 2978 2976 2975 +f 2977 2979 2980 +f 2980 2978 2977 +f 2979 2981 2982 +f 2982 2980 2979 +f 2981 3001 3002 +f 3002 2982 2981 +f 3001 3008 3004 +f 3004 3002 3001 +f 3008 3009 3006 +f 3006 3004 3008 +f 3009 3010 3011 +f 3011 3006 3009 +f 3010 3014 3013 +f 3013 3011 3010 +f 3009 3017 3018 +f 3018 3010 3009 +f 3018 3019 3014 +f 3014 3010 3018 +f 3019 3020 3016 +f 3016 3014 3019 +f 3017 3021 3022 +f 3022 3018 3017 +f 3022 3023 3019 +f 3019 3018 3022 +f 3023 3024 3020 +f 3020 3019 3023 +f 3021 3025 3026 +f 3026 3022 3021 +f 3026 3027 3023 +f 3023 3022 3026 +f 3027 3028 3024 +f 3024 3023 3027 +f 3026 3030 3031 +f 3031 3027 3026 +f 3025 3029 3030 +f 3030 3026 3025 +f 3031 3030 3035 +f 3035 3034 3031 +f 3035 3042 3041 +f 3041 3034 3035 +f 3030 3029 3036 +f 3036 3035 3030 +f 3035 3036 3045 +f 3045 3042 3035 +f 3037 3038 3036 +f 3036 3029 3037 +f 3042 3045 3044 +f 3044 3043 3042 +f 3036 3038 3039 +f 3036 3039 3046 +f 3046 3045 3036 +f 3046 3044 3045 +f 3006 3007 3005 +f 3005 3004 3006 +f 3004 3005 3003 +f 3003 3002 3004 +f 3002 3003 3000 +f 3000 2982 3002 +f 2999 2980 2982 +f 2982 3000 2999 +f 2980 2999 2998 +f 2998 2978 2980 +f 3011 3012 3007 +f 3007 3006 3011 +f 3013 3015 3012 +f 3012 3011 3013 +f 3014 3016 3015 +f 3015 3013 3014 +f 2978 2998 2997 +f 2997 2976 2978 +f 3052 3053 2998 +f 2998 2999 3052 +f 2991 2972 2976 +f 2976 2997 2991 +f 2992 2993 2984 +f 2984 2973 2992 +f 2972 2991 2992 +f 2992 2973 2972 +f 2996 2990 2988 +f 2988 2995 2996 +f 2986 2994 2995 +f 2995 2988 2986 +f 2993 2994 2986 +f 2986 2984 2993 +f 3059 2991 2997 +f 2997 3056 3059 +f 2991 3059 3057 +f 3057 2992 2991 +f 2992 3057 3058 +f 3058 2993 2992 +f 2993 3058 3062 +f 3062 2994 2993 +f 2994 3062 3061 +f 3061 2995 2994 +f 3060 2996 2995 +f 2995 3061 3060 +f 2998 3053 3056 +f 3056 2997 2998 +f 3057 3059 3056 +f 3056 3063 3057 +f 3057 3063 3064 +f 3064 3058 3057 +f 3062 3058 3064 +f 3064 3065 3062 +f 3061 3062 3065 +f 3065 3066 3061 +f 3066 3067 3060 +f 3060 3061 3066 +f 3052 3051 3056 +f 3056 3053 3052 +f 3051 2999 3000 +f 3000 3050 3051 +f 3051 3052 2999 +f 3056 3051 3064 +f 3064 3063 3056 +f 3051 3050 3065 +f 3065 3064 3051 +f 3065 3050 3068 +f 3065 3068 3069 +f 3069 3066 3065 +f 3069 3070 3067 +f 3067 3066 3069 +f 3003 3049 3050 +f 3050 3000 3003 +f 3049 3071 3068 +f 3068 3050 3049 +f 3071 3072 3069 +f 3069 3068 3071 +f 3005 3048 3049 +f 3049 3003 3005 +f 3049 3048 3072 +f 3072 3071 3049 +f 3072 3073 3070 +f 3070 3069 3072 +f 3007 3047 3048 +f 3048 3005 3007 +f 3048 3074 3073 +f 3073 3072 3048 +f 3012 3054 3047 +f 3047 3007 3012 +f 3047 3075 3074 +f 3074 3048 3047 +f 3012 3015 3055 +f 3055 3054 3012 +f 3054 3076 3075 +f 3075 3047 3054 +f 3055 3077 3076 +f 3076 3054 3055 +f 3042 3043 3040 +f 3040 3041 3042 +f 3041 3040 3033 +f 3033 3034 3041 +f 3031 3032 3028 +f 3028 3027 3031 +f 3034 3033 3032 +f 3032 3031 3034 +f 3040 3078 3079 +f 3079 3033 3040 +f 3033 3079 3082 +f 3082 3032 3033 +f 3078 3081 3080 +f 3080 3079 3078 +f 3079 3080 3083 +f 3083 3082 3079 +f 3080 3087 3217 +f 3217 3083 3080 +f 3081 3218 3087 +f 3087 3080 3081 +f 3219 2989 2990 +f 2990 3220 3219 +f 3220 2990 2996 +f 2996 3221 3220 +f 3221 2996 3060 +f 3060 3084 3221 +f 3084 3060 3067 +f 3067 3222 3084 +f 3222 3067 3070 +f 3070 3088 3222 +f 3088 3070 3073 +f 3073 3085 3088 +f 3073 3074 3089 +f 3089 3085 3073 +f 3074 3075 3086 +f 3086 3089 3074 +f 3086 3075 3076 +f 3076 3090 3086 +f 3093 3091 3016 +f 3016 3020 3093 +f 3020 3024 3095 +f 3095 3093 3020 +f 3028 3097 3095 +f 3095 3024 3028 +f 3032 3082 3097 +f 3097 3028 3032 +f 3093 3094 3092 +f 3092 3091 3093 +f 3015 3016 3091 +f 3091 3055 3015 +f 3095 3096 3094 +f 3094 3093 3095 +f 3098 3096 3095 +f 3095 3097 3098 +f 3083 3098 3097 +f 3097 3082 3083 +f 3055 3091 3092 +f 3092 3077 3055 +f 3094 3101 3100 +f 3100 3092 3094 +f 3096 3102 3101 +f 3101 3094 3096 +f 3103 3102 3096 +f 3096 3098 3103 +f 3217 3103 3098 +f 3098 3083 3217 +f 3090 3076 3077 +f 3077 3099 3090 +f 3099 3077 3092 +f 3092 3100 3099 +f 3116 3117 3105 +f 3105 3104 3116 +f 3104 3105 3106 +f 3106 3107 3104 +f 3107 3106 3108 +f 3108 3109 3107 +f 3109 3108 3110 +f 3110 3111 3109 +f 3110 3113 3112 +f 3112 3111 3110 +f 3113 3115 3114 +f 3114 3112 3113 +f 3117 3116 3118 +f 3118 3119 3117 +f 3119 3118 3120 +f 3120 3121 3119 +f 3122 3123 3121 +f 3121 3120 3122 +f 3123 3122 3124 +f 3124 3125 3123 +f 3125 3124 3126 +f 3126 3127 3125 +f 3127 3126 3128 +f 3128 3129 3127 +f 3129 3128 3130 +f 3130 3131 3129 +f 3131 3130 3132 +f 3132 3133 3131 +f 3129 3131 3134 +f 3134 3135 3129 +f 3134 3131 3133 +f 3133 3136 3134 +f 3136 3133 3137 +f 3137 3138 3136 +f 3135 3134 3139 +f 3139 3140 3135 +f 3139 3134 3136 +f 3136 3141 3139 +f 3141 3136 3138 +f 3138 3142 3141 +f 3140 3139 3143 +f 3143 3144 3140 +f 3143 3139 3141 +f 3141 3145 3143 +f 3145 3141 3142 +f 3142 3146 3145 +f 3143 3145 3147 +f 3147 3148 3143 +f 3144 3143 3148 +f 3148 3149 3144 +f 3147 3151 3150 +f 3150 3148 3147 +f 3150 3151 3152 +f 3152 3153 3150 +f 3148 3150 3154 +f 3154 3149 3148 +f 3150 3153 3155 +f 3155 3154 3150 +f 3156 3149 3154 +f 3154 3157 3156 +f 3153 3159 3158 +f 3158 3155 3153 +f 3154 3160 3157 +f 3154 3155 3161 +f 3161 3160 3154 +f 3161 3155 3158 +f 3128 3126 3162 +f 3162 3163 3128 +f 3126 3124 3164 +f 3164 3162 3126 +f 3124 3122 3165 +f 3165 3164 3124 +f 3122 3120 3166 +f 3166 3165 3122 +f 3120 3118 3167 +f 3167 3166 3120 +f 3130 3128 3163 +f 3163 3168 3130 +f 3132 3130 3168 +f 3168 3169 3132 +f 3133 3132 3169 +f 3169 3137 3133 +f 3118 3116 3170 +f 3170 3167 3118 +f 3171 3166 3167 +f 3167 3172 3171 +f 3116 3104 3175 +f 3175 3170 3116 +f 3173 3107 3109 +f 3109 3174 3173 +f 3104 3107 3173 +f 3173 3175 3104 +f 3176 3177 3112 +f 3112 3114 3176 +f 3111 3112 3177 +f 3177 3178 3111 +f 3174 3109 3111 +f 3111 3178 3174 +f 3179 3185 3170 +f 3170 3175 3179 +f 3175 3173 3180 +f 3180 3179 3175 +f 3173 3174 3181 +f 3181 3180 3173 +f 3174 3178 3182 +f 3182 3181 3174 +f 3178 3177 3183 +f 3183 3182 3178 +f 3184 3183 3177 +f 3177 3176 3184 +f 3167 3170 3185 +f 3185 3172 3167 +f 3180 3186 3185 +f 3185 3179 3180 +f 3188 3186 3180 +f 3180 3181 3188 +f 3182 3189 3188 +f 3188 3181 3182 +f 3183 3190 3189 +f 3189 3182 3183 +f 3184 3191 3190 +f 3190 3183 3184 +f 3171 3172 3185 +f 3185 3187 3171 +f 3165 3166 3187 +f 3187 3192 3165 +f 3187 3166 3171 +f 3185 3186 3188 +f 3188 3187 3185 +f 3192 3187 3189 +f 3189 3194 3192 +f 3189 3187 3188 +f 3196 3194 3189 +f 3189 3190 3196 +f 3191 3197 3196 +f 3196 3190 3191 +f 3164 3165 3192 +f 3192 3193 3164 +f 3193 3192 3194 +f 3194 3195 3193 +f 3195 3194 3196 +f 3196 3198 3195 +f 3162 3164 3193 +f 3193 3199 3162 +f 3193 3195 3198 +f 3198 3199 3193 +f 3198 3196 3197 +f 3197 3200 3198 +f 3163 3162 3199 +f 3199 3201 3163 +f 3199 3198 3200 +f 3200 3202 3199 +f 3168 3163 3201 +f 3201 3203 3168 +f 3201 3199 3202 +f 3202 3204 3201 +f 3168 3203 3205 +f 3205 3169 3168 +f 3203 3201 3204 +f 3204 3206 3203 +f 3205 3203 3206 +f 3206 3207 3205 +f 3153 3152 3208 +f 3208 3159 3153 +f 3152 3151 3209 +f 3209 3208 3152 +f 3147 3145 3146 +f 3146 3210 3147 +f 3151 3147 3210 +f 3210 3209 3151 +f 3208 3209 3211 +f 3211 3212 3208 +f 3209 3210 3213 +f 3213 3211 3209 +f 3212 3211 3215 +f 3215 3214 3212 +f 3211 3213 3216 +f 3216 3215 3211 +f 3215 3216 3217 +f 3217 3087 3215 +f 3214 3215 3087 +f 3087 3218 3214 +f 3219 3220 3114 +f 3114 3115 3219 +f 3220 3221 3176 +f 3176 3114 3220 +f 3221 3084 3184 +f 3184 3176 3221 +f 3084 3222 3191 +f 3191 3184 3084 +f 3222 3088 3197 +f 3197 3191 3222 +f 3088 3085 3200 +f 3200 3197 3088 +f 3200 3085 3089 +f 3089 3202 3200 +f 3202 3089 3086 +f 3086 3204 3202 +f 3086 3090 3206 +f 3206 3204 3086 +f 3223 3138 3137 +f 3137 3224 3223 +f 3138 3223 3225 +f 3225 3142 3138 +f 3146 3142 3225 +f 3225 3226 3146 +f 3210 3146 3226 +f 3226 3213 3210 +f 3223 3224 3228 +f 3228 3227 3223 +f 3169 3205 3224 +f 3224 3137 3169 +f 3225 3223 3227 +f 3227 3229 3225 +f 3230 3226 3225 +f 3225 3229 3230 +f 3216 3213 3226 +f 3226 3230 3216 +f 3205 3207 3228 +f 3228 3224 3205 +f 3227 3228 3100 +f 3100 3101 3227 +f 3229 3227 3101 +f 3101 3102 3229 +f 3103 3230 3229 +f 3229 3102 3103 +f 3217 3216 3230 +f 3230 3103 3217 +f 3090 3099 3207 +f 3207 3206 3090 +f 3099 3100 3228 +f 3228 3207 3099 +f 3236 3235 3231 +f 3231 3232 3236 +f 3234 3233 3232 +f 3232 3231 3234 +f 3243 3244 3233 +f 3233 3234 3243 +f 3245 3246 3244 +f 3244 3243 3245 +f 3248 3246 3245 +f 3245 3247 3248 +f 3250 3248 3247 +f 3247 3249 3250 +f 3238 3237 3235 +f 3235 3236 3238 +f 3240 3239 3237 +f 3237 3238 3240 +f 3242 3241 3239 +f 3239 3240 3242 +f 3262 3261 3241 +f 3241 3242 3262 +f 3264 3268 3261 +f 3261 3262 3264 +f 3266 3269 3268 +f 3268 3264 3266 +f 3271 3270 3269 +f 3269 3266 3271 +f 3273 3274 3270 +f 3270 3271 3273 +f 3278 3277 3269 +f 3269 3270 3278 +f 3274 3279 3278 +f 3278 3270 3274 +f 3276 3280 3279 +f 3279 3274 3276 +f 3282 3281 3277 +f 3277 3278 3282 +f 3279 3283 3282 +f 3282 3278 3279 +f 3280 3284 3283 +f 3283 3279 3280 +f 3286 3285 3281 +f 3281 3282 3286 +f 3283 3287 3286 +f 3286 3282 3283 +f 3284 3288 3287 +f 3287 3283 3284 +f 3291 3290 3286 +f 3286 3287 3291 +f 3290 3289 3285 +f 3285 3286 3290 +f 3295 3290 3291 +f 3291 3294 3295 +f 3301 3302 3295 +f 3295 3294 3301 +f 3296 3289 3290 +f 3290 3295 3296 +f 3305 3296 3295 +f 3295 3302 3305 +f 3296 3298 3297 +f 3297 3289 3296 +f 3304 3305 3302 +f 3302 3303 3304 +f 3299 3298 3296 +f 3306 3299 3296 +f 3296 3305 3306 +f 3305 3304 3306 +f 3265 3267 3266 +f 3266 3264 3265 +f 3263 3265 3264 +f 3264 3262 3263 +f 3260 3263 3262 +f 3262 3242 3260 +f 3242 3240 3259 +f 3259 3260 3242 +f 3258 3259 3240 +f 3240 3238 3258 +f 3267 3272 3271 +f 3271 3266 3267 +f 3272 3275 3273 +f 3273 3271 3272 +f 3275 3276 3274 +f 3274 3273 3275 +f 3257 3258 3238 +f 3238 3236 3257 +f 3258 3313 3312 +f 3312 3259 3258 +f 3236 3232 3251 +f 3251 3257 3236 +f 3244 3253 3252 +f 3252 3233 3244 +f 3252 3251 3232 +f 3232 3233 3252 +f 3248 3250 3256 +f 3256 3255 3248 +f 3255 3254 3246 +f 3246 3248 3255 +f 3246 3254 3253 +f 3253 3244 3246 +f 3257 3251 3319 +f 3319 3316 3257 +f 3317 3319 3251 +f 3251 3252 3317 +f 3318 3317 3252 +f 3252 3253 3318 +f 3322 3318 3253 +f 3253 3254 3322 +f 3321 3322 3254 +f 3254 3255 3321 +f 3255 3256 3320 +f 3320 3321 3255 +f 3316 3313 3258 +f 3258 3257 3316 +f 3316 3319 3317 +f 3317 3323 3316 +f 3324 3323 3317 +f 3317 3318 3324 +f 3324 3318 3322 +f 3322 3325 3324 +f 3325 3322 3321 +f 3321 3326 3325 +f 3320 3327 3326 +f 3326 3321 3320 +f 3316 3311 3312 +f 3312 3313 3316 +f 3260 3259 3311 +f 3311 3310 3260 +f 3311 3259 3312 +f 3324 3311 3316 +f 3316 3323 3324 +f 3325 3310 3311 +f 3311 3324 3325 +f 3325 3328 3310 +f 3329 3328 3325 +f 3325 3326 3329 +f 3327 3330 3329 +f 3329 3326 3327 +f 3310 3309 3263 +f 3263 3260 3310 +f 3328 3331 3309 +f 3309 3310 3328 +f 3329 3332 3331 +f 3331 3328 3329 +f 3309 3308 3265 +f 3265 3263 3309 +f 3332 3308 3309 +f 3309 3331 3332 +f 3330 3333 3332 +f 3332 3329 3330 +f 3308 3307 3267 +f 3267 3265 3308 +f 3333 3334 3308 +f 3308 3332 3333 +f 3307 3314 3272 +f 3272 3267 3307 +f 3334 3335 3307 +f 3307 3308 3334 +f 3315 3275 3272 +f 3272 3314 3315 +f 3335 3336 3314 +f 3314 3307 3335 +f 3336 3337 3315 +f 3315 3314 3336 +f 3300 3303 3302 +f 3302 3301 3300 +f 3293 3300 3301 +f 3301 3294 3293 +f 3288 3292 3291 +f 3291 3287 3288 +f 3292 3293 3294 +f 3294 3291 3292 +f 3339 3338 3300 +f 3300 3293 3339 +f 3342 3339 3293 +f 3293 3292 3342 +f 3340 3341 3338 +f 3338 3339 3340 +f 3343 3340 3339 +f 3339 3342 3343 +f 3477 3347 3340 +f 3340 3343 3477 +f 3347 3478 3341 +f 3341 3340 3347 +f 3250 3249 3479 +f 3479 3480 3250 +f 3256 3250 3480 +f 3480 3481 3256 +f 3320 3256 3481 +f 3481 3344 3320 +f 3327 3320 3344 +f 3344 3482 3327 +f 3330 3327 3482 +f 3482 3348 3330 +f 3333 3330 3348 +f 3348 3345 3333 +f 3349 3334 3333 +f 3333 3345 3349 +f 3346 3335 3334 +f 3334 3349 3346 +f 3336 3335 3346 +f 3346 3350 3336 +f 3276 3351 3353 +f 3353 3280 3276 +f 3355 3284 3280 +f 3280 3353 3355 +f 3355 3357 3288 +f 3288 3284 3355 +f 3357 3342 3292 +f 3292 3288 3357 +f 3352 3354 3353 +f 3353 3351 3352 +f 3351 3276 3275 +f 3275 3315 3351 +f 3354 3356 3355 +f 3355 3353 3354 +f 3355 3356 3358 +f 3358 3357 3355 +f 3357 3358 3343 +f 3343 3342 3357 +f 3352 3351 3315 +f 3315 3337 3352 +f 3360 3361 3354 +f 3354 3352 3360 +f 3361 3362 3356 +f 3356 3354 3361 +f 3356 3362 3363 +f 3363 3358 3356 +f 3358 3363 3477 +f 3477 3343 3358 +f 3337 3336 3350 +f 3350 3359 3337 +f 3352 3337 3359 +f 3359 3360 3352 +f 3365 3377 3376 +f 3376 3364 3365 +f 3366 3365 3364 +f 3364 3367 3366 +f 3368 3366 3367 +f 3367 3369 3368 +f 3370 3368 3369 +f 3369 3371 3370 +f 3372 3373 3370 +f 3370 3371 3372 +f 3374 3375 3373 +f 3373 3372 3374 +f 3378 3376 3377 +f 3377 3379 3378 +f 3380 3378 3379 +f 3379 3381 3380 +f 3381 3383 3382 +f 3382 3380 3381 +f 3384 3382 3383 +f 3383 3385 3384 +f 3386 3384 3385 +f 3385 3387 3386 +f 3388 3386 3387 +f 3387 3389 3388 +f 3390 3388 3389 +f 3389 3391 3390 +f 3392 3390 3391 +f 3391 3393 3392 +f 3394 3391 3389 +f 3389 3395 3394 +f 3393 3391 3394 +f 3394 3396 3393 +f 3397 3393 3396 +f 3396 3398 3397 +f 3399 3394 3395 +f 3395 3400 3399 +f 3396 3394 3399 +f 3399 3401 3396 +f 3398 3396 3401 +f 3401 3402 3398 +f 3403 3399 3400 +f 3400 3404 3403 +f 3401 3399 3403 +f 3403 3405 3401 +f 3402 3401 3405 +f 3405 3406 3402 +f 3407 3405 3403 +f 3403 3408 3407 +f 3408 3403 3404 +f 3404 3409 3408 +f 3410 3411 3407 +f 3407 3408 3410 +f 3412 3411 3410 +f 3410 3413 3412 +f 3414 3410 3408 +f 3408 3409 3414 +f 3415 3413 3410 +f 3410 3414 3415 +f 3414 3409 3416 +f 3416 3417 3414 +f 3418 3419 3413 +f 3413 3415 3418 +f 3417 3420 3414 +f 3421 3415 3414 +f 3414 3420 3421 +f 3418 3415 3421 +f 3422 3386 3388 +f 3388 3423 3422 +f 3424 3384 3386 +f 3386 3422 3424 +f 3425 3382 3384 +f 3384 3424 3425 +f 3426 3380 3382 +f 3382 3425 3426 +f 3427 3378 3380 +f 3380 3426 3427 +f 3423 3388 3390 +f 3390 3428 3423 +f 3428 3390 3392 +f 3392 3429 3428 +f 3429 3392 3393 +f 3393 3397 3429 +f 3430 3376 3378 +f 3378 3427 3430 +f 3427 3426 3431 +f 3431 3432 3427 +f 3435 3364 3376 +f 3376 3430 3435 +f 3369 3367 3433 +f 3433 3434 3369 +f 3433 3367 3364 +f 3364 3435 3433 +f 3372 3437 3436 +f 3436 3374 3372 +f 3437 3372 3371 +f 3371 3438 3437 +f 3371 3369 3434 +f 3434 3438 3371 +f 3430 3445 3439 +f 3439 3435 3430 +f 3440 3433 3435 +f 3435 3439 3440 +f 3441 3434 3433 +f 3433 3440 3441 +f 3442 3438 3434 +f 3434 3441 3442 +f 3443 3437 3438 +f 3438 3442 3443 +f 3437 3443 3444 +f 3444 3436 3437 +f 3445 3430 3427 +f 3427 3432 3445 +f 3445 3446 3440 +f 3440 3439 3445 +f 3440 3446 3448 +f 3448 3441 3440 +f 3448 3449 3442 +f 3442 3441 3448 +f 3449 3450 3443 +f 3443 3442 3449 +f 3450 3451 3444 +f 3444 3443 3450 +f 3445 3432 3431 +f 3431 3447 3445 +f 3447 3426 3425 +f 3425 3452 3447 +f 3447 3431 3426 +f 3448 3446 3445 +f 3445 3447 3448 +f 3449 3447 3452 +f 3452 3454 3449 +f 3449 3448 3447 +f 3449 3454 3456 +f 3456 3450 3449 +f 3456 3457 3451 +f 3451 3450 3456 +f 3452 3425 3424 +f 3424 3453 3452 +f 3454 3452 3453 +f 3453 3455 3454 +f 3456 3454 3455 +f 3455 3458 3456 +f 3453 3424 3422 +f 3422 3459 3453 +f 3458 3455 3453 +f 3453 3459 3458 +f 3457 3456 3458 +f 3458 3460 3457 +f 3459 3422 3423 +f 3423 3461 3459 +f 3460 3458 3459 +f 3459 3462 3460 +f 3461 3423 3428 +f 3428 3463 3461 +f 3462 3459 3461 +f 3461 3464 3462 +f 3465 3463 3428 +f 3428 3429 3465 +f 3464 3461 3463 +f 3463 3466 3464 +f 3466 3463 3465 +f 3465 3467 3466 +f 3468 3412 3413 +f 3413 3419 3468 +f 3469 3411 3412 +f 3412 3468 3469 +f 3406 3405 3407 +f 3407 3470 3406 +f 3470 3407 3411 +f 3411 3469 3470 +f 3471 3469 3468 +f 3468 3472 3471 +f 3473 3470 3469 +f 3469 3471 3473 +f 3475 3471 3472 +f 3472 3474 3475 +f 3476 3473 3471 +f 3471 3475 3476 +f 3477 3476 3475 +f 3475 3347 3477 +f 3347 3475 3474 +f 3474 3478 3347 +f 3374 3480 3479 +f 3479 3375 3374 +f 3436 3481 3480 +f 3480 3374 3436 +f 3444 3344 3481 +f 3481 3436 3444 +f 3451 3482 3344 +f 3344 3444 3451 +f 3457 3348 3482 +f 3482 3451 3457 +f 3460 3345 3348 +f 3348 3457 3460 +f 3349 3345 3460 +f 3460 3462 3349 +f 3346 3349 3462 +f 3462 3464 3346 +f 3466 3350 3346 +f 3346 3464 3466 +f 3397 3398 3483 +f 3483 3484 3397 +f 3485 3483 3398 +f 3398 3402 3485 +f 3485 3402 3406 +f 3406 3486 3485 +f 3486 3406 3470 +f 3470 3473 3486 +f 3488 3484 3483 +f 3483 3487 3488 +f 3484 3465 3429 +f 3429 3397 3484 +f 3487 3483 3485 +f 3485 3489 3487 +f 3485 3486 3490 +f 3490 3489 3485 +f 3486 3473 3476 +f 3476 3490 3486 +f 3488 3467 3465 +f 3465 3484 3488 +f 3360 3488 3487 +f 3487 3361 3360 +f 3361 3487 3489 +f 3489 3362 3361 +f 3489 3490 3363 +f 3363 3362 3489 +f 3490 3476 3477 +f 3477 3363 3490 +f 3467 3359 3350 +f 3350 3466 3467 +f 3488 3360 3359 +f 3359 3467 3488 +f 2975 2971 3231 +f 3231 3235 2975 +f 2971 2974 3234 +f 3234 3231 2971 +f 2974 2983 3243 +f 3243 3234 2974 +f 2983 2985 3245 +f 3245 3243 2983 +f 2985 2987 3247 +f 3247 3245 2985 +f 2987 2989 3249 +f 3249 3247 2987 +f 2977 2975 3235 +f 3235 3237 2977 +f 2979 2977 3237 +f 3237 3239 2979 +f 2981 2979 3239 +f 3239 3241 2981 +f 3001 2981 3241 +f 3241 3261 3001 +f 3008 3001 3261 +f 3261 3268 3008 +f 3009 3008 3268 +f 3268 3269 3009 +f 3017 3009 3269 +f 3269 3277 3017 +f 3021 3017 3277 +f 3277 3281 3021 +f 3025 3021 3281 +f 3281 3285 3025 +f 3029 3025 3285 +f 3285 3289 3029 +f 3038 3037 3297 +f 3297 3298 3038 +f 3037 3029 3289 +f 3289 3297 3037 +f 3043 3044 3304 +f 3304 3303 3043 +f 3039 3038 3298 +f 3298 3299 3039 +f 3046 3039 3299 +f 3299 3306 3046 +f 3044 3046 3306 +f 3306 3304 3044 +f 3040 3043 3303 +f 3303 3300 3040 +f 3078 3040 3300 +f 3300 3338 3078 +f 3081 3078 3338 +f 3338 3341 3081 +f 3218 3081 3341 +f 3341 3478 3218 +f 2989 3219 3479 +f 3479 3249 2989 +f 3105 3117 3377 +f 3377 3365 3105 +f 3106 3105 3365 +f 3365 3366 3106 +f 3108 3106 3366 +f 3366 3368 3108 +f 3110 3108 3368 +f 3368 3370 3110 +f 3113 3110 3370 +f 3370 3373 3113 +f 3115 3113 3373 +f 3373 3375 3115 +f 3117 3119 3379 +f 3379 3377 3117 +f 3119 3121 3381 +f 3381 3379 3119 +f 3121 3123 3383 +f 3383 3381 3121 +f 3123 3125 3385 +f 3385 3383 3123 +f 3125 3127 3387 +f 3387 3385 3125 +f 3127 3129 3389 +f 3389 3387 3127 +f 3129 3135 3395 +f 3395 3389 3129 +f 3135 3140 3400 +f 3400 3395 3135 +f 3140 3144 3404 +f 3404 3400 3140 +f 3144 3149 3409 +f 3409 3404 3144 +f 3149 3156 3416 +f 3416 3409 3149 +f 3156 3157 3417 +f 3417 3416 3156 +f 3158 3159 3419 +f 3419 3418 3158 +f 3157 3160 3420 +f 3420 3417 3157 +f 3160 3161 3421 +f 3421 3420 3160 +f 3161 3158 3418 +f 3418 3421 3161 +f 3159 3208 3468 +f 3468 3419 3159 +f 3208 3212 3472 +f 3472 3468 3208 +f 3212 3214 3474 +f 3474 3472 3212 +f 3214 3218 3478 +f 3478 3474 3214 +f 3219 3115 3375 +f 3375 3479 3219 +f 3494 3492 3491 +f 3491 3493 3494 +f 3491 3495 3496 +f 3496 3493 3491 +f 3497 3494 3493 +f 3493 3496 3497 +f 3494 3497 3498 +f 3499 3492 3494 +f 3494 3498 3499 +f 3492 3499 3500 +f 3495 3491 3492 +f 3492 3500 3495 +f 3504 3502 3496 +f 3496 3495 3504 +f 3496 3502 3501 +f 3501 3497 3496 +f 3497 3501 3498 +f 3498 3501 3503 +f 3503 3499 3498 +f 3499 3503 3500 +f 3500 3503 3504 +f 3504 3495 3500 +f 3502 3504 3503 +f 3503 3501 3502 +f 3505 3506 3515 +f 3515 3514 3505 +f 3506 3507 3516 +f 3516 3515 3506 +f 3507 3508 3517 +f 3517 3516 3507 +f 3508 3509 3518 +f 3518 3517 3508 +f 3509 3510 3519 +f 3519 3518 3509 +f 3510 3511 3520 +f 3520 3519 3510 +f 3511 3512 3521 +f 3521 3520 3511 +f 3512 3513 3522 +f 3522 3521 3512 +f 3513 3505 3514 +f 3514 3522 3513 +f 3512 3511 3510 +f 3510 3506 3512 +f 3510 3509 3508 +f 3508 3506 3510 +f 3508 3507 3506 +f 3512 3506 3505 +f 3505 3513 3512 +f 3515 3516 3517 +f 3517 3521 3515 +f 3517 3518 3519 +f 3519 3521 3517 +f 3519 3520 3521 +f 3515 3521 3522 +f 3522 3514 3515 +f 3527 3523 3531 +f 3531 3532 3527 +f 3528 3524 3525 +f 3525 3529 3528 +f 3529 3525 3526 +f 3526 3530 3529 +f 3532 3531 3524 +f 3524 3528 3532 +f 3541 3533 3537 +f 3537 3542 3541 +f 3535 3534 3538 +f 3538 3539 3535 +f 3536 3535 3539 +f 3539 3540 3536 +f 3534 3541 3542 +f 3542 3538 3534 +f 3542 3537 3527 +f 3527 3532 3542 +f 3537 3533 3523 +f 3523 3527 3537 +f 3533 3541 3531 +f 3531 3523 3533 +f 3539 3538 3528 +f 3528 3529 3539 +f 3534 3535 3525 +f 3525 3524 3534 +f 3536 3540 3530 +f 3530 3526 3536 +f 3540 3539 3529 +f 3529 3530 3540 +f 3535 3536 3526 +f 3526 3525 3535 +f 3538 3542 3532 +f 3532 3528 3538 +f 3541 3534 3524 +f 3524 3531 3541 +f 3543 3552 3553 +f 3553 3544 3543 +f 3544 3553 3554 +f 3554 3545 3544 +f 3545 3554 3555 +f 3555 3546 3545 +f 3546 3555 3556 +f 3556 3547 3546 +f 3547 3556 3557 +f 3557 3548 3547 +f 3548 3557 3558 +f 3558 3549 3548 +f 3549 3558 3559 +f 3559 3550 3549 +f 3550 3559 3560 +f 3560 3551 3550 +f 3551 3560 3552 +f 3552 3543 3551 +f 3550 3544 3548 +f 3548 3549 3550 +f 3548 3544 3546 +f 3546 3547 3548 +f 3546 3544 3545 +f 3550 3551 3543 +f 3543 3544 3550 +f 3553 3559 3555 +f 3555 3554 3553 +f 3555 3559 3557 +f 3557 3556 3555 +f 3557 3559 3558 +f 3553 3552 3560 +f 3560 3559 3553 +f 3565 3570 3569 +f 3569 3561 3565 +f 3566 3567 3563 +f 3563 3562 3566 +f 3567 3568 3564 +f 3564 3563 3567 +f 3570 3566 3562 +f 3562 3569 3570 +f 3579 3580 3575 +f 3575 3571 3579 +f 3573 3577 3576 +f 3576 3572 3573 +f 3574 3578 3577 +f 3577 3573 3574 +f 3572 3576 3580 +f 3580 3579 3572 +f 3580 3570 3565 +f 3565 3575 3580 +f 3575 3565 3561 +f 3561 3571 3575 +f 3571 3561 3569 +f 3569 3579 3571 +f 3577 3567 3566 +f 3566 3576 3577 +f 3572 3562 3563 +f 3563 3573 3572 +f 3574 3564 3568 +f 3568 3578 3574 +f 3578 3568 3567 +f 3567 3577 3578 +f 3573 3563 3564 +f 3564 3574 3573 +f 3576 3566 3570 +f 3570 3580 3576 +f 3579 3569 3562 +f 3562 3572 3579 +f 3583 3582 3581 +f 3581 3584 3583 +f 3581 3586 3585 +f 3587 3586 3581 +f 3581 3582 3587 +f 3582 3588 3587 +f 3589 3588 3582 +f 3582 3583 3589 +f 3583 3590 3589 +f 3591 3590 3583 +f 3583 3584 3591 +f 3584 3592 3591 +f 3585 3592 3584 +f 3584 3581 3585 +f 3594 3593 3585 +f 3585 3586 3594 +f 3595 3594 3586 +f 3586 3587 3595 +f 3596 3595 3587 +f 3587 3588 3596 +f 3597 3596 3588 +f 3588 3589 3597 +f 3598 3597 3589 +f 3589 3590 3598 +f 3599 3598 3590 +f 3590 3591 3599 +f 3600 3599 3591 +f 3591 3592 3600 +f 3593 3600 3592 +f 3592 3585 3593 +f 3593 3594 3601 +f 3602 3601 3594 +f 3594 3595 3602 +f 3595 3596 3602 +f 3603 3602 3596 +f 3596 3597 3603 +f 3597 3598 3603 +f 3604 3603 3598 +f 3598 3599 3604 +f 3599 3600 3604 +f 3601 3604 3600 +f 3600 3593 3601 +f 3602 3603 3604 +f 3604 3601 3602 +f 3607 3606 3605 +f 3605 3608 3607 +f 3605 3610 3609 +f 3611 3610 3605 +f 3605 3606 3611 +f 3606 3612 3611 +f 3613 3612 3606 +f 3606 3607 3613 +f 3607 3614 3613 +f 3615 3614 3607 +f 3607 3608 3615 +f 3608 3616 3615 +f 3609 3616 3608 +f 3608 3605 3609 +f 3618 3617 3609 +f 3609 3610 3618 +f 3619 3618 3610 +f 3610 3611 3619 +f 3620 3619 3611 +f 3611 3612 3620 +f 3621 3620 3612 +f 3612 3613 3621 +f 3622 3621 3613 +f 3613 3614 3622 +f 3623 3622 3614 +f 3614 3615 3623 +f 3624 3623 3615 +f 3615 3616 3624 +f 3617 3624 3616 +f 3616 3609 3617 +f 3617 3618 3625 +f 3626 3625 3618 +f 3618 3619 3626 +f 3619 3620 3626 +f 3627 3626 3620 +f 3620 3621 3627 +f 3621 3622 3627 +f 3628 3627 3622 +f 3622 3623 3628 +f 3623 3624 3628 +f 3625 3628 3624 +f 3624 3617 3625 +f 3626 3627 3628 +f 3628 3625 3626 +f 3629 3630 3639 +f 3639 3638 3629 +f 3630 3631 3640 +f 3640 3639 3630 +f 3631 3632 3641 +f 3641 3640 3631 +f 3632 3633 3642 +f 3642 3641 3632 +f 3633 3634 3643 +f 3643 3642 3633 +f 3634 3635 3644 +f 3644 3643 3634 +f 3635 3636 3645 +f 3645 3644 3635 +f 3636 3637 3646 +f 3646 3645 3636 +f 3637 3629 3638 +f 3638 3646 3637 +f 3636 3635 3634 +f 3634 3630 3636 +f 3634 3633 3632 +f 3632 3630 3634 +f 3632 3631 3630 +f 3636 3630 3629 +f 3629 3637 3636 +f 3639 3640 3641 +f 3641 3645 3639 +f 3641 3642 3643 +f 3643 3645 3641 +f 3643 3644 3645 +f 3639 3645 3646 +f 3646 3638 3639 +f 3669 3668 3647 +f 3647 3648 3669 +f 3670 3669 3648 +f 3648 3649 3670 +f 3670 3649 3650 +f 3650 3671 3670 +f 3671 3650 3651 +f 3651 3672 3671 +f 3672 3651 3652 +f 3652 3673 3672 +f 3674 3673 3652 +f 3652 3653 3674 +f 3675 3674 3653 +f 3653 3654 3675 +f 3675 3654 3655 +f 3655 3676 3675 +f 3676 3655 3656 +f 3656 3677 3676 +f 3677 3656 3657 +f 3657 3678 3677 +f 3679 3678 3657 +f 3657 3658 3679 +f 3679 3658 3659 +f 3659 3680 3679 +f 3680 3659 3660 +f 3660 3681 3680 +f 3681 3660 3661 +f 3661 3682 3681 +f 3682 3661 3662 +f 3662 3683 3682 +f 3683 3662 3663 +f 3663 3684 3683 +f 3685 3684 3663 +f 3663 3664 3685 +f 3686 3685 3664 +f 3664 3665 3686 +f 3687 3686 3665 +f 3665 3666 3687 +f 3688 3687 3666 +f 3666 3667 3688 +f 3689 3710 3711 +f 3711 3690 3689 +f 3690 3711 3712 +f 3712 3691 3690 +f 3692 3691 3712 +f 3712 3713 3692 +f 3693 3692 3713 +f 3713 3714 3693 +f 3694 3693 3714 +f 3714 3715 3694 +f 3716 3695 3694 +f 3694 3715 3716 +f 3695 3716 3717 +f 3717 3696 3695 +f 3697 3696 3717 +f 3717 3718 3697 +f 3698 3697 3718 +f 3718 3719 3698 +f 3699 3698 3719 +f 3719 3720 3699 +f 3699 3720 3721 +f 3721 3700 3699 +f 3701 3700 3721 +f 3721 3722 3701 +f 3702 3701 3722 +f 3722 3723 3702 +f 3703 3702 3723 +f 3723 3724 3703 +f 3704 3703 3724 +f 3724 3725 3704 +f 3705 3704 3725 +f 3725 3726 3705 +f 3705 3726 3727 +f 3727 3706 3705 +f 3706 3727 3728 +f 3728 3707 3706 +f 3707 3728 3729 +f 3729 3708 3707 +f 3708 3729 3730 +f 3730 3709 3708 +f 3689 3690 3648 +f 3648 3647 3689 +f 3711 3710 3668 +f 3668 3669 3711 +f 3710 3689 3647 +f 3647 3668 3710 +f 3690 3691 3649 +f 3649 3648 3690 +f 3712 3711 3669 +f 3669 3670 3712 +f 3713 3712 3670 +f 3670 3671 3713 +f 3691 3692 3650 +f 3650 3649 3691 +f 3714 3713 3671 +f 3671 3672 3714 +f 3692 3693 3651 +f 3651 3650 3692 +f 3715 3714 3672 +f 3672 3673 3715 +f 3693 3694 3652 +f 3652 3651 3693 +f 3653 3652 3694 +f 3694 3695 3653 +f 3716 3715 3673 +f 3673 3674 3716 +f 3695 3696 3654 +f 3654 3653 3695 +f 3717 3716 3674 +f 3674 3675 3717 +f 3718 3717 3675 +f 3675 3676 3718 +f 3696 3697 3655 +f 3655 3654 3696 +f 3719 3718 3676 +f 3676 3677 3719 +f 3697 3698 3656 +f 3656 3655 3697 +f 3720 3719 3677 +f 3677 3678 3720 +f 3698 3699 3657 +f 3657 3656 3698 +f 3699 3700 3658 +f 3658 3657 3699 +f 3721 3720 3678 +f 3678 3679 3721 +f 3722 3721 3679 +f 3679 3680 3722 +f 3700 3701 3659 +f 3659 3658 3700 +f 3723 3722 3680 +f 3680 3681 3723 +f 3701 3702 3660 +f 3660 3659 3701 +f 3724 3723 3681 +f 3681 3682 3724 +f 3702 3703 3661 +f 3661 3660 3702 +f 3725 3724 3682 +f 3682 3683 3725 +f 3703 3704 3662 +f 3662 3661 3703 +f 3726 3725 3683 +f 3683 3684 3726 +f 3704 3705 3663 +f 3663 3662 3704 +f 3705 3706 3664 +f 3664 3663 3705 +f 3727 3726 3684 +f 3684 3685 3727 +f 3706 3707 3665 +f 3665 3664 3706 +f 3728 3727 3685 +f 3685 3686 3728 +f 3707 3708 3666 +f 3666 3665 3707 +f 3729 3728 3686 +f 3686 3687 3729 +f 3708 3709 3667 +f 3667 3666 3708 +f 3709 3730 3688 +f 3688 3667 3709 +f 3730 3729 3687 +f 3687 3688 3730 +f 3733 3734 3731 +f 3731 3732 3733 +f 3731 3735 3736 +f 3737 3732 3731 +f 3731 3736 3737 +f 3732 3737 3738 +f 3739 3733 3732 +f 3732 3738 3739 +f 3733 3739 3740 +f 3741 3734 3733 +f 3733 3740 3741 +f 3734 3741 3742 +f 3735 3731 3734 +f 3734 3742 3735 +f 3744 3736 3735 +f 3735 3743 3744 +f 3745 3737 3736 +f 3736 3744 3745 +f 3746 3738 3737 +f 3737 3745 3746 +f 3747 3739 3738 +f 3738 3746 3747 +f 3748 3740 3739 +f 3739 3747 3748 +f 3749 3741 3740 +f 3740 3748 3749 +f 3750 3742 3741 +f 3741 3749 3750 +f 3743 3735 3742 +f 3742 3750 3743 +f 3743 3751 3744 +f 3752 3745 3744 +f 3744 3751 3752 +f 3745 3752 3746 +f 3753 3747 3746 +f 3746 3752 3753 +f 3747 3753 3748 +f 3754 3749 3748 +f 3748 3753 3754 +f 3749 3754 3750 +f 3751 3743 3750 +f 3750 3754 3751 +f 3752 3751 3754 +f 3754 3753 3752 +f 3757 3758 3755 +f 3755 3756 3757 +f 3755 3759 3760 +f 3761 3756 3755 +f 3755 3760 3761 +f 3756 3761 3762 +f 3763 3757 3756 +f 3756 3762 3763 +f 3757 3763 3764 +f 3765 3758 3757 +f 3757 3764 3765 +f 3758 3765 3766 +f 3759 3755 3758 +f 3758 3766 3759 +f 3768 3760 3759 +f 3759 3767 3768 +f 3769 3761 3760 +f 3760 3768 3769 +f 3770 3762 3761 +f 3761 3769 3770 +f 3771 3763 3762 +f 3762 3770 3771 +f 3772 3764 3763 +f 3763 3771 3772 +f 3773 3765 3764 +f 3764 3772 3773 +f 3774 3766 3765 +f 3765 3773 3774 +f 3767 3759 3766 +f 3766 3774 3767 +f 3767 3775 3768 +f 3776 3769 3768 +f 3768 3775 3776 +f 3769 3776 3770 +f 3777 3771 3770 +f 3770 3776 3777 +f 3771 3777 3772 +f 3778 3773 3772 +f 3772 3777 3778 +f 3773 3778 3774 +f 3775 3767 3774 +f 3774 3778 3775 +f 3776 3775 3778 +f 3778 3777 3776 +f 3782 3781 3779 +f 3779 3780 3782 +f 3779 3781 3784 +f 3784 3783 3779 +f 3785 3784 3781 +f 3781 3782 3785 +f 3782 3786 3785 +f 3787 3786 3782 +f 3782 3780 3787 +f 3780 3788 3787 +f 3783 3788 3780 +f 3780 3779 3783 +f 3792 3783 3784 +f 3784 3790 3792 +f 3784 3785 3789 +f 3789 3790 3784 +f 3785 3786 3789 +f 3786 3787 3791 +f 3791 3789 3786 +f 3787 3788 3791 +f 3788 3783 3792 +f 3792 3791 3788 +f 3790 3789 3791 +f 3791 3792 3790 +f 3793 3802 3803 +f 3803 3794 3793 +f 3794 3803 3804 +f 3804 3795 3794 +f 3795 3804 3805 +f 3805 3796 3795 +f 3796 3805 3806 +f 3806 3797 3796 +f 3797 3806 3807 +f 3807 3798 3797 +f 3798 3807 3808 +f 3808 3799 3798 +f 3799 3808 3809 +f 3809 3800 3799 +f 3800 3809 3810 +f 3810 3801 3800 +f 3801 3810 3802 +f 3802 3793 3801 +f 3800 3794 3798 +f 3798 3799 3800 +f 3798 3794 3796 +f 3796 3797 3798 +f 3796 3794 3795 +f 3800 3801 3793 +f 3793 3794 3800 +f 3803 3809 3805 +f 3805 3804 3803 +f 3805 3809 3807 +f 3807 3806 3805 +f 3807 3809 3808 +f 3803 3802 3810 +f 3810 3809 3803 +f 3833 3812 3811 +f 3811 3832 3833 +f 3834 3813 3812 +f 3812 3833 3834 +f 3834 3835 3814 +f 3814 3813 3834 +f 3835 3836 3815 +f 3815 3814 3835 +f 3836 3837 3816 +f 3816 3815 3836 +f 3838 3817 3816 +f 3816 3837 3838 +f 3839 3818 3817 +f 3817 3838 3839 +f 3839 3840 3819 +f 3819 3818 3839 +f 3840 3841 3820 +f 3820 3819 3840 +f 3841 3842 3821 +f 3821 3820 3841 +f 3843 3822 3821 +f 3821 3842 3843 +f 3843 3844 3823 +f 3823 3822 3843 +f 3844 3845 3824 +f 3824 3823 3844 +f 3845 3846 3825 +f 3825 3824 3845 +f 3846 3847 3826 +f 3826 3825 3846 +f 3847 3848 3827 +f 3827 3826 3847 +f 3849 3828 3827 +f 3827 3848 3849 +f 3850 3829 3828 +f 3828 3849 3850 +f 3851 3830 3829 +f 3829 3850 3851 +f 3852 3831 3830 +f 3830 3851 3852 +f 3853 3854 3875 +f 3875 3874 3853 +f 3854 3855 3876 +f 3876 3875 3854 +f 3856 3877 3876 +f 3876 3855 3856 +f 3857 3878 3877 +f 3877 3856 3857 +f 3858 3879 3878 +f 3878 3857 3858 +f 3880 3879 3858 +f 3858 3859 3880 +f 3859 3860 3881 +f 3881 3880 3859 +f 3861 3882 3881 +f 3881 3860 3861 +f 3862 3883 3882 +f 3882 3861 3862 +f 3863 3884 3883 +f 3883 3862 3863 +f 3863 3864 3885 +f 3885 3884 3863 +f 3865 3886 3885 +f 3885 3864 3865 +f 3866 3887 3886 +f 3886 3865 3866 +f 3867 3888 3887 +f 3887 3866 3867 +f 3868 3889 3888 +f 3888 3867 3868 +f 3869 3890 3889 +f 3889 3868 3869 +f 3869 3870 3891 +f 3891 3890 3869 +f 3870 3871 3892 +f 3892 3891 3870 +f 3871 3872 3893 +f 3893 3892 3871 +f 3872 3873 3894 +f 3894 3893 3872 +f 3853 3811 3812 +f 3812 3854 3853 +f 3875 3833 3832 +f 3832 3874 3875 +f 3874 3832 3811 +f 3811 3853 3874 +f 3854 3812 3813 +f 3813 3855 3854 +f 3876 3834 3833 +f 3833 3875 3876 +f 3877 3835 3834 +f 3834 3876 3877 +f 3855 3813 3814 +f 3814 3856 3855 +f 3878 3836 3835 +f 3835 3877 3878 +f 3856 3814 3815 +f 3815 3857 3856 +f 3879 3837 3836 +f 3836 3878 3879 +f 3857 3815 3816 +f 3816 3858 3857 +f 3817 3859 3858 +f 3858 3816 3817 +f 3880 3838 3837 +f 3837 3879 3880 +f 3859 3817 3818 +f 3818 3860 3859 +f 3881 3839 3838 +f 3838 3880 3881 +f 3882 3840 3839 +f 3839 3881 3882 +f 3860 3818 3819 +f 3819 3861 3860 +f 3883 3841 3840 +f 3840 3882 3883 +f 3861 3819 3820 +f 3820 3862 3861 +f 3884 3842 3841 +f 3841 3883 3884 +f 3862 3820 3821 +f 3821 3863 3862 +f 3863 3821 3822 +f 3822 3864 3863 +f 3885 3843 3842 +f 3842 3884 3885 +f 3886 3844 3843 +f 3843 3885 3886 +f 3864 3822 3823 +f 3823 3865 3864 +f 3887 3845 3844 +f 3844 3886 3887 +f 3865 3823 3824 +f 3824 3866 3865 +f 3888 3846 3845 +f 3845 3887 3888 +f 3866 3824 3825 +f 3825 3867 3866 +f 3889 3847 3846 +f 3846 3888 3889 +f 3867 3825 3826 +f 3826 3868 3867 +f 3890 3848 3847 +f 3847 3889 3890 +f 3868 3826 3827 +f 3827 3869 3868 +f 3869 3827 3828 +f 3828 3870 3869 +f 3891 3849 3848 +f 3848 3890 3891 +f 3870 3828 3829 +f 3829 3871 3870 +f 3892 3850 3849 +f 3849 3891 3892 +f 3871 3829 3830 +f 3830 3872 3871 +f 3893 3851 3850 +f 3850 3892 3893 +f 3872 3830 3831 +f 3831 3873 3872 +f 3873 3831 3852 +f 3852 3894 3873 +f 3894 3852 3851 +f 3851 3893 3894 +# 6964 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Atlas/urdf/mesh/utorso_chull.obj b/examples/Atlas/urdf/mesh/utorso_chull.obj new file mode 100644 index 0000000..71bab05 --- /dev/null +++ b/examples/Atlas/urdf/mesh/utorso_chull.obj @@ -0,0 +1,93 @@ +#### +# +# OBJ File Generated by Meshlab +# +#### +# Object utorso_chull.obj +# +# Vertices: 27 +# Faces: 50 +# +#### +v 0.032539 -0.156783 0.753842 +v -0.293741 -0.152667 0.679347 +v 0.017266 0.173258 0.000282 +v -0.288954 -0.167352 0.485234 +v 0.215929 -0.098697 0.825145 +v 0.314544 0.169152 0.635927 +v 0.017304 -0.173477 0.000797 +v -0.278758 -0.170369 0.007620 +v 0.254327 -0.050807 0.172335 +v 0.064651 -0.099192 0.829739 +v 0.237092 -0.256176 0.451440 +v 0.314624 -0.158811 0.634749 +v 0.213052 0.095372 0.829794 +v 0.178757 -0.292493 0.417514 +v 0.252567 0.044361 0.158183 +v -0.294428 0.149534 0.678421 +v 0.032113 0.157303 0.753814 +v 0.060147 0.098957 0.828936 +v -0.288857 0.170868 0.009706 +v 0.237091 0.256193 0.451472 +v 0.179044 0.292521 0.417914 +v -0.272395 0.172224 0.484290 +v -0.314709 0.000906 0.214023 +v 0.133763 0.081531 -0.030466 +v 0.144263 -0.068900 -0.036127 +v 0.133395 -0.266829 0.507198 +v 0.133143 0.266942 0.507079 +# 27 vertices, 0 vertices normals + +f 25 8 7 +f 10 1 2 +f 14 4 2 +f 2 26 14 +f 19 24 3 +f 8 23 4 +f 8 4 14 +f 1 26 2 +f 21 3 24 +f 11 25 14 +f 11 12 9 +f 7 14 25 +f 26 5 11 +f 24 15 20 +f 13 27 6 +f 27 20 6 +f 8 14 7 +f 25 19 8 +f 23 8 19 +f 12 6 9 +f 11 9 25 +f 23 2 4 +f 26 11 14 +f 5 26 1 +f 10 5 1 +f 12 11 5 +f 20 15 6 +f 5 13 6 +f 6 12 5 +f 16 23 19 +f 17 27 13 +f 17 13 18 +f 24 25 15 +f 6 15 9 +f 16 19 22 +f 17 16 27 +f 16 17 18 +f 21 19 3 +f 24 20 21 +f 21 20 27 +f 27 16 21 +f 21 16 22 +f 21 22 19 +f 24 19 25 +f 18 2 16 +f 18 10 2 +f 18 13 10 +f 13 5 10 +f 16 2 23 +f 15 25 9 +# 50 faces, 0 coords texture + +# End of File \ No newline at end of file diff --git a/examples/Go2/Project.toml b/examples/Go2/Project.toml new file mode 100644 index 0000000..feb57ff --- /dev/null +++ b/examples/Go2/Project.toml @@ -0,0 +1,4 @@ +[deps] +MeshCat = "283c5d60-a78f-5afe-a0af-af636b173e11" +MeshCatMechanisms = "6ad125db-dd91-5488-b820-c1df6aab299d" +RigidBodyDynamics = "366cf18f-59d5-5db9-a4de-86a9f6786172" diff --git a/examples/Go2/test.jl b/examples/Go2/test.jl new file mode 100644 index 0000000..de8e624 --- /dev/null +++ b/examples/Go2/test.jl @@ -0,0 +1,66 @@ +using RigidBodyDynamics, MeshCat, MeshCatMechanisms +using Random, StaticArrays, Rotations, LinearAlgebra +using ForwardDiff; import ForwardDiff as FD # alias for brevity + +const Δt = 0.005 # 200 Hz simulation +const N = 300 # 1.5 s horizon +const nd = 12 # DoFs (Go2 has 3×4 legs) + + +URDF_PATH = joinpath("urdf","go2.urdf") # <-- change me +isfile(URDF_PATH) || error("URDF file not found: $URDF_PATH") +mech = parse_urdf(URDF_PATH) +root = RigidBodyDynamics.root_body(mech) # helper to fetch the root body +state = MechanismState(mech) # positions+velocities +feet = map(n -> findbody(mech, n), + ["FL_foot","FR_foot","RL_foot","RR_foot"] +) # foot bodies + +function rollout(u::AbstractVector) + X = zeros(nd*2, N+1) # [q; q̇] trajectory + τ = reshape(u, nd, :) # piecewise-constant torques + for k in 1:N + # set current state + set_configuration!(state, X[1:nd,k]) + set_velocity!(state, X[nd+1:end,k]) + + # forward dynamics: q̈ = M⁻¹(τ - C(q, q̇)) ---------------- + qdd = FDynamics(state, τ[:,k]) # alias to RBD.forward_dynamics! + X[1:nd, k+1] = X[1:nd,k] + Δt*X[nd+1:end,k] + X[nd+1:end,k+1] = X[nd+1:end,k] + Δt*qdd + end + return X +end + +hip_body = findbody(mech, "trunk") # Go2 torso link name +apex_k = 180 # ≈0.9 s + +function cost(u) + X = rollout(u) + q_apex = X[1:nd, apex_k] + com_z = center_of_mass(mech, q_apex)[3] # height of CoM + + J = -com_z # higher ⇒ lower cost + J += 1e-4*sum(abs2, u) # torque regularizer + return J +end + +nx = nd*2 +nu = nd*(N) # control vector length + +u = randn(nu) * 0.1 # random seed torques +lr = 2e-2 # learning rate +for iter in 1:350 + g = FD.gradient(cost, u) # ForwardDiff dual propagation + u -= lr .* g # vanilla GD step + if iter % 25 == 0 + @info "iter $iter cost=$(cost(u)) ‖∇‖=$(norm(g))" + end +end +X_opt = rollout(u) + +vis = MechanismVisualizer(mech, URDFVisuals(urdf_path)) +open(vis) # launches WebGL viewer + +fps = Int(1/Δt) +setanimation!(vis, X_opt[1:nd,:], fps = fps) # live replay \ No newline at end of file diff --git a/examples/Go2/urdf/go2.urdf b/examples/Go2/urdf/go2.urdf new file mode 100644 index 0000000..0c91557 --- /dev/null +++ b/examples/Go2/urdf/go2.urdf @@ -0,0 +1,1375 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file