diff --git a/ros_kortex/.gitignore b/ros_kortex/.gitignore deleted file mode 100644 index be12629..0000000 --- a/ros_kortex/.gitignore +++ /dev/null @@ -1,27 +0,0 @@ -# Files generated by invoking Julia with --code-coverage -*.jl.cov -*.jl.*.cov - -# Files generated by invoking Julia with --track-allocation -*.jl.mem - -# System-specific files and directories generated by the BinaryProvider and BinDeps packages -# They contain absolute paths specific to the host computer, and so should not be committed -deps/deps.jl -deps/build.log -deps/downloads/ -deps/usr/ -deps/src/ - -# Build artifacts for creating documentation generated by the Documenter package -docs/build/ -docs/site/ - -# File generated by Pkg, the package manager, based on a corresponding Project.toml -# It records a fixed state of all packages used by the project. As such, it should not be -# committed for packages, but should be committed for applications that require a static -# environment. -Manifest.toml - -# Jupyter -.ipynb_checkpoints/ diff --git a/ros_kortex/.travis.yml b/ros_kortex/.travis.yml deleted file mode 100644 index 16f9330..0000000 --- a/ros_kortex/.travis.yml +++ /dev/null @@ -1,26 +0,0 @@ -# Documentation: http://docs.travis-ci.com/user/languages/julia/ - -language: julia - -os: - - linux - - osx - -julia: - - nightly - - 1 - -jobs: - allow_failures: - - julia: nightly - include: - - stage: "Documentation" - julia: 1.5 - os: linux - script: - - julia --color=yes --project=docs/ -e 'using Pkg; Pkg.develop(PackageSpec(path=pwd())); Pkg.instantiate()' - - julia --color=yes --project=docs/ docs/make.jl - after_success: skip - -notifications: - email: false diff --git a/ros_kortex/CMakeLists.txt b/ros_kortex/CMakeLists.txt new file mode 120000 index 0000000..66dd650 --- /dev/null +++ b/ros_kortex/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/melodic/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/ros_kortex/LICENSE b/ros_kortex/LICENSE index 6562b9e..f37a869 100644 --- a/ros_kortex/LICENSE +++ b/ros_kortex/LICENSE @@ -1,21 +1,62 @@ -MIT License - -Copyright (c) 2020 Henrique Ferrolho - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. +Copyright (c) 2018, Kinova inc. +All rights reserved. +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: +* Redistributions of source code must retain the above copyright notice, +this list of conditions and the following disclaimer. +* Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the following disclaimer in the documentation +and/or other materials provided with the distribution. +* Neither the name of the copyright holder nor the names of its contributors +may be used to endorse or promote products derived from this software +without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR +CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, +EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +____________________________________________________________________ + + +Protocol Buffer license + +Copyright 2008 Google Inc. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + + * Redistributions of source code must retain the above copyright +notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above +copyright notice, this list of conditions and the following disclaimer +in the documentation and/or other materials provided with the +distribution. + * Neither the name of Google Inc. nor the names of its +contributors may be used to endorse or promote products derived from +this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +Code generated by the Protocol Buffer compiler is owned by the owner +of the input file used when generating it. This code is not +standalone and requires a support library to be linked with it. This +support library is itself covered by the above license. \ No newline at end of file diff --git a/ros_kortex/Project.toml b/ros_kortex/Project.toml deleted file mode 100644 index 4d8cbc0..0000000 --- a/ros_kortex/Project.toml +++ /dev/null @@ -1,22 +0,0 @@ -name = "TORA" -uuid = "a6da6c0f-f153-4ec6-bf42-6dc0ab733f84" -authors = ["Henrique Ferrolho "] -version = "0.1.0" - -[deps] -Colors = "5ae59095-9a9b-59fe-a467-6f913c188581" -DiffEqCallbacks = "459566f4-90b8-5000-8ac3-15dfb0a30def" -ForwardDiff = "f6369f11-7733-5829-9624-2563aa707210" -GeometryTypes = "4d00f742-c7ba-57c2-abde-4428a4b178cb" -Ipopt = "b6b21f68-93f8-5de0-b562-5493be1d77c9" -LinearAlgebra = "37e2e46d-f89d-539d-b4ee-838fcccc9c8e" -MeshCat = "283c5d60-a78f-5afe-a0af-af636b173e11" -MeshCatMechanisms = "6ad125db-dd91-5488-b820-c1df6aab299d" -NPZ = "15e1cf62-19b3-5cfa-8e77-841668bca605" -Plots = "91a5bcdd-55d7-5caf-9e0b-520d859cae80" -Random = "9a3f8284-a2c9-5f02-9a11-845980a1fd5c" -Requires = "ae029012-a4dd-5104-9daa-d747884805df" -Revise = "295af30f-e4ad-537b-8983-00126c2a3abe" -RigidBodyDynamics = "366cf18f-59d5-5db9-a4de-86a9f6786172" -SparseArrays = "2f01184e-e22b-5df5-ae63-d93ebab69eaf" -SparseDiffTools = "47a9eef4-7e08-11e9-0b38-333d64bd3804" diff --git a/ros_kortex/README.md b/ros_kortex/README.md deleted file mode 100644 index 4804057..0000000 --- a/ros_kortex/README.md +++ /dev/null @@ -1,49 +0,0 @@ -# TORA.jl - -*Trajectory Optimization for Robot Arms* - -| **Documentation** | **Build Status** | -| :-----------------------------------------------------------------------: | :---------------------------------------------------------------------------------------------: | -| [![][docs-stable-img]][docs-stable-url] [![][docs-dev-img]][docs-dev-url] | [![][travis-img]][travis-url] [![][appveyor-img]][appveyor-url] [![][codecov-img]][codecov-url] | - -## Installation - -The package can be installed with the Julia package manager. - -From the Julia REPL, type `]` to enter the Pkg REPL mode and run: -``` -pkg> add https://github.com/ferrolho/TORA.jl -``` - -Or, equivalently, via the Pkg API: -``` -julia> import Pkg; Pkg.add("https://github.com/ferrolho/TORA.jl") -``` - -## Documentation - -- [**STABLE**][docs-stable-url] — **documentation of the most recently tagged version.** -- [**DEVEL**][docs-dev-url] — *documentation of the in-development version.* - -## Contributions and Questions - -Contributions are very welcome, as are feature requests and suggestions. - -Please open an [issue][issues-url] if you encounter any problems. - -[docs-dev-img]: https://img.shields.io/badge/docs-dev-blue.svg -[docs-dev-url]: https://ferrolho.github.io/TORA.jl/dev - -[docs-stable-img]: https://img.shields.io/badge/docs-stable-blue.svg -[docs-stable-url]: https://ferrolho.github.io/TORA.jl/stable - -[travis-img]: https://travis-ci.com/ferrolho/TORA.jl.svg?branch=main&token=wa8UTQ2MKiuHJN6QRxtH -[travis-url]: https://travis-ci.com/ferrolho/TORA.jl - -[appveyor-img]: https://ci.appveyor.com/api/projects/status/x?svg=true -[appveyor-url]: https://ci.appveyor.com/project/ferrolho/tora-jl - -[codecov-img]: https://codecov.io/gh/ferrolho/TORA.jl/branch/main/graph/badge.svg -[codecov-url]: https://codecov.io/gh/ferrolho/TORA.jl - -[issues-url]: https://github.com/ferrolho/TORA.jl/issues diff --git a/ros_kortex/docs/Project.toml b/ros_kortex/docs/Project.toml deleted file mode 100644 index 53c4b94..0000000 --- a/ros_kortex/docs/Project.toml +++ /dev/null @@ -1,6 +0,0 @@ -[deps] -Documenter = "e30172f5-a6a5-5a46-863b-614d45cd2de4" -MeshCat = "283c5d60-a78f-5afe-a0af-af636b173e11" -MeshCatMechanisms = "6ad125db-dd91-5488-b820-c1df6aab299d" -RigidBodyDynamics = "366cf18f-59d5-5db9-a4de-86a9f6786172" -TORA = "a6da6c0f-f153-4ec6-bf42-6dc0ab733f84" diff --git a/ros_kortex/docs/make.jl b/ros_kortex/docs/make.jl deleted file mode 100644 index 5a1035c..0000000 --- a/ros_kortex/docs/make.jl +++ /dev/null @@ -1,25 +0,0 @@ -using Documenter, TORA - -makedocs( - modules = [TORA], - format = Documenter.HTML(), - sitename = "TORA.jl", - authors = "Henrique Ferrolho", - pages = [ - "Home" => "index.md", - "Getting Started" => [ - "install.md", - "tutorial.md", - ], - "Manual" => [ - "methods.md", - "advanced.md", - "new_robot.md", - ] - ] -) - -deploydocs( - repo = "github.com/ferrolho/TORA.jl", - devbranch = "main", -) diff --git a/ros_kortex/docs/src/advanced.md b/ros_kortex/docs/src/advanced.md deleted file mode 100644 index 5e5a7a4..0000000 --- a/ros_kortex/docs/src/advanced.md +++ /dev/null @@ -1 +0,0 @@ -# Advanced Usage diff --git a/ros_kortex/docs/src/assets/logo-dark.drawio b/ros_kortex/docs/src/assets/logo-dark.drawio deleted file mode 100644 index d1e64cd..0000000 --- a/ros_kortex/docs/src/assets/logo-dark.drawio +++ /dev/null @@ -1 +0,0 @@ -3VjbcpswEP0aP7YjEGD82NiOO03bdOrOdPLUkZEMagRiZDm2+/UVIHH1BbvOJKl5MDparVZ7dpeFARzH25lAafSFY8IGNsDbAZwMbNsCvq/+MmRXICPfK4BQUKyFKmBO/xCzUqNrismqISg5Z5KmTTDgSUIC2cCQEHzTFFty1tw1RSHpAPMAsS76k2IZFagPQIV/JDSMZGsiRkZWA6sIYb6pQXA6gGPBuSzu4u2YsMx3xi3FutsDs9quldwZS41BgiSyj4aJfWfD+W6C4NfJwwQMv4+s+3fWqFDzhNi6obe2EUnwh8yzapTwRIE3kYyZGlnqtjwmyAZS8MfSb75CAh7TQM/+pmGY66xEx5xxke8CpyC71Ez3XPrsBDeo06ecER4TKXZKYFMR5moWohpXBhOEIUmfmoQjHTdhqa7c4RunyhIb6BiHQ61HRzj0QVPFiq9FQPSqOiFtRX5TkQNaiiQSIZEdReqmduwKyvk+h3vv+bj3QI186zT5t9n1Bsi3vBb53qXk201FdjuKrkc+ie9+xXC2mN09LJahc3NzD1kv8gVfJ5hgTdomopLMUxRksxtV/Y8FwyORQbQ3MjLZJU9kjf3i14kLHXBLythZofJEhCTbo8FygE3XkFILplKmHk0OOBw4DabOpmV4bVperfNt4DbLn991/nCP79uJconv99dD+/nq4fDMevhWHoY2HL0fevt5PLcknqytz/08hD34Z0x1ouR03qFVWrSnS7rNcnVPIvZJuJHv+gv3SglntfoNt5tw+4pdm4brJZzz+hyOAXRs/0qPF9gKaPjSDu/xdLm0wrn/aYU72aj17vheuLz5Z3HPlVyT+3aiIOIvg27jrxCMVlHen2TLlM5byqp2BAnZ2iPHtAyoB1m+nC3y+yzraJDL/17Hqf5w4JihPoOO2Eb7WbVL2hy91gJm7zqARKCHNsgPvZ2o0xjLEpT+4AVDBbJAwWOY73C/lowmJt65kBEPeYLYZ85TDSb8k7JVDw6mCiaMSLTIx9mk4h1NMTU7oiSIuMhtmFChSh7liZZMiaBKmoisStIkPJR70Pc8HLyF3GuljGNdmHvlq7Vp9GG/3FORinY1sTQTWB022Gm/0lvgqF1uq7iYbwt95e3RcXnP+Tf5c+03fq1KV+HB6/Zp7utrG2w8QtaV2gbYCtayH6glnbMn6S54KVXD6otkwU/1WRdO/wI= \ No newline at end of file diff --git a/ros_kortex/docs/src/assets/logo-dark.svg b/ros_kortex/docs/src/assets/logo-dark.svg deleted file mode 100644 index a591af7..0000000 --- a/ros_kortex/docs/src/assets/logo-dark.svg +++ /dev/null @@ -1,3 +0,0 @@ - - - \ No newline at end of file diff --git a/ros_kortex/docs/src/assets/logo.drawio b/ros_kortex/docs/src/assets/logo.drawio deleted file mode 100644 index 7ff7519..0000000 --- a/ros_kortex/docs/src/assets/logo.drawio +++ /dev/null @@ -1 +0,0 @@ -3VjbcpswEP0aP7YjEGD8WNuJO03bdOrOdPLUkZEMagRiZDm2+/UVIHH1BbvOJKl5MDparVZ7dpeFAZzE25lAafSFY8IGNsDbAZwObNsCvq/+MmRXICPfK4BQUKyFKmBO/xCzUqNrismqISg5Z5KmTTDgSUIC2cCQEHzTFFty1tw1RSHpAPMAsS76k2IZFagPQIV/JDSMZGsiRkZWA6sIYb6pQfBmACeCc1ncxdsJYZnvjFuKdbcHZrVdK7kzlhqDBElkHw1T+86G890Uwa/ThykYfh9Z9++sUaHmCbF1Q29tI5LgD5ln1SjhiQLHkYyZGlnqtjwmyAZS8MfSb75CAh7TQM/+pmGY66xEJ5xxke8CxyC71Ez3XPrsBDeo06ecER4TKXZKYFMR5moWohpXBhOEIUmfmoQjHTdhqa7c4RunyhIb6BiHQ61HRzj0QVPFiq9FQPSqOiFtRX5TkQNaiiQSIZEdReqmduwKyvk+h3vv+bj3QI186zT5t9n1Bsi3vBb53qXk201FdjuKrkc+ie9+xXC2mN09LJahMx7fQ9aLfMHXCSZYk7aJqCTzFAXZ7EZV/2PB8EhkEO2NjEx2yRNZY7/4deJCB9ySMnZWqDwRIcn2aLAcYNM1pNSCqZSpR5MDDgdOg6mzaRlem5ZX63wbuM3y53edP9zj+3aiXOL7/fXQfr56ODyzHr6Vh6ENR++H3n4ezy2JJ2vrcz8PYQ/+GVOdKDmdd2iVFu3pkm6zXN2TiH0SbuS7/sK9UsJZrX7D7SbcvmLXpuF6Cee8PodjAB3bv9LjBbYCGr60w3s8XS6tcO5/WuFONmq9O74XLm/+WdxzJdfkvp0oiPjLoNv4KwSjVZT3J9kypfOWsqodQUK29sgxLQPqQZYvZ4v8Pss6GuTyv9dxqj8cOGaoz6AjttF+Vu2SNkevtYDZuw4gEeihDfJDb6fqNMayBKU/eMFQgSxQ8BjmO9yvJaOJiXcuZMRDniD2mfNUgwn/pGzVg4OpggkjEi3ycTapeEc3mJodURJEXOQ2TKlQJY/yREumRFAlTURWJWkSHso96HseDt5C7rVSxrEuzL3y1do0+rBf7qlIRbuaWJoJrA4b7LRf6S1w1C63VVzMt4W+8vbouLzn/Jv8ufYbv1alq/Dgdfs09/W1DTYeIetKbQNsBWvZD9SSztmTdBe8lKph9UWy4Kf6rAtv/gI= \ No newline at end of file diff --git a/ros_kortex/docs/src/assets/logo.svg b/ros_kortex/docs/src/assets/logo.svg deleted file mode 100644 index 52efb7d..0000000 --- a/ros_kortex/docs/src/assets/logo.svg +++ /dev/null @@ -1,3 +0,0 @@ - - - \ No newline at end of file diff --git a/ros_kortex/docs/src/assets/screenshots/tutorial_01.png b/ros_kortex/docs/src/assets/screenshots/tutorial_01.png deleted file mode 100644 index 77bf0ff..0000000 Binary files a/ros_kortex/docs/src/assets/screenshots/tutorial_01.png and /dev/null differ diff --git a/ros_kortex/docs/src/assets/screenshots/tutorial_02.png b/ros_kortex/docs/src/assets/screenshots/tutorial_02.png deleted file mode 100644 index a5de17d..0000000 Binary files a/ros_kortex/docs/src/assets/screenshots/tutorial_02.png and /dev/null differ diff --git a/ros_kortex/docs/src/assets/screenshots/tutorial_03.png b/ros_kortex/docs/src/assets/screenshots/tutorial_03.png deleted file mode 100644 index bed4ae7..0000000 Binary files a/ros_kortex/docs/src/assets/screenshots/tutorial_03.png and /dev/null differ diff --git a/ros_kortex/docs/src/assets/videos/tutorial.mp4 b/ros_kortex/docs/src/assets/videos/tutorial.mp4 deleted file mode 100644 index 2d3eb9e..0000000 Binary files a/ros_kortex/docs/src/assets/videos/tutorial.mp4 and /dev/null differ diff --git a/ros_kortex/docs/src/index.md b/ros_kortex/docs/src/index.md deleted file mode 100644 index b9b01fa..0000000 --- a/ros_kortex/docs/src/index.md +++ /dev/null @@ -1,3 +0,0 @@ -# TORA.jl - -Documentation for TORA.jl diff --git a/ros_kortex/docs/src/install.md b/ros_kortex/docs/src/install.md deleted file mode 100644 index c4c261a..0000000 --- a/ros_kortex/docs/src/install.md +++ /dev/null @@ -1,84 +0,0 @@ -# Installation - -First things first: install [Julia](https://julialang.org/). You can follow my tutorial [here](https://ferrolho.github.io/blog/2019-01-26/how-to-install-julia-on-ubuntu). - -To install TORA.jl, start Julia and enter `Pkg` mode by pressing `]`, and then run -``` -add https://github.com/ferrolho/TORA.jl -``` - -After the command above, you are pretty much done. - -!!! tip "You are good to go" - - I recommend you to go and follow the [tutorial](@ref Tutorial) now. - -The installation notes below need not be followed right now. -At the end of the tutorial, I will refer you back here. - -## HSL Routines for Ipopt - -This section will guide you through the steps required to install the [Harwell Subroutine Library (HSL)](http://www.hsl.rl.ac.uk/ipopt/). - -!!! info "Information about Ipopt and the HSL" - TORA.jl uses [Ipopt](https://github.com/coin-or/Ipopt) (**I**nterior-**P**oint **OPT**imizer) by default, a large-scale nonlinear optimization solver. - - Ipopt itself depends on other solvers to handle systems of linear equations. - - The [Harwell Subroutine Library (HSL)](http://www.hsl.rl.ac.uk/ipopt/) provides a number of linear solvers that can be used in Ipopt. - -!!! tip "Choose a good linear solver" - Picking a good linear solver is **extremely important** to maximise the performance of nonlinear solvers. - - For example, the linear solver `MA27` is out dated and can be quite slow. `MA57` is a much better alternative, especially for highly-sparse problems (such as trajectory optimization problems). - -First, install the following dependencies: -``` -sudo apt install gcc g++ gfortran git patch wget pkg-config liblapack-dev libmetis-dev -``` - -Clone Ipopt to your `Home` folder: -``` -git clone https://github.com/coin-or/Ipopt.git ~/Ipopt -``` - -Clone the COIN-OR Tools project [ThirdParty-HSL](https://github.com/coin-or-tools/ThirdParty-HSL) into Ipopt's folder: -``` -cd ~/Ipopt -git clone https://github.com/coin-or-tools/ThirdParty-HSL.git -``` - -Go to [http://www.hsl.rl.ac.uk/ipopt/](http://www.hsl.rl.ac.uk/ipopt/) and download **Coin-HSL Full (Stable)** [Linux x86_64]. - -!!! warning - Downloading **Coin-HSL Full** requires a licence. If you are an academic, you can get one for free. - -Extract and rename the downloaded archive into `~/Ipopt/ThirdParty-HSL`: -``` -cd ~/Ipopt/ThirdParty-HSL -tar -xvzf ~/Downloads/coinhsl-2019.05.21.tar.gz -mv coinhsl-2019.05.21 coinhsl -``` - -Configure, make, and install HSL: -``` -./configure -make -sudo make install -``` - -For compatibility, create `libhsl.so` linking to `libcoinhsl.so`: -``` -cd /usr/local/lib -sudo ln -s libcoinhsl.so libhsl.so -``` - -Finally, add the following line to the end of your `.bashrc` (or `.zshrc`): -``` -export LD_LIBRARY_PATH="/usr/local/lib:$LD_LIBRARY_PATH" -``` - -## Artelys Knitro - -!!! unknown "Not ready yet" - Documentation to be written. diff --git a/ros_kortex/docs/src/methods.md b/ros_kortex/docs/src/methods.md deleted file mode 100644 index afc4de1..0000000 --- a/ros_kortex/docs/src/methods.md +++ /dev/null @@ -1,43 +0,0 @@ -# Methods - -## Problem - -```@docs -Problem -``` - -```@docs -fix_joint_positions! -fix_joint_velocities! -fix_joint_torques! -``` - -```@docs -constrain_ee_position! -``` - -```@docs -show_problem_info -``` - -## Solver Log - -```@docs -SolverLog -update! -length -save -load! -``` - -## Plot Utilities - -```@docs -plot_results -plot_log -``` - -## Index - -```@index -``` diff --git a/ros_kortex/docs/src/new_robot.md b/ros_kortex/docs/src/new_robot.md deleted file mode 100644 index 1666810..0000000 --- a/ros_kortex/docs/src/new_robot.md +++ /dev/null @@ -1 +0,0 @@ -# Adding a new robot diff --git a/ros_kortex/docs/src/tutorial.md b/ros_kortex/docs/src/tutorial.md deleted file mode 100644 index 3367042..0000000 --- a/ros_kortex/docs/src/tutorial.md +++ /dev/null @@ -1,302 +0,0 @@ -# Tutorial - -!!! info - A [Jupyter](https://jupyter.org/) notebook of this tutorial is available [here](https://github.com/ferrolho/TORA.jl/blob/main/notebooks/Tutorial.ipynb). - -## Setup - -We are going to use TORA.jl as well as other packages to visualise and handle rigid-body mechanisms. - -```julia -using TORA -using MeshCat -using MeshCatMechanisms -using RigidBodyDynamics -``` - -```@setup example_1 -using TORA -using MeshCat -using MeshCatMechanisms -using RigidBodyDynamics - -vis = Visualizer() -``` - -Try to call `TORA.greet()`. It should simply print "Hello World!" -```@example example_1 -TORA.greet() -``` - -Next, we want to create a 3D viewer using [MeshCat.jl](https://github.com/rdeits/MeshCat.jl) -```julia -vis = Visualizer() -``` - -Let's open the visualizer (in a separate browser tab) -```julia -open(vis) -``` - -It should look like this: - -![Empty viewer](../assets/screenshots/tutorial_01.png) - -## Loading a Robot - -After starting the viewer, we are now ready to load a robot. Let's load a [KUKA LBR iiwa 14](https://www.kuka.com/en-gb/products/robotics-systems/industrial-robots/lbr-iiwa) with - -```@example example_1 -robot = TORA.create_robot_kuka_iiwa_14(vis) -# hide -``` - -!!! info - To load a different robot, check the [Adding a New Robot](@ref Adding-a-new-robot) page of the documentation. - -Afterwards, you should be able to see the robot in the viewer: - -![Robot spawn](../assets/screenshots/tutorial_02.png) - -## Creating a Problem - -Having loaded the robot, we are now ready to define the task we want to solve. - -TORA.jl uses a Direct Transcription[^1] approach to optimize trajectories. -This technique splits the trajectory into $N$ equally-spaced[^2] segments -```math - t_I = t_1 < t_2 < \dots < t_M = t_F, -``` -where $t_I$ and $t_F$ are the start and final instants, respectively. -This division results in $M = N + 1$ discrete *mesh points* (a.k.a. *knots*), for each of which TORA.jl discretizes the states of the system, as well as the control inputs. - -[^1]: - Betts, John T. [*Practical Methods for Optimal Control and Estimation Using Nonlinear Programming*](https://epubs.siam.org/doi/book/10.1137/1.9780898718577). Society for Industrial and Applied Mathematics, 2010. - -[^2]: - Direct Transcription does not necessarily require equally-spaced segments. - -To create a new problem, we use the [`TORA.Problem`](@ref) constructor, which takes three arguments: -1. a [`TORA.Robot`](@ref), -2. the number of *knots* we wish to use for representing the trajectory, and -3. the time step duration between each pair of consecutive knots. - -```@setup example_2 -``` -Suppose we want to optimize a motion with a total duration of *2 seconds*, and that we want to calculate the control inputs to the system at a frequency of *150 Hz*. -```@example example_2 -const duration = 2.0 # in seconds -const hz = 150 -# hide -``` -In that case, the time step duration would be -```@example example_2 -dt = 1/150 -``` -and the total number of *knots* would be given by -```@example example_2 -hz * duration + 1 -``` - -Therefore, we create the problem by running -```@example example_1 -problem = TORA.Problem(robot, 301, 1/150) -# hide -``` - -We can use [`TORA.show_problem_info`](@ref) to print a summary of relevant information of a [`TORA.Problem`](@ref). -```@example example_1 -TORA.show_problem_info(problem) -``` -The summary above shows that the total duration of the motion is 2.0 seconds, just like we wanted. - -The summary also shows that there are no constraints defined yet, as we have just now created the problem. - -## Defining Constraints - -The decision variables of the optimization problem at every *knot* are: -- joint positions, -- joint velocities, and -- joint torques.[^3] - -[^3]: - An exception to this is the last knot, which only discretizes joint positions and joint velocities. - -### Bounds of the Decision Variables - -The bounds of the decision variables need not be defined. -They are automatically inferred from the URDF model. - -### Fixing Values of the Decision Variables - -It is possible to fix the values of specific decision variables with: -- [`TORA.fix_joint_positions!`](@ref) -- [`TORA.fix_joint_velocities!`](@ref) -- [`TORA.fix_joint_torques!`](@ref) - -Suppose we want to enforce zero joint velocities both at the very *start* of the motion and at the very *end* of the motion. We can specify such constraints with - -```@example example_1 -# Constrain initial and final joint velocities to zero -TORA.fix_joint_velocities!(problem, robot, 1, zeros(robot.n_v)) -TORA.fix_joint_velocities!(problem, robot, problem.num_knots, zeros(robot.n_v)) -# hide -``` - -Let's have a look at the problem summary output again: -```@example example_1 -TORA.show_problem_info(problem) -``` - -The output confirms that there are now *two knots* for which we have fixed specific joint velocities. - -### End-effector Constraints - -[`TORA.constrain_ee_position!`](@ref) allows us to enforce specific positions for the end-effector of the robot. - -If we want the end-effector of the robot to be located at $[0.5, 0.2, 0.3]$ in knot $k = 33$ we would write -```julia -TORA.constrain_ee_position!(problem, 33, [0.5, 0.2, 0.3]) -``` - -But let's do something more interesting for this tutorial... Let's define a problem where the robot must trace a circular path. For that, we just need to call [`TORA.constrain_ee_position!`](@ref) multiple times with the right combination of knot and position such that we describe a circle. - -```@example example_1 -let CubicTimeScaling(Tf::Number, t::Number) = 3(t / Tf)^2 - 2(t / Tf)^3 - for k = 1:2:problem.num_knots # For every other knot - θ = CubicTimeScaling(problem.num_knots - 1, k - 1) * 2π - pos = [0.5, 0.2 * cos(θ), 0.8 + 0.2 * sin(θ)] - TORA.constrain_ee_position!(problem, k, pos) - end -end -``` - -In the snippet above, `CubicTimeScaling` is a helper function (a cubic polynomial). It allows us to specify a path for the end-effector that accelerates at first, and decelerates near the end. This is a better alternative to tracing the path with constant velocity. - -The `for` loop inside the `let` block samples every other knot of the trajectory, and computes the position `pos` of the end-effector at that knot using the angle $\theta$. - - -Let's print the problem summary once again: -```@example example_1 -TORA.show_problem_info(problem) -``` - -The output correctly shows that we now have end-effector position constraints in 151 knots. - -## Providing an Initial Guess - -Trajectory Optimization problems can be very challenging to solve. As such, providing a good initial guess (starting point) for the trajectory helps solvers significantly. - -For our circle-tracing task, we are going to define a very simple (but reasonably good) initial guess: a static configuration, zero velocities, and zero torques. - -First, let's define the static configuration: - -```@example example_1 -initial_q = [0, 0, 0, -π/2, 0, 0, 0] -# hide -``` - -We can visualize this configuration by running -```@example example_1 -zero!(robot.state) -set_configuration!(robot.state, initial_q) -set_configuration!(robot.mvis, configuration(robot.state)) -``` - -This will update the configuration of the robot in the viewer: - -![Robot initial configuration](../assets/screenshots/tutorial_03.png) - -We can now define the initial guess for the joint positions with that fixed configuration, repeated for every knot: - -```@example example_1 -initial_qs = repeat(initial_q, 1, problem.num_knots) -``` - -For the joint velocities we are going to start with zeroes repeated for every knot: - -```@example example_1 -initial_vs = zeros(robot.n_v, problem.num_knots) -``` - -And the same for the joint torques: - -```@example example_1 -initial_τs = zeros(robot.n_τ, problem.num_knots) -``` - -We can concatenate these matrices into a single one: -```@example example_1 -initial_guess = [initial_qs; initial_vs; initial_τs] -``` - -Notice that the dimensions are `21×301`, i.e., the dimension of each knot ($\mathbb{R}^{21}$) times the 301 knots. - -We can flatten this matrix into a vector with -```@example example_1 -initial_guess = vec(initial_guess) -# hide -``` - -!!! note "Remember" - Julia follows a column-major convention. See [Access arrays in memory order, along columns](https://docs.julialang.org/en/v1/manual/performance-tips/#man-performance-column-major). - -As a very last step, we just need to truncate the last few values that correspond to the control inputs at the last knot. The last knot represents the end of the motion, so we only represent the robot state. - -```@example example_1 -initial_guess = initial_guess[1:end - robot.n_τ] -# hide -``` - -## Solving the Problem - -```@example example_1 -user_options = Dict("print_level" => 0) # hide -cpu_time, x, solver_log = TORA.solve_with_ipopt(problem, robot, initial_guess=initial_guess, user_options=user_options) # hide -# hide -``` - -Once we are happy with the problem definition, we just need to call solve and the optimization will start. - -```@example example_1 -cpu_time, x, solver_log = TORA.solve_with_ipopt(problem, robot, initial_guess=initial_guess) -# hide -``` - -!!! info - There exist additional parameters that you can pass to `TORA.solve_with_*`. See [Advanced Usage](@ref). - -## Showing the Results - -When the optimization finishes, we can playback the trajectory on the robot shown in the viewer. - -```julia -play_trajectory(vis, problem, robot, x) -``` - -You should be able to see this: - -```@raw html - -``` - -We can also plot the positions, velocities, and torques of the obtained trajectory: - -```@example example_1 -TORA.plot_results(problem, robot, x) -``` - -Lastly, we can plot the [`TORA.SolverLog`](@ref) (returned by the solve function) to study the evolution of the feasibility error and of the objective function value (if one has been defined) per iteration. - -```@example example_1 -TORA.plot_log(solver_log) -``` - -!!! tip "You have reached the end" - That concludes this tutorial. Congratulations! And thank you for sticking around this far. - -```@raw html -
- That's all Folks! -
-``` diff --git a/ros_kortex/iiwa_stack b/ros_kortex/iiwa_stack deleted file mode 160000 index a4f132a..0000000 --- a/ros_kortex/iiwa_stack +++ /dev/null @@ -1 +0,0 @@ -Subproject commit a4f132ad093d276e63040ddbbac6b2cd1facbdcc diff --git a/ros_kortex/kortex_api/.gitignore b/ros_kortex/kortex_api/.gitignore new file mode 100644 index 0000000..a6510df --- /dev/null +++ b/ros_kortex/kortex_api/.gitignore @@ -0,0 +1,2 @@ +include +lib \ No newline at end of file diff --git a/ros_kortex/kortex_control/CMakeLists.txt b/ros_kortex/kortex_control/CMakeLists.txt new file mode 100644 index 0000000..10cb67c --- /dev/null +++ b/ros_kortex/kortex_control/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.3) + +project(kortex_control) + +find_package(catkin REQUIRED) + +catkin_package() + +find_package(roslaunch) + +# Install +foreach(dir arms grippers) + install(DIRECTORY ${dir}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) +endforeach(dir) diff --git a/ros_kortex/kortex_control/arms/gen3/6dof/config/joint_position_controllers.yaml b/ros_kortex/kortex_control/arms/gen3/6dof/config/joint_position_controllers.yaml new file mode 100644 index 0000000..5c2f22b --- /dev/null +++ b/ros_kortex/kortex_control/arms/gen3/6dof/config/joint_position_controllers.yaml @@ -0,0 +1,75 @@ +# Publish all joint states ----------------------------------- +$(arg prefix)joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + +$(arg prefix)gen3_joint_trajectory_controller: + type: effort_controllers/JointTrajectoryController + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + constraints: + goal_time: 1.0 + stopped_velocity_tolerance: 0.5 + stop_trajectory_duration: 1.0 + state_publish_rate: 25 + action_monitor_rate: 25 + gains: + $(arg prefix)joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0} + $(arg prefix)joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0} + $(arg prefix)joint_3: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_4: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_5: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_6: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1} + +$(arg prefix)joint_1_position_controller: + joint: $(arg prefix)joint_1 + pid: + p: 3000.0 + i: 0.0 + d: 2.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_2_position_controller: + joint: $(arg prefix)joint_2 + pid: + p: 50000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_3_position_controller: + joint: $(arg prefix)joint_3 + pid: + p: 50000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_4_position_controller: + joint: $(arg prefix)joint_4 + pid: + p: 750.0 + i: 0.0 + d: 0.2 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_5_position_controller: + joint: $(arg prefix)joint_5 + pid: + p: 5000.0 + i: 0.0 + d: 1.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_6_position_controller: + joint: $(arg prefix)joint_6 + pid: + p: 100.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController diff --git a/ros_kortex/kortex_control/arms/gen3/7dof/config/joint_position_controllers.yaml b/ros_kortex/kortex_control/arms/gen3/7dof/config/joint_position_controllers.yaml new file mode 100644 index 0000000..621a0b3 --- /dev/null +++ b/ros_kortex/kortex_control/arms/gen3/7dof/config/joint_position_controllers.yaml @@ -0,0 +1,85 @@ +# Publish all joint states ----------------------------------- +$(arg prefix)joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + +$(arg prefix)gen3_joint_trajectory_controller: + type: effort_controllers/JointTrajectoryController + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 + constraints: + goal_time: 1.0 + stopped_velocity_tolerance: 0.5 + stop_trajectory_duration: 1.0 + state_publish_rate: 25 + action_monitor_rate: 25 + gains: + $(arg prefix)joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0} + $(arg prefix)joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0} + $(arg prefix)joint_3: {p: 3000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_4: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_5: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_6: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_7: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1} + +$(arg prefix)joint_1_position_controller: + joint: $(arg prefix)joint_1 + pid: + p: 3000.0 + i: 0.0 + d: 2.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_2_position_controller: + joint: $(arg prefix)joint_2 + pid: + p: 50000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_3_position_controller: + joint: $(arg prefix)joint_3 + pid: + p: 3000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_4_position_controller: + joint: $(arg prefix)joint_4 + pid: + p: 50000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_5_position_controller: + joint: $(arg prefix)joint_5 + pid: + p: 750.0 + i: 0.0 + d: 0.2 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_6_position_controller: + joint: $(arg prefix)joint_6 + pid: + p: 5000.0 + i: 0.0 + d: 1.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_7_position_controller: + joint: $(arg prefix)joint_7 + pid: + p: 100.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController diff --git a/ros_kortex/kortex_control/arms/gen3_lite/6dof/config/joint_position_controllers.yaml b/ros_kortex/kortex_control/arms/gen3_lite/6dof/config/joint_position_controllers.yaml new file mode 100644 index 0000000..c869f63 --- /dev/null +++ b/ros_kortex/kortex_control/arms/gen3_lite/6dof/config/joint_position_controllers.yaml @@ -0,0 +1,75 @@ +# Publish all joint states ----------------------------------- +$(arg prefix)joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + +$(arg prefix)gen3_lite_joint_trajectory_controller: + type: effort_controllers/JointTrajectoryController + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + constraints: + goal_time: 1.0 + stopped_velocity_tolerance: 0.5 + stop_trajectory_duration: 1.0 + state_publish_rate: 25 + action_monitor_rate: 25 + gains: + $(arg prefix)joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0} + $(arg prefix)joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0} + $(arg prefix)joint_3: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_4: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_5: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0} + $(arg prefix)joint_6: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1} + +$(arg prefix)joint_1_position_controller: + joint: $(arg prefix)joint_1 + pid: + p: 3000.0 + i: 0.0 + d: 2.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_2_position_controller: + joint: $(arg prefix)joint_2 + pid: + p: 50000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_3_position_controller: + joint: $(arg prefix)joint_3 + pid: + p: 50000.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_4_position_controller: + joint: $(arg prefix)joint_4 + pid: + p: 750.0 + i: 0.0 + d: 0.2 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_5_position_controller: + joint: $(arg prefix)joint_5 + pid: + p: 5000.0 + i: 0.0 + d: 1.0 + type: effort_controllers/JointPositionController + +$(arg prefix)joint_6_position_controller: + joint: $(arg prefix)joint_6 + pid: + p: 100.0 + i: 0.0 + d: 0.0 + type: effort_controllers/JointPositionController diff --git a/ros_kortex/kortex_control/grippers/gen3_lite_2f/config/gripper_action_controller_parameters.yaml b/ros_kortex/kortex_control/grippers/gen3_lite_2f/config/gripper_action_controller_parameters.yaml new file mode 100644 index 0000000..87ac60a --- /dev/null +++ b/ros_kortex/kortex_control/grippers/gen3_lite_2f/config/gripper_action_controller_parameters.yaml @@ -0,0 +1,11 @@ +$(arg prefix)gen3_lite_2f_gripper_controller: + type: position_controllers/GripperActionController + joint: $(arg prefix)right_finger_bottom_joint + action_monitor_rate: 100 + +gazebo_ros_control: + pid_gains: + $(arg prefix)right_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0} + $(arg prefix)right_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0} + $(arg prefix)left_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0} + $(arg prefix)left_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0} \ No newline at end of file diff --git a/ros_kortex/kortex_control/grippers/robotiq_2f_140/config/gripper_action_controller_parameters.yaml b/ros_kortex/kortex_control/grippers/robotiq_2f_140/config/gripper_action_controller_parameters.yaml new file mode 100644 index 0000000..869f515 --- /dev/null +++ b/ros_kortex/kortex_control/grippers/robotiq_2f_140/config/gripper_action_controller_parameters.yaml @@ -0,0 +1,13 @@ +$(arg prefix)robotiq_2f_140_gripper_controller: + type: position_controllers/GripperActionController + joint: $(arg prefix)finger_joint + action_monitor_rate: 100 + +gazebo_ros_control: + pid_gains: + $(arg prefix)finger_joint: {p: 10.0, i: 0.0, d: 0.01} + $(arg prefix)right_outer_knuckle_joint: {p: 10.0, i: 0.0, d: 0.00} + $(arg prefix)right_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01} + $(arg prefix)left_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01} + $(arg prefix)left_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001} + $(arg prefix)right_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001} \ No newline at end of file diff --git a/ros_kortex/kortex_control/grippers/robotiq_2f_85/config/gripper_action_controller_parameters.yaml b/ros_kortex/kortex_control/grippers/robotiq_2f_85/config/gripper_action_controller_parameters.yaml new file mode 100644 index 0000000..4e40277 --- /dev/null +++ b/ros_kortex/kortex_control/grippers/robotiq_2f_85/config/gripper_action_controller_parameters.yaml @@ -0,0 +1,13 @@ +$(arg prefix)robotiq_2f_85_gripper_controller: + type: position_controllers/GripperActionController + joint: $(arg prefix)finger_joint + action_monitor_rate: 100 + +gazebo_ros_control: + pid_gains: + $(arg prefix)finger_joint: {p: 10.0, i: 0.0, d: 0.01} + $(arg prefix)right_outer_knuckle_joint: {p: 10.0, i: 0.0, d: 0.00} + $(arg prefix)right_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01} + $(arg prefix)left_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01} + $(arg prefix)left_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001} + $(arg prefix)right_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001} \ No newline at end of file diff --git a/ros_kortex/kortex_control/package.xml b/ros_kortex/kortex_control/package.xml new file mode 100644 index 0000000..f937c18 --- /dev/null +++ b/ros_kortex/kortex_control/package.xml @@ -0,0 +1,25 @@ + + kortex_control + 2.2.2 + +

Gazebo ROS Control package for simulated Kortex robots

+

This package contains configuration files for the gazebo_ros_control controllers for simulation of Kortex arms

+
+ Alexandre Vannobel + + BSD + catkin + roslaunch + robot_state_publisher + rviz + joint_state_publisher + gazebo + xacro + gazebo_ros + gazebo_ros_control + ros_control + ros_controllers + + + +
diff --git a/ros_kortex/kortex_control/readme.md b/ros_kortex/kortex_control/readme.md new file mode 100644 index 0000000..65e5350 --- /dev/null +++ b/ros_kortex/kortex_control/readme.md @@ -0,0 +1,24 @@ + + +# Kortex Control + +## Overview +This package contains the configuration files for the [ros_control controllers](http://wiki.ros.org/ros_control) used to control the simulated arms. + +## Loading and starting the controllers for simulation + +The `joint_position_controllers.yaml` file for the chosen arm is loaded to the Parameter Server from the [spawn_kortex_robot.launch](../kortex_gazebo/launch/spawn_kortex_robot.launch) file. The `controller_manager` node is then called to load and start the controllers as [Gazebo plugins](http://wiki.ros.org/gazebo_ros_control). + +## ROS Control support for the real arm + +ROS Control support for the Kinova Gen3 and Gen3 lite robots is not currently available and will be part of a future release. diff --git a/ros_kortex/kortex_description/CMakeLists.txt b/ros_kortex/kortex_description/CMakeLists.txt new file mode 100644 index 0000000..40d0704 --- /dev/null +++ b/ros_kortex/kortex_description/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.3) + +project(kortex_description) + +find_package(catkin REQUIRED) + +catkin_package() + +find_package(roslaunch) + +# Install +foreach(dir arms grippers robots launch) + install(DIRECTORY ${dir}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) +endforeach(dir) diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/config/gazebo_initial_joint_positions.yaml b/ros_kortex/kortex_description/arms/gen3/6dof/config/gazebo_initial_joint_positions.yaml new file mode 100644 index 0000000..729f82b --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/config/gazebo_initial_joint_positions.yaml @@ -0,0 +1,6 @@ +initial_joint_positions: "-J $(arg prefix)joint_1 1.57 + -J $(arg prefix)joint_2 -0.35 + -J $(arg prefix)joint_3 -2.00 + -J $(arg prefix)joint_4 0 + -J $(arg prefix)joint_5 -1.00 + -J $(arg prefix)joint_6 1.57 " \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/config/joint_limits.yaml b/ros_kortex/kortex_description/arms/gen3/6dof/config/joint_limits.yaml new file mode 100644 index 0000000..e524d93 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/config/joint_limits.yaml @@ -0,0 +1,21 @@ +joint_names: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 +maximum_velocities: + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 +maximum_accelerations: + - 1.0 + - 1.0 + - 1.0 + - 10.0 + - 10.0 + - 10.0 diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/config/twist_limits.yaml b/ros_kortex/kortex_description/arms/gen3/6dof/config/twist_limits.yaml new file mode 100644 index 0000000..7b71f61 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/config/twist_limits.yaml @@ -0,0 +1,4 @@ +maximum_linear_velocity: 0.5 +maximum_angular_velocity: 1.74 +maximum_linear_acceleration: 0.4 +maximum_angular_acceleration: 0.4 \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/base_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/base_link.STL new file mode 100644 index 0000000..93f35be Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/base_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bicep_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bicep_link.STL new file mode 100644 index 0000000..579db32 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bicep_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bracelet_no_vision_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bracelet_no_vision_link.STL new file mode 100644 index 0000000..326b1d7 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bracelet_no_vision_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bracelet_with_vision_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bracelet_with_vision_link.STL new file mode 100644 index 0000000..98941ff Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/bracelet_with_vision_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/forearm_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/forearm_link.STL new file mode 100644 index 0000000..c1831b6 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/forearm_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/shoulder_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/shoulder_link.STL new file mode 100644 index 0000000..03928f3 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/shoulder_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/spherical_wrist_1_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/spherical_wrist_1_link.STL new file mode 100644 index 0000000..e3cb5df Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/spherical_wrist_1_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/meshes/spherical_wrist_2_link.STL b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/spherical_wrist_2_link.STL new file mode 100644 index 0000000..0fcd6d6 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/6dof/meshes/spherical_wrist_2_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/urdf/GEN3-6DOF_NO-VISION_URDF_ARM_V01.urdf b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/GEN3-6DOF_NO-VISION_URDF_ARM_V01.urdf new file mode 100644 index 0000000..960ae01 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/GEN3-6DOF_NO-VISION_URDF_ARM_V01.urdf @@ -0,0 +1,205 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/urdf/GEN3-6DOF_VISION_URDF_ARM_V01.urdf b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/GEN3-6DOF_VISION_URDF_ARM_V01.urdf new file mode 100644 index 0000000..89b673e --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/GEN3-6DOF_VISION_URDF_ARM_V01.urdf @@ -0,0 +1,226 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro new file mode 100644 index 0000000..c12d737 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro @@ -0,0 +1,244 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/arms/gen3/6dof/urdf/gen3_transmission_macro.xacro b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/gen3_transmission_macro.xacro new file mode 100644 index 0000000..9dd1f76 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/6dof/urdf/gen3_transmission_macro.xacro @@ -0,0 +1,68 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/config/gazebo_initial_joint_positions.yaml b/ros_kortex/kortex_description/arms/gen3/7dof/config/gazebo_initial_joint_positions.yaml new file mode 100644 index 0000000..2ab9226 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/7dof/config/gazebo_initial_joint_positions.yaml @@ -0,0 +1,7 @@ +initial_joint_positions: "-J $(arg prefix)joint_1 1.57 + -J $(arg prefix)joint_2 -0.35 + -J $(arg prefix)joint_3 3.14 + -J $(arg prefix)joint_4 -2.00 + -J $(arg prefix)joint_5 0 + -J $(arg prefix)joint_6 -1.00 + -J $(arg prefix)joint_7 1.57" \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/config/joint_limits.yaml b/ros_kortex/kortex_description/arms/gen3/7dof/config/joint_limits.yaml new file mode 100644 index 0000000..9b5a25e --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/7dof/config/joint_limits.yaml @@ -0,0 +1,24 @@ +joint_names: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 +maximum_velocities: + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 + - 0.8727 +maximum_accelerations: + - 1.0 + - 1.0 + - 1.0 + - 1.0 + - 10.0 + - 10.0 + - 10.0 \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/config/twist_limits.yaml b/ros_kortex/kortex_description/arms/gen3/7dof/config/twist_limits.yaml new file mode 100644 index 0000000..7b71f61 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/7dof/config/twist_limits.yaml @@ -0,0 +1,4 @@ +maximum_linear_velocity: 0.5 +maximum_angular_velocity: 1.74 +maximum_linear_acceleration: 0.4 +maximum_angular_acceleration: 0.4 \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/base_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/base_link.STL new file mode 100644 index 0000000..0a35a8a Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/base_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/bracelet_no_vision_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/bracelet_no_vision_link.STL new file mode 100644 index 0000000..326b1d7 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/bracelet_no_vision_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/bracelet_with_vision_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/bracelet_with_vision_link.STL new file mode 100644 index 0000000..146b69b Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/bracelet_with_vision_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/end_effector_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/end_effector_link.STL new file mode 100644 index 0000000..6dc3cfa Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/end_effector_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/forearm_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/forearm_link.STL new file mode 100644 index 0000000..ac791a3 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/forearm_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/half_arm_1_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/half_arm_1_link.STL new file mode 100644 index 0000000..1df304c Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/half_arm_1_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/half_arm_2_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/half_arm_2_link.STL new file mode 100644 index 0000000..78bc722 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/half_arm_2_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/shoulder_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/shoulder_link.STL new file mode 100644 index 0000000..69ecb76 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/shoulder_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/spherical_wrist_1_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/spherical_wrist_1_link.STL new file mode 100644 index 0000000..3bbf04a Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/spherical_wrist_1_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/meshes/spherical_wrist_2_link.STL b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/spherical_wrist_2_link.STL new file mode 100644 index 0000000..14bbff5 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3/7dof/meshes/spherical_wrist_2_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/urdf/GEN3_URDF_V12.urdf b/ros_kortex/kortex_description/arms/gen3/7dof/urdf/GEN3_URDF_V12.urdf new file mode 100644 index 0000000..4304441 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/7dof/urdf/GEN3_URDF_V12.urdf @@ -0,0 +1,234 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro b/ros_kortex/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro new file mode 100644 index 0000000..1314425 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro @@ -0,0 +1,336 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/arms/gen3/7dof/urdf/gen3_transmission_macro.xacro b/ros_kortex/kortex_description/arms/gen3/7dof/urdf/gen3_transmission_macro.xacro new file mode 100644 index 0000000..97e7056 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3/7dof/urdf/gen3_transmission_macro.xacro @@ -0,0 +1,78 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/config/joint_limits.yaml b/ros_kortex/kortex_description/arms/gen3_lite/6dof/config/joint_limits.yaml new file mode 100644 index 0000000..ee40c40 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3_lite/6dof/config/joint_limits.yaml @@ -0,0 +1,21 @@ +joint_names: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 +maximum_velocities: + - 0.5 + - 0.5 + - 0.5 + - 0.5 + - 0.5 + - 0.5 +maximum_accelerations: + - 1.0 + - 0.5 + - 0.4 + - 1.0 + - 10.0 + - 10.0 \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/config/twist_limits.yaml b/ros_kortex/kortex_description/arms/gen3_lite/6dof/config/twist_limits.yaml new file mode 100644 index 0000000..efb4374 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3_lite/6dof/config/twist_limits.yaml @@ -0,0 +1,4 @@ +maximum_linear_velocity: 0.3 +maximum_angular_velocity: 0.85 +maximum_linear_acceleration: 0.4 +maximum_angular_acceleration: 0.4 \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/arm_link.STL b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/arm_link.STL new file mode 100644 index 0000000..ca9a4bd Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/arm_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/base_link.STL b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/base_link.STL new file mode 100644 index 0000000..f861db3 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/base_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/forearm_link.STL b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/forearm_link.STL new file mode 100644 index 0000000..af4de3d Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/forearm_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/lower_wrist_link.STL b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/lower_wrist_link.STL new file mode 100644 index 0000000..4685f96 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/lower_wrist_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/shoulder_link.STL b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/shoulder_link.STL new file mode 100644 index 0000000..20c2f6d Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/shoulder_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/upper_wrist_link.STL b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/upper_wrist_link.STL new file mode 100644 index 0000000..5619736 Binary files /dev/null and b/ros_kortex/kortex_description/arms/gen3_lite/6dof/meshes/upper_wrist_link.STL differ diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/GEN3-LITE.urdf b/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/GEN3-LITE.urdf new file mode 100644 index 0000000..bc02cb9 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/GEN3-LITE.urdf @@ -0,0 +1,188 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro b/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro new file mode 100644 index 0000000..0c9b84a --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro @@ -0,0 +1,211 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_transmission_macro.xacro b/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_transmission_macro.xacro new file mode 100644 index 0000000..9dd1f76 --- /dev/null +++ b/ros_kortex/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_transmission_macro.xacro @@ -0,0 +1,68 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + 1 + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/config/joint_limits.yaml b/ros_kortex/kortex_description/grippers/gen3_lite_2f/config/joint_limits.yaml new file mode 100644 index 0000000..b0f21f2 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/gen3_lite_2f/config/joint_limits.yaml @@ -0,0 +1,8 @@ +gripper_joint_names: + - $(arg prefix)right_finger_bottom_joint + +gripper_joint_limits_min: + - 0.96 + +gripper_joint_limits_max: + - -0.09 \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/gripper_base_link.STL b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/gripper_base_link.STL new file mode 100644 index 0000000..8775961 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/gripper_base_link.STL differ diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/left_finger_dist_link.STL b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/left_finger_dist_link.STL new file mode 100644 index 0000000..c4bdc8f Binary files /dev/null and b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/left_finger_dist_link.STL differ diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/left_finger_prox_link.STL b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/left_finger_prox_link.STL new file mode 100644 index 0000000..fed7fe5 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/left_finger_prox_link.STL differ diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/right_finger_dist_link.STL b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/right_finger_dist_link.STL new file mode 100644 index 0000000..eb2e844 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/right_finger_dist_link.STL differ diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/right_finger_prox_link.STL b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/right_finger_prox_link.STL new file mode 100644 index 0000000..430f164 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/gen3_lite_2f/meshes/right_finger_prox_link.STL differ diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/GEN3-LITE-GRIPPER_URDF_SIMPLIFIED_V2.urdf b/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/GEN3-LITE-GRIPPER_URDF_SIMPLIFIED_V2.urdf new file mode 100644 index 0000000..931e71b --- /dev/null +++ b/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/GEN3-LITE-GRIPPER_URDF_SIMPLIFIED_V2.urdf @@ -0,0 +1,125 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro b/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro new file mode 100644 index 0000000..6989156 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro @@ -0,0 +1,182 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Gray + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Kortex/Blue + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_transmission_macro.xacro b/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_transmission_macro.xacro new file mode 100644 index 0000000..e04ae66 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_transmission_macro.xacro @@ -0,0 +1,62 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + 1 + hardware_interface/PositionJointInterface + + + + + + ${prefix}right_finger_bottom_joint + ${prefix}right_finger_tip_joint + -0.676 + 0.149 + 5.0 + + + + ${prefix}right_finger_bottom_joint + ${prefix}left_finger_bottom_joint + -1.0 + 0.0 + 5.0 + + + + ${prefix}right_finger_bottom_joint + ${prefix}left_finger_tip_joint + -0.676 + 0.149 + 5.0 + + + + + + my_gen3_lite_gripper + ${prefix}end_effector_link + ${prefix}right_finger_dist_link + ${prefix}left_finger_dist_link + + 100 + 10 + 3 + 10 + 0.001 + false + __default_topic__ + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/LICENSE b/ros_kortex/kortex_description/grippers/robotiq_2f_140/LICENSE new file mode 100644 index 0000000..316f610 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/LICENSE @@ -0,0 +1,23 @@ +Copyright (c) 2013, ROS-Industrial +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or + other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/README.md b/ros_kortex/kortex_description/grippers/robotiq_2f_140/README.md new file mode 100644 index 0000000..0db6472 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/README.md @@ -0,0 +1,12 @@ +This is the README file from Robotiq's package for the 2F-140 gripper. The package's license file can also be found in this folder. +We used commit `4e3196c1c6a83f54acfa3dd8cf02b575ebba3e53` from [Robotiq's ROS Industrial Github repository](https://github.com/ros-industrial/robotiq) + +# Robotiq 140mm 2-Finger-Adaptive-Gripper + +This package contains the URDF files describing the 140mm stroke gripper from robotiq, also known as series **C3**. + +## Robot Visual +![140](https://user-images.githubusercontent.com/8356912/49428409-463f8580-f7a6-11e8-8278-5246acdc5c14.png) + +## Robot Collision +![1402](https://user-images.githubusercontent.com/8356912/49428407-463f8580-f7a6-11e8-9c4e-df69e478f107.png) diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/config/joint_limits.yaml b/ros_kortex/kortex_description/grippers/robotiq_2f_140/config/joint_limits.yaml new file mode 100644 index 0000000..dd1fd9e --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/config/joint_limits.yaml @@ -0,0 +1,8 @@ +gripper_joint_names: + - $(arg prefix)finger_joint + +gripper_joint_limits_min: + - 0.000 + +gripper_joint_limits_max: + - 0.700 \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_inner_finger.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_inner_finger.stl new file mode 100644 index 0000000..4eb5a1f Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_inner_finger.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_inner_knuckle.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_inner_knuckle.stl new file mode 100644 index 0000000..49e8169 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_inner_knuckle.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_outer_finger.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_outer_finger.stl new file mode 100644 index 0000000..046135f Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_outer_finger.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_outer_knuckle.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_outer_knuckle.stl new file mode 100644 index 0000000..2d53aa7 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_140_outer_knuckle.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_base_link.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_base_link.stl new file mode 100644 index 0000000..7eccbbb Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_base_link.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_coupling.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_coupling.stl new file mode 100644 index 0000000..3afb382 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/collision/robotiq_arg2f_coupling.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_inner_finger.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_inner_finger.stl new file mode 100644 index 0000000..ad723f3 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_inner_finger.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_inner_knuckle.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_inner_knuckle.stl new file mode 100644 index 0000000..616da3d Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_inner_knuckle.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_outer_finger.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_outer_finger.stl new file mode 100644 index 0000000..64301c5 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_outer_finger.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_outer_knuckle.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_outer_knuckle.stl new file mode 100644 index 0000000..9621fc8 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_140_outer_knuckle.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_base_link.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_base_link.stl new file mode 100644 index 0000000..d0f3a2c Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_base_link.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_coupling.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_coupling.stl new file mode 100644 index 0000000..02c600f Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_140/meshes/visual/robotiq_arg2f_coupling.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro new file mode 100644 index 0000000..572af02 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro @@ -0,0 +1,7 @@ + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_transmission_macro.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_transmission_macro.xacro new file mode 100644 index 0000000..f1a85b8 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_transmission_macro.xacro @@ -0,0 +1,79 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + 1 + hardware_interface/PositionJointInterface + + + + + + ${prefix}finger_joint + ${prefix}right_outer_knuckle_joint + -1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}right_inner_knuckle_joint + -1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}left_inner_knuckle_joint + -1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}left_inner_finger_joint + 1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}right_inner_finger_joint + 1.0 + 0.0 + 5.0 + + + + + + my_robotiq_gripper + ${prefix}bracelet_link + ${prefix}left_inner_finger + ${prefix}right_inner_finger + + 100 + 10 + 3 + 10 + 0.001 + false + __default_topic__ + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_arg2f.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_arg2f.xacro new file mode 100644 index 0000000..4b548ff --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_arg2f.xacro @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_arg2f_140_model_macro.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_arg2f_140_model_macro.xacro new file mode 100644 index 0000000..484121f --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_arg2f_140_model_macro.xacro @@ -0,0 +1,252 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.792156862745098 0.819607843137255 0.933333333333333 1 + 0.792156862745098 0.819607843137255 0.933333333333333 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/LICENSE b/ros_kortex/kortex_description/grippers/robotiq_2f_85/LICENSE new file mode 100644 index 0000000..316f610 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/LICENSE @@ -0,0 +1,23 @@ +Copyright (c) 2013, ROS-Industrial +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or + other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/README.md b/ros_kortex/kortex_description/grippers/robotiq_2f_85/README.md new file mode 100644 index 0000000..cd862a9 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/README.md @@ -0,0 +1,13 @@ +This is the README file from Robotiq's package for the 2F-85 gripper. The package's license file can also be found in this folder. +We used commit `4e3196c1c6a83f54acfa3dd8cf02b575ebba3e53` from [Robotiq's ROS Industrial Github repository](https://github.com/ros-industrial/robotiq) + +# Robotiq 85mm 2-Finger-Adaptive-Gripper + +This package contains the URDF files describing the 85mm stroke gripper from robotiq, also known as series **C3**. + +## Robot Visual +![85](https://user-images.githubusercontent.com/8356912/49428405-45a6ef00-f7a6-11e8-822b-c6870c39d445.png) + +## Robot Collision +![852](https://user-images.githubusercontent.com/8356912/49428404-450e5880-f7a6-11e8-82a8-564247ebe7fc.png) + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/config/joint_limits.yaml b/ros_kortex/kortex_description/grippers/robotiq_2f_85/config/joint_limits.yaml new file mode 100644 index 0000000..d67e31f --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/config/joint_limits.yaml @@ -0,0 +1,8 @@ +gripper_joint_names: + - $(arg prefix)finger_joint + +gripper_joint_limits_min: + - 0.000 + +gripper_joint_limits_max: + - 0.800 \ No newline at end of file diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_base_link.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_base_link.stl new file mode 100644 index 0000000..cb9fec8 Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_base_link.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae new file mode 100644 index 0000000..0863206 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_finger.dae @@ -0,0 +1,56 @@ + + + + + VCGLab + VCGLib | MeshLab + + Mon Dec 3 16:35:50 2018 GMT + Mon Dec 3 16:35:50 2018 GMT + Y_UP + + + + + + 7 -18.9031 44.5146 -7 -13.9031 44.5149 -7 -18.9031 44.5146 7 -13.9031 44.5149 -7 -23.9018 13.5144 7 -23.9018 13.5144 -7 5.563 2.24789 7 5.563 2.24789 -7 -1.45127 -5.82184 7 -0.834774 -5.94165 7 -1.45127 -5.82184 -7 -0.834774 -5.94165 7 -2.05187 -5.63825 -7 -2.05187 -5.63825 -7 -19.9533 0.87644 7 -19.9533 0.87644 -7 5.7675 1.65408 7 5.7675 1.65408 7 5.9088 1.04215 -7 5.9088 1.04215 7 -20.6251 1.16853 -7 -20.6251 1.16853 7 -23.9014 6.51442 -7 -23.9014 6.51442 7 -21.2564 1.54031 -7 -21.8376 1.98625 7 -21.8376 1.98625 -7 -21.2564 1.54031 7 -22.8162 3.07301 7 -23.199 3.69762 -7 -23.199 3.69762 -7 -22.8162 3.07301 -7 -23.5028 4.36423 7 -23.5028 4.36423 -7 -23.7231 5.0629 7 -23.7231 5.0629 7 5.98537 0.418805 -7 5.98537 0.418805 -7 5.99635 -0.20913 7 5.99635 -0.20913 7 -22.3601 2.49971 -7 -22.3601 2.49971 -7 -23.8567 5.78321 7 -23.8567 5.78321 -7.5 -22.1867 3.93849 -7.5 4.9959 -0.202394 -7.5 4.98562 0.378963 -7.5 -21.9642 9.42908 -7.5 -21.5984 9.88103 -7.5 2.16462 4.50715 -7.5 2.67323 4.22538 -7.5 2.821 -4.12819 -7.5 3.28118 -3.77278 -7.5 -16.2747 11.2427 -7.5 1.62673 4.72797 -7.5 -0.492538 -4.97568 -7.5 -1.06685 -4.88486 -7.5 0.66821 -4.95515 -7.5 1.23895 -4.84407 -7.5 4.62539 -1.89889 -7.5 4.37367 -2.42302 -7.5 4.55534 2.06129 -7.5 4.76383 1.51851 -7.5 3.14569 3.88647 -7.5 -22.8401 7.2957 -7.5 -22.716 7.86376 -7.5 -19.1404 11.3588 -7.5 -18.5696 11.4698 -7.5 -20.2241 10.9425 -7.5 -20.7224 10.6429 -7.5 -21.4771 3.01969 -7.5 -21.0471 2.62822 -7.5 -19.5282 1.78671 -7.5 -1.62673 -4.72797 -7.5 -20.066 2.00753 -7.5 4.90791 0.955196 -7.5 4.28523 2.5762 -7.5 3.95718 3.05626 -7.5 -22.5268 8.41357 -7.5 -21.1826 10.2875 -7.5 -17.9899 11.5139 -7.5 1.79293 -4.66748 -7.5 -20.5747 2.28931 -7.5 -22.8871 6.13572 -7.5 -22.8093 5.55949 -7.5 4.93862 -0.781014 -7.5 -17.4089 11.4904 -7.5 3.57561 3.495 -7.5 -22.2751 8.93771 -7.5 -22.8973 6.71708 -7.5 -19.6944 11.1822 -7.5 0.0884342 -4.99922 -7.5 -16.8346 11.3995 -7.5 4.81456 -1.34907 -7.5 3.69699 -3.36635 -7.5 -21.8586 3.45843 -7.5 2.32267 -4.42777 -7.5 -22.6653 4.99618 -7.5 4.0628 -2.91439 -7.5 -22.4568 4.4534 7 5.94165 -0.834774 -7 5.94165 -0.834774 7 3.85693 -4.5961 -7 3.35538 -4.97408 -7 3.85693 -4.5961 7 3.35538 -4.97408 -7 5.08843 -3.17929 7 5.08843 -3.17929 7 4.72823 -3.69376 -7 4.72823 -3.69376 -7 5.39288 -2.62999 7 5.39288 -2.62999 -7 5.63825 -2.05187 7 5.63825 -2.05187 7 1.04215 -5.9088 -7 1.04215 -5.9088 -7 1.65408 -5.7675 7 1.65408 -5.7675 -7 0.418805 -5.98537 7 0.418805 -5.98537 7 -0.20913 -5.99635 -7 -0.20913 -5.99635 7 2.24789 -5.563 -7 2.24789 -5.563 7.5 2.51531 -4.32125 7.5 -19.8981 11.0987 7.5 -19.3524 11.2995 7.5 -15.9373 11.1128 7.5 1.96414 4.59806 7.5 3.81882 3.22747 7.5 3.41832 3.64899 7.5 4.70449 -1.69346 7.5 4.86928 -1.13585 7.5 4.69238 1.72672 7.5 4.86111 1.17029 7.5 -17.0506 11.4418 7.5 -17.6284 11.5072 7.5 -20.9014 10.5147 7.5 -21.3455 10.1394 7.5 -22.9014 6.49699 7.5 -22.8696 7.07757 7.5 -22.7626 5.3444 7.5 -22.5938 4.78797 7.5 -16.4844 11.3097 7.5 4.16769 2.76231 7.5 2.97158 4.02116 7.5 2.48466 4.33895 7.5 -18.7871 11.4356 7.5 -18.2098 11.5052 7.5 -22.8655 5.91665 7.5 -0.850809 -4.92708 7.5 -1.41706 -4.79499 7.5 -22.7707 7.65054 7.5 -22.6059 8.20815 7.5 3.44406 -3.6247 7.5 3.84157 -3.20036 7.5 -20.4167 10.8359 7.5 -1.96414 -4.59806 7.5 4.96411 0.598037 7.5 -20.3861 2.17574 7.5 -20.873 2.49353 7.5 -21.743 9.71505 7.5 -22.3616 4.25489 7.5 -22.0691 3.75237 7.5 4.46019 2.25979 7.5 -19.8656 1.91663 7.5 -22.3775 8.74286 7.5 4.99997 0.0176953 7.5 -21.3197 2.8657 7.5 4.96821 -0.562885 7.5 -22.0886 9.24743 7.5 0.308388 -4.99048 7.5 0.885662 -4.92094 7.5 -0.273057 -4.99254 7.5 4.47608 -2.22817 7.5 4.18714 -2.73274 7.5 1.45096 -4.78484 7.5 1.99663 -4.58404 7.5 -21.7203 3.28721 7.5 2.99997 -4.00002 -7 2.81707 -5.29756 7 2.81707 -5.29756 -7 5.82184 -1.45127 7 5.82184 -1.45127 7 4.31622 -4.16776 -7 4.31622 -4.16776 + + + + + + + + + + -0.999885 -6.58811e-07 0.0151494 0.893835 0.407279 0.187573 0.999885 -6.58678e-07 0.0151464 0.97135 -0.234625 0.037832 -0.892862 -0.228542 -0.388028 -0.894566 -0.152842 -0.419988 -0.894566 -0.152843 -0.41999 0.999879 0.00527213 0.0146462 0.999879 0.0053288 0.0146428 0.999885 0.00344961 0.014788 0.999887 0.00169444 0.0149551 -0.893489 -0.13128 -0.429467 0.895752 -0.152028 -0.417751 0.940352 -0.339696 0.0185767 -0.895157 -0.445751 -2.04049e-05 -0.893915 0.444893 0.0546462 -0.893184 0.425185 0.146424 -0.893223 0.408385 0.188082 -0.895768 0.414959 0.1594 -0.999879 0.00532991 0.0146458 -0.999761 -0.0152696 0.0156217 -0.999885 -0.00114887 0.0151176 -0.999811 -0.0118922 0.0153975 -0.893184 -0.0857859 -0.441433 -0.895485 -0.120093 -0.428585 -0.895485 -0.25943 -0.361666 -0.892707 -0.274314 -0.357527 -0.893046 -0.179405 -0.412654 -0.895056 -0.169365 -0.412542 -0.895289 -0.215886 -0.389681 0.999486 0.0232355 0.0220775 0.999848 0.00777246 0.0156138 0.999855 -0.00769614 0.0151899 0.99987 -0.00556636 0.0151267 0.999885 -5.36535e-05 0.0151443 0.892981 -0.131576 -0.430433 0.892417 -0.179901 -0.413797 0.892981 0.438554 0.101269 0.894433 -0.447203 -2.04713e-05 0.894596 -0.427647 -0.129679 -0.89446 0.44708 0.00782346 -0.89448 0.447038 0.0079079 -0.893931 0.446501 -0.0390439 -0.895056 0.441953 0.0595984 -0.893489 0.43757 0.101042 -0.895485 0.431212 0.110289 -0.989204 0.129772 0.0680744 -0.999886 0.000610579 0.0150737 -0.999637 0.018129 0.0199097 -0.999765 0.0126268 0.0176023 -0.999869 0.00614285 0.014963 -0.999831 0.00890353 0.0160713 -0.999183 -0.0364293 0.0174953 -0.998199 -0.0567288 0.0195193 -0.971201 -0.235223 0.0379285 -0.992628 -0.118413 0.0258604 -0.957945 -0.285557 0.0282693 -0.999522 -0.0261159 0.0165226 -0.999678 -0.0197277 0.0159675 -0.999874 -0.00481738 0.0151129 -0.999882 -0.00293873 0.0150995 -0.999862 -0.00686051 0.0151612 -0.999842 -0.0091688 0.0152517 -0.895768 -0.0694353 -0.439065 -0.892584 -0.316014 -0.321603 -0.895644 -0.299452 -0.328862 0.995719 0.079881 0.0464971 0.998888 0.0377137 0.0282848 0.999697 0.0157521 0.0189081 0.999795 0.011067 0.016957 0.999879 -0.00363541 0.0151007 0.999884 -0.00182008 0.0151072 0.895752 -0.152028 -0.417751 0.895919 -0.150453 -0.417964 0.893142 -0.0858021 -0.441516 0.895805 -0.100966 -0.432828 0.895919 0.437193 0.0786852 0.893141 0.425265 0.146451 0.895805 0.425323 0.128975 0.895547 0.407949 0.177687 0.999832 -0.0101404 0.0152994 0.999795 -0.0130756 0.0154714 0.999631 -0.0218487 0.0161457 0.999735 -0.0167965 0.0157349 0.979989 -0.196148 0.0338707 0.997259 -0.0709609 0.020971 0.999427 -0.0293775 0.0168228 0.998941 -0.0423056 0.0180717 0.89341 -0.428444 -0.135108 -0.892401 -0.410605 -0.187147 0.894267 -0.440458 -0.0792697 0.893674 -0.441199 -0.0817945 0.893976 -0.447262 -0.0276369 0.893906 -0.447417 -0.0273819 -0.89504 0.443818 -0.0439332 -0.999338 0.0274601 0.023882 -0.998332 0.0476736 0.0325778 -0.999883 0.00412776 0.0147316 -0.999886 0.00235471 0.0148886 -0.895473 0.135183 -0.424091 -0.892942 0.00787636 -0.450104 -0.895908 -0.0179822 -0.443875 -0.893001 -0.0392043 -0.448343 -0.895906 0.0336706 -0.442965 -0.892493 -0.352992 -0.280809 -0.895768 -0.33542 -0.291708 0.892548 -0.274506 -0.357777 0.895694 -0.284619 -0.341648 0.89589 0.443429 0.0274023 0.89303 0.449928 0.00787328 0.892944 0.44681 0.0548817 0.894597 0.410951 -0.175544 0.894351 0.41181 -0.174782 0.894023 0.428451 -0.13097 0.894944 0.427884 -0.126452 0.895719 0.443957 -0.0242816 -0.893005 0.0548668 -0.446689 -0.895761 0.0849236 -0.436348 -0.893192 0.101174 -0.438145 0.892659 -0.31591 -0.321497 0.892974 -0.38377 -0.235197 -0.89576 -0.444468 -0.00786718 -0.892402 -0.430351 -0.13571 -0.895905 -0.43039 -0.110081 -0.895925 -0.414665 -0.159287 -0.892498 -0.450209 -0.0275528 -0.895852 -0.440367 -0.0593809 -0.892434 -0.443619 -0.0822431 -0.89504 0.183862 -0.406324 -0.893501 0.146219 -0.424588 -0.89448 0.230367 -0.383192 -0.895056 0.27259 -0.352944 -0.893915 0.269771 -0.357965 -0.895768 0.345524 -0.279665 -0.893184 0.339399 -0.295009 -0.895485 0.311119 -0.318296 -0.893489 0.30629 -0.328426 -0.895906 0.400455 -0.192323 -0.89243 -0.384689 -0.23576 -0.895856 -0.366865 -0.250703 -0.895908 -0.3934 -0.206363 0.895548 -0.0500923 -0.442137 0.894597 0.0534496 -0.443666 0.892467 -0.228939 -0.388702 0.895805 -0.242912 -0.372192 0.89588 -0.197994 -0.397741 0.89324 0.447872 -0.0391638 0.895404 0.43876 -0.0757649 0.893571 0.440678 -0.0856385 0.893828 0.392198 -0.217376 0.892944 0.270934 -0.359508 0.894944 0.104432 -0.433784 0.895145 -0.38526 -0.224255 0.893177 -0.409206 -0.186509 0.894889 -0.409161 -0.178217 0.892801 -0.352515 -0.280429 0.895365 -0.356271 -0.267195 0.895547 -0.322574 -0.306499 -0.892942 0.39374 -0.21823 -0.895908 0.375416 -0.23751 -0.893001 0.368674 -0.258124 -0.895761 0.42035 -0.144629 -0.893005 0.414277 -0.175829 0.894023 0.100802 -0.436534 0.894351 0.0545401 -0.444029 0.895146 0.00157708 -0.445771 0.893828 0.00784552 -0.448341 0.893424 -0.0391311 -0.447506 0.895146 0.386838 -0.221519 0.893424 0.367986 -0.257642 0.895547 0.357856 -0.26445 0.895919 0.28674 -0.339278 0.89324 0.190019 -0.40745 0.895404 0.153765 -0.41786 0.893571 0.146174 -0.424457 0.895719 0.20095 -0.396618 0.89589 0.245445 -0.37032 0.89303 0.231782 -0.385712 -0.89446 0.230316 -0.383271 -0.893931 0.189437 -0.406203 -0.893192 0.430032 -0.131453 -0.895473 0.434866 -0.0949739 -0.893501 0.440814 -0.085665 0.895805 0.324357 -0.303853 0.893141 0.339463 -0.295065 0.892981 0.306978 -0.329164 0 -4.34875e-05 1 0 -4.34875e-05 1 0 -0.987248 0.159189 0 -0.987248 0.159189 0 0.9083 0.418319 0 0.9083 0.418319 0 -0.190766 -0.981636 0 -0.190766 -0.981636 0 -0.292329 -0.956318 0 -0.292329 -0.956318 0 -0.341978 -0.939708 0 -0.341978 -0.939708 0 0.97436 0.224995 0 0.97436 0.224995 0 0.945504 0.32561 0 0.945504 0.32561 0 -0.398707 -0.917078 0 -0.398707 -0.917078 0 -1 -4.57764e-05 0 -1 -4.57764e-05 0 -0.608725 -0.793382 0 -0.608725 -0.793382 0 -0.507499 -0.861652 0 -0.507499 -0.861652 0 -0.852618 -0.522535 0 -0.852618 -0.522535 0 -0.909942 -0.414737 0 -0.909942 -0.414737 0 -0.953704 -0.300747 0 -0.953704 -0.300747 0 0.992541 0.121914 0 0.992541 0.121914 0 0.999847 0.0174963 0 0.999847 0.0174963 0 -0.700882 -0.713277 0 -0.700882 -0.713277 0 -0.78258 -0.62255 0 -0.78258 -0.62255 0 -0.998133 -0.0610856 0 -0.998133 -0.0610856 0 -0.983246 -0.182285 0 -0.983246 -0.182285 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.996199 -0.0871118 0 0.996199 -0.0871118 0 0.601851 -0.798609 0 0.601851 -0.798609 0 0.819178 -0.57354 0 0.819178 -0.57354 0 0.874641 -0.484771 0 0.874641 -0.484771 0 0.920522 -0.390691 0 0.920522 -0.390691 0 0.224994 -0.97436 0 0.224994 -0.97436 0 0.121914 -0.992541 0 0.121914 -0.992541 0 -0.0871103 -0.996199 0 -0.0871103 -0.996199 0 0.0174963 -0.999847 0 0.0174963 -0.999847 0 0.325611 -0.945504 0 0.325611 -0.945504 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.515076 -0.857144 0 0.515076 -0.857144 0 0.422658 -0.906289 0 0.422658 -0.906289 0 0.981636 -0.190765 0 0.981636 -0.190765 0 0.956318 -0.292329 0 0.956318 -0.292329 0 0.754739 -0.656026 0 0.754739 -0.656026 0 0.682031 -0.731323 0 0.682031 -0.731323 + + + + + + + + + + + + + + +

1 0 80 0 2 0 164 1 7 1 3 1 0 2 136 2 3 2 140 3 0 3 5 3 82 4 21 4 27 4 13 5 72 5 73 5 14 6 72 6 13 6 143 7 127 7 3 7 127 8 128 8 3 8 143 9 3 9 135 9 136 10 135 10 3 10 8 11 13 11 73 11 12 12 165 12 15 12 139 13 140 13 5 13 23 14 4 14 89 14 37 15 46 15 19 15 62 16 6 16 16 16 6 17 61 17 1 17 62 18 61 18 6 18 54 19 53 19 1 19 79 20 48 20 2 20 80 21 67 21 2 21 69 22 79 22 2 22 8 23 56 23 11 23 8 24 73 24 56 24 71 25 82 25 27 25 25 26 71 26 27 26 21 27 74 27 14 27 74 28 72 28 14 28 21 29 82 29 74 29 130 30 129 30 3 30 128 31 146 31 3 31 0 32 156 32 125 32 125 33 126 33 0 33 0 34 148 34 136 34 10 35 151 35 12 35 165 36 20 36 15 36 17 37 134 37 18 37 139 38 5 38 22 38 142 39 141 39 35 39 38 40 45 40 37 40 45 41 46 41 37 41 101 42 45 42 38 42 46 43 75 43 19 43 19 44 75 44 16 44 16 45 75 45 62 45 61 46 76 46 1 46 1 47 86 47 80 47 87 48 63 48 1 48 63 49 50 49 1 49 49 50 54 50 1 50 50 51 49 51 1 51 88 52 78 52 2 52 78 53 65 53 2 53 2 54 64 54 4 54 65 55 64 55 2 55 4 56 64 56 89 56 47 57 88 57 2 57 48 58 47 58 2 58 90 59 2 59 66 59 67 60 66 60 2 60 90 61 68 61 2 61 68 62 69 62 2 62 56 63 55 63 11 63 41 64 70 64 25 64 70 65 71 65 25 65 144 66 164 66 3 66 129 67 144 67 3 67 145 68 130 68 3 68 146 69 145 69 3 69 126 70 147 70 0 70 147 71 148 71 0 71 157 72 165 72 12 72 151 73 157 73 12 73 9 74 150 74 10 74 150 75 151 75 10 75 134 76 158 76 18 76 7 77 133 77 17 77 133 78 134 78 17 78 7 79 164 79 133 79 0 80 137 80 156 80 138 81 137 81 0 81 170 82 161 82 0 82 161 83 138 83 0 83 140 84 152 84 0 84 152 85 153 85 0 85 166 86 170 86 0 86 153 87 166 87 0 87 142 88 35 88 33 88 30 89 32 89 99 89 149 90 43 90 141 90 141 91 43 91 35 91 139 92 43 92 149 92 22 93 43 93 139 93 85 94 45 94 101 94 77 95 87 95 1 95 76 96 77 96 1 96 53 97 92 97 1 97 92 98 86 98 1 98 58 99 81 99 116 99 118 100 121 100 91 100 91 101 121 101 55 101 55 102 121 102 11 102 118 103 91 103 57 103 31 104 95 104 41 104 95 105 70 105 41 105 24 106 160 106 26 106 160 107 168 107 26 107 167 108 36 108 158 108 39 109 36 109 167 109 158 110 36 110 18 110 111 111 131 111 174 111 113 112 131 112 111 112 183 113 131 113 113 113 132 114 131 114 183 114 39 115 167 115 169 115 57 116 115 116 118 116 58 117 115 117 57 117 58 118 116 118 115 118 168 119 40 119 26 119 28 120 163 120 29 120 23 121 89 121 83 121 34 122 97 122 32 122 84 123 97 123 34 123 32 124 97 124 99 124 83 125 42 125 23 125 84 126 42 126 83 126 84 127 34 127 42 127 96 128 123 128 81 128 81 129 123 129 116 129 103 130 96 130 51 130 51 131 52 131 104 131 103 132 51 132 104 132 109 133 94 133 98 133 109 134 185 134 94 134 94 135 185 135 52 135 52 136 185 136 104 136 59 137 110 137 60 137 31 138 30 138 44 138 95 139 31 139 44 139 99 140 44 140 30 140 173 141 150 141 9 141 171 142 119 142 172 142 20 143 159 143 24 143 159 144 160 144 24 144 20 145 165 145 159 145 169 146 100 146 39 146 132 147 100 147 169 147 132 148 183 148 100 148 107 149 111 149 174 149 105 150 102 150 179 150 117 151 176 151 172 151 163 152 162 152 29 152 29 153 162 153 33 153 33 154 162 154 142 154 40 155 178 155 28 155 178 156 163 156 28 156 40 157 168 157 178 157 110 158 106 158 60 158 60 159 106 159 98 159 98 160 106 160 109 160 93 161 112 161 59 161 112 162 110 162 59 162 117 163 172 163 114 163 119 164 114 164 172 164 173 165 120 165 171 165 120 166 119 166 171 166 173 167 9 167 120 167 107 168 174 168 175 168 107 169 175 169 108 169 175 170 155 170 108 170 102 171 154 171 179 171 177 172 122 172 181 172 176 173 122 173 177 173 176 174 117 174 122 174 181 175 124 175 177 175 179 176 124 176 105 176 181 177 105 177 124 177 103 178 180 178 96 178 180 179 123 179 96 179 182 180 112 180 93 180 85 181 182 181 93 181 85 182 101 182 182 182 154 183 184 183 155 183 155 184 184 184 108 184 154 185 102 185 184 185 2 186 0 186 1 186 1 187 0 187 3 187 4 188 0 188 2 188 0 189 4 189 5 189 6 190 1 190 3 190 7 191 6 191 3 191 9 192 10 192 8 192 9 193 8 193 11 193 12 194 8 194 10 194 8 195 12 195 13 195 13 196 12 196 14 196 14 197 12 197 15 197 17 198 18 198 16 198 19 199 16 199 18 199 6 200 7 200 16 200 17 201 16 201 7 201 15 202 20 202 14 202 20 203 21 203 14 203 4 204 22 204 5 204 23 205 22 205 4 205 25 206 24 206 26 206 24 207 25 207 27 207 20 208 24 208 21 208 21 209 24 209 27 209 30 210 28 210 29 210 31 211 28 211 30 211 29 212 32 212 30 212 33 213 32 213 29 213 34 214 32 214 35 214 33 215 35 215 32 215 36 216 19 216 18 216 36 217 37 217 19 217 37 218 36 218 38 218 39 219 38 219 36 219 40 220 25 220 26 220 25 221 40 221 41 221 40 222 28 222 31 222 40 223 31 223 41 223 42 224 22 224 23 224 22 225 42 225 43 225 34 226 35 226 42 226 43 227 42 227 35 227 45 228 44 228 46 228 47 229 48 229 44 229 49 230 50 230 44 230 51 231 44 231 52 231 53 232 54 232 44 232 55 233 56 233 44 233 57 234 44 234 58 234 59 235 60 235 44 235 61 236 62 236 44 236 63 237 44 237 50 237 64 238 65 238 44 238 67 239 44 239 66 239 68 240 44 240 69 240 70 241 44 241 71 241 72 242 44 242 73 242 74 243 44 243 72 243 75 244 46 244 44 244 76 245 61 245 44 245 77 246 76 246 44 246 78 247 44 247 65 247 48 248 79 248 44 248 80 249 44 249 67 249 69 250 44 250 79 250 56 251 73 251 44 251 81 252 58 252 44 252 71 253 44 253 82 253 74 254 82 254 44 254 83 255 44 255 84 255 75 256 44 256 62 256 85 257 44 257 45 257 86 258 44 258 80 258 63 259 87 259 44 259 49 260 44 260 54 260 78 261 88 261 44 261 64 262 44 262 89 262 47 263 44 263 88 263 66 264 44 264 90 264 68 265 90 265 44 265 55 266 44 266 91 266 92 267 44 267 86 267 59 268 44 268 93 268 52 269 44 269 94 269 95 270 44 270 70 270 85 271 93 271 44 271 77 272 44 272 87 272 92 273 53 273 44 273 81 274 44 274 96 274 57 275 91 275 44 275 97 276 84 276 44 276 98 277 44 277 60 277 83 278 89 278 44 278 97 279 44 279 99 279 51 280 96 280 44 280 98 281 94 281 44 281 39 282 100 282 38 282 38 283 100 283 101 283 102 284 103 284 104 284 103 285 102 285 105 285 107 286 108 286 106 286 109 287 106 287 108 287 110 288 111 288 106 288 107 289 106 289 111 289 110 290 112 290 111 290 113 291 111 291 112 291 115 292 116 292 114 292 117 293 114 293 116 293 115 294 114 294 118 294 118 295 114 295 119 295 11 296 120 296 9 296 121 297 120 297 11 297 119 298 120 298 118 298 120 299 121 299 118 299 116 300 122 300 117 300 123 301 122 301 116 301 125 302 124 302 126 302 127 303 124 303 128 303 129 304 130 304 124 304 131 305 132 305 124 305 133 306 124 306 134 306 136 307 124 307 135 307 137 308 138 308 124 308 139 309 124 309 140 309 141 310 142 310 124 310 127 311 143 311 124 311 135 312 124 312 143 312 144 313 129 313 124 313 145 314 146 314 124 314 147 315 124 315 148 315 139 316 149 316 124 316 150 317 124 317 151 317 152 318 124 318 153 318 154 319 155 319 124 319 146 320 128 320 124 320 125 321 156 321 124 321 148 322 124 322 136 322 157 323 151 323 124 323 158 324 134 324 124 324 159 325 124 325 160 325 161 326 124 326 138 326 141 327 124 327 149 327 162 328 163 328 124 328 144 329 124 329 164 329 145 330 124 330 130 330 147 331 126 331 124 331 157 332 124 332 165 332 166 333 153 333 124 333 158 334 124 334 167 334 133 335 164 335 124 335 160 336 124 336 168 336 169 337 124 337 132 337 137 338 124 338 156 338 161 339 170 339 124 339 152 340 140 340 124 340 166 341 124 341 170 341 171 342 172 342 124 342 173 343 171 343 124 343 131 344 124 344 174 344 169 345 167 345 124 345 175 346 124 346 155 346 176 347 177 347 124 347 173 348 124 348 150 348 159 349 165 349 124 349 178 350 124 350 163 350 176 351 124 351 172 351 162 352 124 352 142 352 178 353 168 353 124 353 175 354 174 354 124 354 154 355 124 355 179 355 180 356 103 356 105 356 181 357 180 357 105 357 123 358 180 358 122 358 122 359 180 359 181 359 100 360 182 360 101 360 100 361 183 361 182 361 112 362 182 362 113 362 113 363 182 363 183 363 108 364 184 364 109 364 184 365 185 365 109 365 104 366 184 366 102 366 185 367 184 367 104 367

+
+
+
+
+ + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae new file mode 100644 index 0000000..a32a3a7 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_inner_knuckle.dae @@ -0,0 +1,56 @@ + + + + + VCGLab + VCGLib | MeshLab + + Mon Dec 3 16:34:34 2018 GMT + Mon Dec 3 16:34:34 2018 GMT + Y_UP + + + + + + -16.7877 18.9747 31.4552 16.7877 28.0996 23.6618 17 18.0385 30.3589 16.7877 18.9747 31.4552 13.1548 30.4682 26.4351 13.5 39.564 42.9502 16.9466 27.6365 23.1196 13.5 39.6132 43.575 13.5 39.2476 44.7635 13.5 38.8557 45.2525 13.5 39.5054 44.1923 -17 18.0385 30.3589 -15.1957 20.5359 33.2831 15.1957 20.5359 33.2831 -13.5 38.3546 45.6288 -13.5 37.7756 45.8686 -13.5 37.1552 45.9569 -13.5 36.5323 45.8881 13.5 38.3546 45.6288 13.5 37.1552 45.9569 13.5 37.7756 45.8686 13.5 36.5323 45.8881 16.9466 18.5116 30.913 -16.9466 18.5116 30.913 -13.5 38.8557 45.2525 -16.7877 28.0996 23.6618 -13.5 39.2476 44.7635 -13.5 39.5054 44.1923 -13.5 39.6132 43.575 -13.5 39.564 42.9502 -13.1548 30.4682 26.4351 -16.9466 27.6365 23.1196 -19.5 -0.314016 -5.99178 19.5 0.470755 -5.9815 19.5 -0.314016 -5.99178 -19.5 0.470755 -5.9815 -19.5 1.24747 -5.86889 19.5 1.24747 -5.86889 -12 32.5535 47.3539 12 32.5535 47.3539 12 33.1012 47.9161 -12 33.1012 47.9161 19.5 4.01478 -4.45887 -19.5 4.01478 -4.45887 -19.5 4.56244 -3.89669 19.5 4.56244 -3.89669 -19.5 3.39844 -4.94476 19.5 2.72394 -5.34604 19.5 3.39844 -4.94476 -19.5 2.72394 -5.34604 -19.5 2.00284 -5.65585 19.5 2.00284 -5.65585 19.5 -5.34604 -2.72394 -19.5 -5.34604 -2.72394 19.5 -5.65585 -2.00284 -19.5 -5.65585 -2.00284 12 42.148 40.1894 -12 42.5315 40.8741 12 42.5315 40.8741 -12 42.148 40.1894 12 41.6784 39.5605 -12 41.6784 39.5605 19.5 -1.8541 -5.70634 -19.5 -1.8541 -5.70634 -19.5 -2.58307 -5.41551 19.5 -2.58307 -5.41551 19.5 -3.89669 -4.56244 -19.5 -3.89669 -4.56244 -19.5 -4.45887 -4.01478 19.5 -4.45887 -4.01478 -19.5 -5.99178 0.314016 19.5 -5.89953 1.09341 19.5 -5.99178 0.314016 -19.5 -5.89953 1.09341 19.5 -5.9815 -0.470755 -19.5 -5.9815 -0.470755 -19.5 -5.86889 -1.24747 19.5 -5.86889 -1.24747 12 43.0155 42.3638 -12 43.0155 42.3638 -12 43.1077 43.1432 12 43.1077 43.1432 -19.5 -5.03202 3.26783 19.5 -4.56244 3.89669 19.5 -5.03202 3.26783 -19.5 -4.56244 3.89669 19.5 -5.41551 2.58307 -19.5 -5.41551 2.58307 -19.5 -5.70634 1.8541 19.5 -5.70634 1.8541 -7.39096 22.4038 35.4701 7.39096 22.4038 35.4701 12 42.462 46.1811 12 42.0607 46.8556 -12 42.0607 46.8556 -12 42.462 46.1811 -19.3223 0.989514 10.3972 19.3223 0.989514 10.3972 19.5 -1.09341 -5.89953 -19.5 -1.09341 -5.89953 19.5 -3.26783 -5.03202 -19.5 -3.26783 -5.03202 -19.5 -4.94476 -3.39844 -19.5 0.131506 9.39259 -19.5 9.25638 1.59921 19.5 -4.94476 -3.39844 19.5 0.131506 9.39259 19.5 9.25638 1.59921 8.2941 16.1092 28.1001 -8.2941 16.1092 28.1001 12 42.8223 41.6031 -12 42.8223 41.6031 12 37.43 49.449 -12 37.43 49.449 -12 38.2094 49.3567 12 38.2094 49.3567 12 38.9701 49.1635 -12 38.9701 49.1635 12 33.7175 48.402 -12 33.7175 48.402 12 34.392 48.8032 -12 34.392 48.8032 -19.3223 10.1144 2.60381 19.3223 10.1144 2.60381 8.2941 25.2341 20.3067 -8.2941 25.2341 20.3067 12 43.0975 43.928 -12 43.0975 43.928 12 41.0126 48.0196 -12 40.3838 48.4892 12 40.3838 48.4892 -12 41.0126 48.0196 12 42.7718 45.46 -12 42.7718 45.46 17.9756 2.46592 12.1258 -17.9756 2.46592 12.1258 -12 42.9848 44.7047 12 42.9848 44.7047 -12 36.6452 49.4387 12 35.8685 49.3261 -12 35.8685 49.3261 12 36.6452 49.4387 -12 41.5748 47.472 12 41.5748 47.472 12 39.699 48.8727 -12 39.699 48.8727 12 35.1131 49.113 -12 35.1131 49.113 6.56274 30.597 26.5859 -6.56274 30.597 26.5859 + + + + + + + + + + 0.274634 -0.68876 0.670959 0.000909477 -0.76027 0.649607 -0.919002 0.391522 -0.0463353 -0.274634 -0.68876 0.670959 -0.00101522 -0.760229 0.649655 2.67985e-07 -0.760406 0.649448 -0.918698 -0.10721 0.380131 -0.919713 -0.131495 0.369915 -0.899248 -0.172676 0.401917 -0.826239 -0.288024 0.484119 -0.673256 -0.453065 0.584345 -0.657818 -0.466285 0.591484 0.673409 0.647933 -0.355955 0.00057084 0.760491 -0.649349 0.657795 0.657159 -0.368033 0.274649 0.770443 -0.575314 -0.274649 0.770443 -0.575314 -0.657797 0.657157 -0.368032 -0.995955 0.0583571 0.0683273 -2.89301e-07 -0.760406 0.649448 1.41082e-05 -0.760406 0.649448 -0.966148 -0.0283074 0.256429 -0.981195 0.0271964 0.191092 -0.989575 0.0864715 0.115172 -0.987028 0.0614393 0.148329 -0.919731 0.0553108 0.388633 -0.919465 0.236065 0.314416 -0.919391 0.235345 0.315171 -2.0889e-07 -0.760406 0.649448 -2.67985e-07 -0.760406 0.649448 1.89347e-05 0.760406 -0.649448 5.64453e-05 0.760409 -0.649444 0.995955 0.0583571 0.0683273 0.995955 0.0583571 0.0683273 0.989941 0.0918835 0.107582 0.988564 0.117689 0.0942865 0.918628 0.339571 0.202026 -0.919208 0.361797 0.155435 0 -0.760406 0.649448 -1.41082e-05 -0.760406 0.649448 2.0889e-07 -0.760406 0.649448 0.000174421 -0.760389 0.649468 3.94178e-05 -0.760404 0.649451 1.58797e-06 -0.760406 0.649448 2.06294e-05 -0.760403 0.649452 2.16959e-06 -0.760406 0.649448 0.826244 0.52321 -0.208739 0.899246 0.423983 -0.107679 -0.918637 0.0972567 0.382947 -0.919152 0.0462978 0.391172 0.918637 0.0972567 0.382947 0.657818 -0.466285 0.591484 0.673253 -0.453078 0.584337 0.919049 -0.0565529 0.390066 0.826239 -0.288024 0.484119 -1.9306e-05 0.760406 -0.649448 2.64332e-07 0.760406 -0.649448 0 0.760406 -0.649448 3.27417e-07 0.760406 -0.649448 4.41978e-07 0.760406 -0.649448 -2.0498e-07 0.760406 -0.649448 0.98472 0.158719 0.0716633 0.9756 0.216287 0.0377472 0.91978 0.38659 0.0674691 0.919675 0.357892 0.161592 0.91916 0.387052 -0.0730464 0.948637 0.315391 -0.0248217 0.919002 0.391522 -0.0463353 0.91986 0.391038 -0.030775 0.919099 0.389948 0.0565416 0.918679 0.394972 0.00516843 0.987028 0.0614393 0.148329 0.989575 0.0864715 0.115172 0.919391 0.235345 0.315171 0.919465 0.236065 0.314416 0.919327 0.309016 0.243611 0.919541 0.306704 0.245716 0.918619 0.27573 0.28304 0.918647 0.380245 0.107241 0.919208 0.361797 0.155435 -0.918679 0.394972 0.00516843 -0.91986 0.391038 -0.030775 -0.918628 0.339571 0.202026 -0.919675 0.357892 0.161592 -0.000174421 -0.760389 0.649468 -4.06123e-05 -0.760404 0.649451 -1.29023e-06 -0.760406 0.649448 -1.86832e-05 -0.760401 0.649454 -2.16959e-06 -0.760406 0.649448 6.1231e-07 -0.760406 0.649448 2.53138e-07 -0.760406 0.649448 -0.918648 0.380245 0.107241 -0.91978 0.38659 0.0674691 -0.919099 0.389948 0.0565416 -0.918622 0.193073 0.344755 -0.919611 0.150328 0.362928 -0.919266 0.145866 0.365613 -0.918662 -0.00517278 0.395011 -0.919049 -0.0565529 0.390066 -0.919824 -0.0430483 0.389964 -0.918619 0.27573 0.28304 -0.919541 0.306704 0.245716 -0.919327 0.309016 0.243611 0.918622 0.193073 0.344755 0.919266 0.145866 0.365613 0.919611 0.150328 0.362928 0.918662 -0.00517278 0.395011 0.919824 -0.0430483 0.389964 0.919152 0.0462978 0.391172 0.919731 0.0553108 0.388633 0.981195 0.0271965 0.191092 0.966148 -0.0283076 0.256429 0.918698 -0.10721 0.380131 0.919713 -0.131495 0.369915 0.899248 -0.172676 0.401917 -5.64453e-05 0.760409 -0.649444 -0.995955 0.0583571 0.0683273 -0.989941 0.0918835 0.107582 -0.00057084 0.760491 -0.649349 -0.988564 0.117689 0.0942865 -0.98472 0.158719 0.0716633 -0.9756 0.216287 0.0377472 -0.948637 0.315391 -0.0248216 -0.91916 0.387052 -0.0730464 -0.899246 0.423983 -0.107679 -0.826244 0.52321 -0.208739 -0.67341 0.647932 -0.355954 1.0249e-07 0.760406 -0.649448 -3.02094e-07 0.760406 -0.649448 -3.31907e-07 0.760406 -0.649448 -2.45562e-07 0.760406 -0.649448 -3.78838e-07 0.760406 -0.649448 0 0.0130893 -0.999914 0 0.0130893 -0.999914 0 0.143492 -0.989651 0 0.143492 -0.989651 0 -0.716303 0.697789 0 -0.716303 0.697789 0 0.716302 -0.69779 0 0.716302 -0.69779 0 0.511293 -0.859406 0 0.511293 -0.859406 0 0.619093 -0.785317 0 0.619093 -0.785317 0 0.271441 -0.962455 0 0.271441 -0.962455 0 0.394744 -0.918791 0 0.394744 -0.918791 0 -0.918791 -0.394744 0 -0.918791 -0.394744 0 0.872492 -0.488628 0 0.872492 -0.488628 0 0.801256 -0.598322 0 0.801256 -0.598322 0 -0.370557 -0.92881 0 -0.370557 -0.92881 0 -0.69779 -0.716302 0 -0.69779 -0.716302 0 -0.993068 0.117538 0 -0.993068 0.117538 0 -0.999914 -0.0130893 0 -0.999914 -0.0130893 0 -0.962455 -0.271441 0 -0.962455 -0.271441 0 -0.989651 -0.143492 0 -0.989651 -0.143492 0 0.99307 -0.117527 0 0.99307 -0.117527 0 -0.801254 0.598324 0 -0.801254 0.598324 0 -0.872495 0.488622 0 -0.872495 0.488622 0 -0.92881 0.370557 0 -0.92881 0.370557 0 -0.969231 0.246153 0 -0.969231 0.246153 0 -0.760406 0.649448 0 -0.760406 0.649448 0 0.859403 0.511299 0 0.859403 0.511299 0 -0.760406 0.649448 0 -0.760406 0.649448 0 -0.117538 -0.993068 0 -0.117538 -0.993068 0 -0.246153 -0.969231 0 -0.246153 -0.969231 0 -0.488622 -0.872495 0 -0.488622 -0.872495 0 -0.598324 -0.801254 0 -0.598324 -0.801254 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.785317 -0.619093 0 -0.785317 -0.619093 0 -0.859406 -0.511293 0 -0.859406 -0.511293 0 -0.760406 0.649448 0 -0.760406 0.649448 0 0.92881 -0.370557 0 0.92881 -0.370557 0 0.969231 -0.246155 0 0.969231 -0.246155 0 0.117536 0.993069 0 0.117536 0.993069 0 0.246155 0.969231 0 0.246155 0.969231 0 -0.619091 0.785319 0 -0.619091 0.785319 0 -0.511298 0.859404 0 -0.511298 0.859404 0 0.760406 -0.649448 0 0.760406 -0.649448 0 0.760406 -0.649448 0 0.760406 -0.649448 0 0.999914 0.0130844 0 0.999914 0.0130844 0 0.598317 0.801259 0 0.598317 0.801259 0 0.918796 0.394733 0 0.918796 0.394733 0 -0.760406 0.649448 0 -0.760406 0.649448 0 -0.760406 0.649448 0 -0.760406 0.649448 0 0.962454 0.271444 0 0.962454 0.271444 0 0.989651 0.143497 0 0.989651 0.143497 0 -0.143483 0.989653 0 -0.143483 0.989653 0 -0.0130942 0.999914 0 -0.0130942 0.999914 0 0.697797 0.716296 0 0.697797 0.716296 0 0.785313 0.619098 0 0.785313 0.619098 0 0.488624 0.872495 0 0.488624 0.872495 0 0.37056 0.928809 0 0.37056 0.928809 0 -0.271446 0.962454 0 -0.271446 0.962454 0 -0.394742 0.918792 0 -0.394742 0.918792 0 0.760406 -0.649448 0 0.760406 -0.649448 0 0.760406 -0.649448 0 0.760406 -0.649448 + + + + + + + + + + + + + + +

39 0 3 0 40 0 22 1 3 1 39 1 79 2 29 2 80 2 0 3 38 3 41 3 38 4 0 4 23 4 13 5 39 5 91 5 17 6 147 6 140 6 23 7 147 7 17 7 121 8 147 8 23 8 119 9 121 9 23 9 0 10 119 10 23 10 0 11 41 11 119 11 6 12 1 12 58 12 6 13 60 13 1 13 1 14 56 14 58 14 1 15 60 15 56 15 25 16 59 16 61 16 59 17 25 17 57 17 104 18 103 18 23 18 12 19 135 19 109 19 106 20 97 20 83 20 17 21 16 21 23 21 23 22 16 22 15 22 14 23 24 23 23 23 15 24 14 24 23 24 16 25 114 25 15 25 14 26 131 26 24 26 14 27 129 27 131 27 90 28 12 28 109 28 12 29 90 29 38 29 123 30 107 30 45 30 123 31 6 31 107 31 106 32 107 32 22 32 22 33 107 33 6 33 6 34 9 34 22 34 8 35 9 35 6 35 8 36 92 36 93 36 133 37 27 37 95 37 12 38 96 38 135 38 103 39 85 39 96 39 91 40 108 40 13 40 106 41 22 41 2 41 106 42 2 42 97 42 97 43 2 43 13 43 22 44 39 44 2 44 13 45 2 45 39 45 110 46 6 46 58 46 110 47 78 47 6 47 114 48 117 48 15 48 16 49 113 49 114 49 20 50 116 50 115 50 3 51 118 51 40 51 118 52 3 52 22 52 139 53 21 53 141 53 120 54 118 54 22 54 104 55 122 55 44 55 124 56 4 56 123 56 123 57 4 57 6 57 60 58 4 58 124 58 6 59 4 59 60 59 61 60 149 60 125 60 10 61 8 61 6 61 7 62 10 62 6 62 137 63 10 63 7 63 8 64 10 64 92 64 78 65 5 65 6 65 6 66 5 66 7 66 78 67 81 67 5 67 7 68 5 68 81 68 7 69 126 69 137 69 126 70 7 70 81 70 18 71 20 71 22 71 9 72 18 72 22 72 18 73 128 73 130 73 9 74 128 74 18 74 8 75 93 75 143 75 143 76 9 76 8 76 143 77 128 77 9 77 132 78 10 78 137 78 10 79 132 79 92 79 80 80 28 80 127 80 29 81 28 81 80 81 26 82 94 82 95 82 27 83 26 83 95 83 103 84 11 84 23 84 96 85 11 85 103 85 11 86 96 86 12 86 38 87 23 87 11 87 12 88 38 88 11 88 97 89 13 89 134 89 108 90 134 90 13 90 27 91 133 91 136 91 27 92 136 92 28 92 28 93 136 93 127 93 14 94 145 94 129 94 15 95 145 95 14 95 117 96 145 96 15 96 16 97 138 97 113 97 138 98 17 98 140 98 138 99 16 99 17 99 131 100 142 100 24 100 24 101 142 101 26 101 26 102 142 102 94 102 18 103 130 103 144 103 20 104 144 104 116 104 18 105 144 105 20 105 112 106 141 106 19 106 21 107 19 107 141 107 112 108 19 108 115 108 115 109 19 109 20 109 20 110 19 110 22 110 22 111 19 111 21 111 21 112 139 112 146 112 21 113 146 113 22 113 146 114 120 114 22 114 122 115 104 115 31 115 23 116 31 116 104 116 24 117 31 117 23 117 31 118 25 118 61 118 26 119 31 119 24 119 26 120 27 120 31 120 28 121 31 121 27 121 28 122 29 122 31 122 29 123 79 123 31 123 111 124 31 124 79 124 111 125 57 125 31 125 25 126 31 126 57 126 124 127 148 127 60 127 122 128 30 128 125 128 31 129 30 129 122 129 125 130 30 130 61 130 30 131 31 131 61 131 34 132 32 132 33 132 33 133 32 133 35 133 33 134 36 134 37 134 33 135 35 135 36 135 40 136 38 136 39 136 41 137 38 137 40 137 44 138 42 138 43 138 44 139 45 139 42 139 47 140 46 140 48 140 47 141 49 141 46 141 42 142 46 142 43 142 48 143 46 143 42 143 37 144 50 144 51 144 36 145 50 145 37 145 51 146 50 146 47 146 47 147 50 147 49 147 52 148 54 148 55 148 53 149 52 149 55 149 57 150 58 150 56 150 59 151 57 151 56 151 61 152 56 152 60 152 59 153 56 153 61 153 63 154 62 154 64 154 62 155 65 155 64 155 67 156 66 156 68 156 66 157 69 157 68 157 71 158 70 158 72 158 73 159 70 159 71 159 74 160 70 160 75 160 72 161 70 161 74 161 54 162 76 162 55 162 77 163 76 163 54 163 74 164 75 164 76 164 74 165 76 165 77 165 79 166 80 166 78 166 81 167 78 167 80 167 83 168 82 168 84 168 85 169 82 169 83 169 84 170 82 170 86 170 82 171 87 171 86 171 86 172 88 172 89 172 87 173 88 173 86 173 89 174 88 174 71 174 88 175 73 175 71 175 38 176 90 176 39 176 91 177 39 177 90 177 93 178 92 178 94 178 94 179 92 179 95 179 85 180 83 180 96 180 97 181 96 181 83 181 32 182 98 182 99 182 32 183 34 183 98 183 63 184 99 184 98 184 98 185 62 185 63 185 65 186 100 186 64 186 64 187 100 187 101 187 101 188 100 188 67 188 100 189 66 189 67 189 46 190 102 190 43 190 63 191 102 191 99 191 102 192 32 192 99 192 102 193 101 193 67 193 82 194 102 194 87 194 104 195 102 195 103 195 32 196 102 196 35 196 67 197 68 197 102 197 102 198 50 198 36 198 43 199 102 199 44 199 102 200 36 200 35 200 102 201 63 201 64 201 101 202 102 202 64 202 102 203 53 203 55 203 102 204 46 204 49 204 50 205 102 205 49 205 44 206 102 206 104 206 88 207 87 207 102 207 70 208 102 208 75 208 76 209 75 209 102 209 103 210 102 210 85 210 70 211 73 211 102 211 76 212 102 212 55 212 82 213 85 213 102 213 88 214 102 214 73 214 47 215 48 215 105 215 33 216 37 216 105 216 37 217 51 217 105 217 71 218 105 218 89 218 83 219 84 219 105 219 77 220 54 220 105 220 86 221 89 221 105 221 33 222 105 222 34 222 106 223 83 223 105 223 42 224 105 224 48 224 71 225 72 225 105 225 47 226 105 226 51 226 62 227 105 227 65 227 86 228 105 228 84 228 74 229 77 229 105 229 42 230 45 230 105 230 52 231 105 231 54 231 98 232 105 232 62 232 100 233 105 233 66 233 105 234 107 234 106 234 66 235 105 235 69 235 74 236 105 236 72 236 107 237 105 237 45 237 98 238 34 238 105 238 100 239 65 239 105 239 69 240 105 240 68 240 102 241 68 241 105 241 52 242 53 242 105 242 102 243 105 243 53 243 90 244 108 244 91 244 108 245 90 245 109 245 57 246 110 246 58 246 111 247 110 247 57 247 79 248 110 248 111 248 78 249 110 249 79 249 113 250 112 250 114 250 112 251 115 251 114 251 115 252 116 252 114 252 117 253 114 253 116 253 41 254 40 254 118 254 119 255 41 255 118 255 118 256 120 256 119 256 119 257 120 257 121 257 44 258 122 258 45 258 45 259 122 259 123 259 124 260 122 260 125 260 123 261 122 261 124 261 80 262 126 262 81 262 127 263 126 263 80 263 130 264 128 264 129 264 128 265 131 265 129 265 92 266 132 266 95 266 133 267 95 267 132 267 97 268 134 268 96 268 96 269 134 269 135 269 134 270 108 270 109 270 135 271 134 271 109 271 136 272 132 272 137 272 132 273 136 273 133 273 136 274 126 274 127 274 126 275 136 275 137 275 139 276 138 276 140 276 139 277 141 277 138 277 113 278 138 278 112 278 112 279 138 279 141 279 128 280 142 280 131 280 143 281 142 281 128 281 93 282 94 282 142 282 143 283 93 283 142 283 129 284 144 284 130 284 145 285 144 285 129 285 116 286 144 286 117 286 145 287 117 287 144 287 139 288 140 288 146 288 147 289 146 289 140 289 147 290 121 290 146 290 120 291 146 291 121 291 60 292 148 292 61 292 61 293 148 293 149 293 124 294 125 294 148 294 149 295 148 295 125 295

+
+
+
+
+ + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae new file mode 100644 index 0000000..0a5e7a1 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_finger.dae @@ -0,0 +1,56 @@ + + + + + VCGLab + VCGLib | MeshLab + + Mon Dec 3 16:31:45 2018 GMT + Mon Dec 3 16:31:45 2018 GMT + Y_UP + + + + + + 12 12.0649 46.3529 -12 12.1139 47.0239 -12 12.0649 46.3529 12 12.1139 47.0239 -7.07463 -2.07595 30.6293 7.07463 -2.07595 30.6293 12 0.164657 47.897 -12 0.164657 47.897 12 5.95012 -0.772068 12 5.82626 -1.43342 -12 5.82626 -1.43342 -12 5.95012 -0.772068 -12 5.62914 -2.07674 12 5.62914 -2.07674 -12 -5.95012 0.772068 12 -5.95012 0.772068 12 8.19151 52.7541 -12 8.19151 52.7541 -12 8.80872 52.4862 12 8.80872 52.4862 12 10.4282 51.2956 -12 10.8681 50.7864 12 10.8681 50.7864 -12 10.4282 51.2956 -12 9.93416 51.7523 12 9.93416 51.7523 12 6.21579 53.1241 -12 5.54346 53.0977 12 5.54346 53.0977 -12 6.21579 53.1241 12 6.88684 53.0751 -12 6.88684 53.0751 12 9.39204 52.1508 -12 9.39204 52.1508 12 -5.99915 0.101011 -12 -5.99915 0.101011 7.5 10.0286 30.6594 -7.5 10.0286 30.6594 12 4.87832 52.9962 -12 4.87832 52.9962 -12 4.22872 52.8208 12 4.22872 52.8208 -12 3.60285 52.5738 12 3.60285 52.5738 -12 3.00856 52.2583 12 3.00856 52.2583 12 7.54819 52.9512 -12 7.54819 52.9512 -12 11.2481 50.2312 12 11.5637 49.6369 -12 11.5637 49.6369 12 11.2481 50.2312 12 -5.44887 -2.51193 -12 -5.44887 -2.51193 -12 -5.13337 -3.10621 12 -5.13337 -3.10621 12 -5.97274 -0.571316 -12 -5.97274 -0.571316 -12 -5.87122 -1.23646 12 -5.87122 -1.23646 12 12.0875 47.6963 12 11.986 48.3614 -12 11.986 48.3614 -12 12.0875 47.6963 -12 0.288514 48.5583 12 0.288514 48.5583 12 0.48564 49.2017 -12 0.48564 49.2017 -13.5 3.87478 48.2351 -13.5 -2.42146 -0.621725 -13.5 -2.5 -6.66134e-15 -13.5 8.60614 46.9174 -13.5 2.48029 -0.313333 -13.5 7.08208 49.4302 -13.5 6.47839 49.5984 -13.5 -2.42146 0.621725 -13.5 2.32444 -0.920311 -13.5 2.02254 -1.46946 -13.5 0.468453 -2.45572 -13.5 -0.156976 -2.49507 -13.5 8.5795 47.5434 -13.5 1.59356 -1.92628 -13.5 7.62499 49.1172 -13.5 -0.772542 -2.37764 -13.5 -1.33957 -2.11082 -13.5 4.68667 49.1769 -13.5 4.22123 48.7573 -13.5 3.66907 47.6431 -13.5 5.85185 49.6111 -13.5 1.06445 -2.26207 -13.5 -2.19077 -1.20438 -13.5 5.24184 49.4676 -13.5 8.39798 48.1432 -13.5 -1.82242 -1.71137 -13.5 8.07301 48.6791 12 2.45334 51.8782 -12 2.45334 51.8782 12 1.94416 51.4384 -12 1.94416 51.4384 12 5.02588 -3.27727 -12 5.02588 -3.27727 -12 4.62735 -3.81938 12 4.62735 -3.81938 12 4.17061 -4.31347 -12 4.17061 -4.31347 12 -5.69586 -1.88605 -12 -5.69586 -1.88605 13.5 0.468453 -2.45572 13.5 -2.42146 0.621725 13.5 3.66907 47.6431 13.5 4.22123 48.7573 13.5 3.87478 48.2351 13.5 5.85185 49.6111 13.5 6.47839 49.5984 13.5 8.60614 46.9174 13.5 2.48029 -0.313333 13.5 -2.19077 -1.20438 13.5 -2.42146 -0.621725 13.5 -2.5 -5.55112e-15 13.5 5.24184 49.4676 13.5 8.5795 47.5434 13.5 -1.33957 -2.11082 13.5 -1.82242 -1.71137 13.5 8.39798 48.1432 13.5 7.62499 49.1172 13.5 8.07301 48.6791 13.5 4.68667 49.1769 13.5 7.08208 49.4302 13.5 2.32444 -0.920311 13.5 2.02254 -1.46946 13.5 1.59356 -1.92628 13.5 1.06445 -2.26207 13.5 -0.156976 -2.49507 13.5 -0.772542 -2.37764 12 -0.772068 -5.95012 -12 -0.772068 -5.95012 -12 -1.43342 -5.82626 12 -1.43342 -5.82626 12 2.51193 -5.44887 -12 1.88605 -5.69586 12 1.88605 -5.69586 -12 2.51193 -5.44887 -12 3.10621 -5.13337 12 3.10621 -5.13337 12 -2.69394 -5.36122 -12 -3.27727 -5.02588 12 -3.27727 -5.02588 -12 -2.69394 -5.36122 12 -4.7533 -3.66143 12 -4.31347 -4.17061 -12 -4.31347 -4.17061 -12 -4.7533 -3.66143 12 -3.81938 -4.62735 -12 -3.81938 -4.62735 12 11.8106 49.011 -12 11.8106 49.011 -12 0.753556 49.8189 12 0.753556 49.8189 -12 1.08889 50.4022 12 1.08889 50.4022 12 1.48743 50.9443 -12 1.48743 50.9443 -12 -2.07674 -5.62914 12 -2.07674 -5.62914 12 5.36122 -2.69394 -12 5.36122 -2.69394 12 3.66143 -4.7533 -12 3.66143 -4.7533 12 1.23646 -5.87122 12 0.571316 -5.97274 -12 0.571316 -5.97274 -12 1.23646 -5.87122 -12 -0.101011 -5.99915 12 -0.101011 -5.99915 + + + + + + + + + + 0.919468 -0.389896 0.0505916 6.51936e-08 -0.991686 0.128678 -0.919252 0.3904 -0.0506352 -0.918764 0.393756 -0.028775 -0.91894 0.387657 -0.072601 -0.919146 0.390643 -0.0506885 0.919252 0.3904 -0.0506352 0.918764 0.393756 -0.028775 0.919941 -0.388965 0.0491377 0.919904 -0.388896 0.0503724 0.91894 0.387657 -0.0726009 0.919146 0.390643 -0.0506885 0.919899 -0.370425 0.128728 0.919935 -0.326705 0.216757 -0.919815 0.0246361 -0.391578 -0.919832 -0.389219 -0.0491698 -0.918838 -0.394331 -0.0154913 -0.919941 -0.388965 0.0491376 -0.919031 -0.393137 0.0287247 -1.30387e-07 -0.991686 0.128678 -0.919032 0.028722 0.393136 -0.918848 0.298625 0.257957 -1.64119e-06 0.991686 -0.128678 0.918848 0.298625 0.257957 0.919848 0.274281 0.280444 0.919244 0.267237 0.289092 0.918983 -0.0154762 0.393995 0.919941 0.00795919 0.391976 0.919032 0.028722 0.393136 0.91877 0.233844 0.318086 -0.919468 -0.389896 0.0505916 -0.919904 -0.388896 0.0503724 -0.919201 -0.10263 0.38018 -0.919547 0.195857 0.340696 -0.918767 0.1572 0.362154 -0.918868 -0.059533 0.390048 -0.919876 -0.0898123 0.381787 -0.918983 -0.0154762 0.393995 -0.919941 0.00795919 0.391976 -0.919796 -0.262753 0.291439 0.918953 -0.341899 0.196545 0.91889 -0.361889 0.15709 0.918788 -0.388006 0.0726669 0.919159 -0.376603 0.115397 -0.919466 0.288712 -0.266886 -0.918761 0.318104 -0.233857 -0.919083 0.376772 -0.11545 -0.91993 0.379764 -0.0975071 -0.919661 0.286275 -0.26883 -0.919942 -0.249904 -0.302082 -0.919015 -0.267601 -0.289486 0.918767 0.1572 0.362154 0.919547 0.195857 0.340696 0.919578 0.196233 0.340394 -0.918838 0.0726478 0.387891 -0.919831 0.105259 0.37793 -0.919269 0.115325 0.376358 0.919 0.348225 0.184876 0.919943 0.335217 0.20331 0.919014 0.325309 0.222682 0.919031 -0.393137 0.0287246 1.64119e-06 0.991686 -0.128678 0.918868 -0.059533 0.390048 0.919876 -0.0898123 0.381787 0.919201 -0.10263 0.38018 0.918778 -0.144915 0.367215 0.919636 -0.182193 0.347959 0.919492 -0.184333 0.347213 -0.918778 -0.144915 0.367215 -0.919636 -0.182193 0.347959 -0.919492 -0.184333 0.347213 -0.91877 0.233844 0.318086 -0.919578 0.196233 0.340394 -0.919244 0.267237 0.289092 -0.919848 0.274281 0.280444 0.919796 -0.262753 0.291439 -0.918762 -0.223016 0.325792 -0.919315 -0.257245 0.2978 -0.918813 0.362053 -0.15716 -0.919777 0.343898 -0.18906 -0.919338 0.34112 -0.196098 -0.918782 0.258057 -0.29874 -0.919862 -0.167008 -0.354911 -0.918999 -0.233528 -0.317657 -0.918857 -0.196658 -0.342093 -0.918847 -0.298625 -0.257958 -0.919848 -0.317358 -0.230574 -0.919245 -0.324864 -0.222377 -0.919268 -0.389126 -0.0593931 -0.918767 -0.381157 -0.102893 -0.919577 -0.365318 -0.144639 -0.919548 -0.365545 -0.144253 -0.91877 -0.348698 -0.185125 0.918838 0.0726478 0.387891 0.919831 0.105259 0.37793 0.919269 0.115325 0.376358 -0.919 0.348225 0.184876 -0.919943 0.335217 0.20331 -0.919014 0.325309 0.222682 0.919083 0.376772 -0.11545 0.91993 0.379764 -0.0975072 0.919888 0.210142 -0.33113 -0.918829 0.0595474 -0.390137 0.919577 -0.365318 -0.144639 0.91877 -0.348698 -0.185125 0.918838 -0.394331 -0.0154911 0.919832 -0.389219 -0.0491698 0.919268 -0.389126 -0.059393 0.919607 -0.0736113 -0.385882 0.918774 -0.115661 -0.377462 -0.918773 0.390266 0.0595662 -0.919605 0.392489 0.0167036 -0.919521 0.392737 0.0154329 0.918773 0.390266 0.0595662 0.919605 0.392489 0.0167036 0.919521 0.392737 0.0154329 -0.918788 -0.388006 0.0726669 -0.919159 -0.376603 0.115397 -0.919899 -0.370425 0.128728 -0.919935 -0.326705 0.216757 0.918762 -0.223016 0.325792 0.919315 -0.257245 0.2978 -0.919888 0.210142 -0.33113 -0.919181 0.222462 -0.324988 -0.918878 0.185007 -0.348476 -0.919607 -0.0736113 -0.385882 -0.91952 -0.0723517 -0.386326 0.918761 0.318104 -0.233857 0.919661 0.286275 -0.26883 0.919466 0.288712 -0.266886 -0.919939 0.121154 -0.372873 -0.919048 0.102722 -0.380525 -0.918968 0.144749 -0.366803 0.918767 -0.381157 -0.102893 0.919548 -0.365545 -0.144253 0.919815 0.0246362 -0.391578 0.919939 0.121153 -0.372873 0.91952 -0.0723517 -0.386326 0.918878 0.185007 -0.348476 0.918968 0.144749 -0.366803 0.919862 -0.167008 -0.354911 0.919223 -0.156779 -0.361177 0.918857 -0.196658 -0.342093 0.918847 -0.298625 -0.257958 0.919848 -0.317358 -0.230574 0.919245 -0.324864 -0.222377 0.919942 -0.249904 -0.302082 0.919015 -0.267601 -0.289486 0.918999 -0.233528 -0.317657 -0.918857 0.367047 0.144841 -0.919862 0.375429 0.113614 -0.919224 0.380127 0.102617 0.918857 0.367047 0.144841 0.919862 0.375429 0.113614 0.919224 0.380127 0.102617 -0.918953 -0.341899 0.196545 -0.91889 -0.361889 0.15709 -0.919066 -0.31753 0.233436 -0.918821 -0.289817 0.267909 0.919066 -0.31753 0.233436 0.918821 -0.289817 0.267909 -0.919223 -0.156779 -0.361177 -0.918774 -0.115661 -0.377462 0.918813 0.362053 -0.15716 0.919777 0.343898 -0.18906 0.919338 0.34112 -0.196098 0.919181 0.222462 -0.324988 0.918782 0.258057 -0.29874 0.918829 0.0595473 -0.390137 0.919048 0.102722 -0.380525 0.919291 0.0154496 -0.393276 0.918764 -0.0287699 -0.393757 -0.919291 0.0154496 -0.393276 -0.918764 -0.0287699 -0.393757 0 0.99734 -0.072884 0 0.99734 -0.072884 0 -0.991686 0.128678 0 -0.991686 0.128678 0 0.982911 -0.184081 0 0.982911 -0.184081 0 0.956121 -0.292972 0 0.956121 -0.292972 0 -0.991686 0.128678 0 -0.991686 0.128678 0 0.398176 0.917309 0 0.398176 0.917309 0 0.756755 0.653698 0 0.756755 0.653698 0 0.678805 0.734318 0 0.678805 0.734318 0 -0.0392499 0.999229 0 -0.0392499 0.999229 0 0.0728645 0.997342 0 0.0728645 0.997342 0 0.498388 0.866954 0 0.498388 0.866954 0 0.59232 0.805703 0 0.59232 0.805703 0 -0.997341 0.0728708 0 -0.997341 0.0728708 0 0.991687 -0.128677 0 0.991687 -0.128677 0 0.991686 -0.128678 0 0.991686 -0.128678 0 -0.150883 0.988552 0 -0.150883 0.988552 0 -0.260621 0.965441 0 -0.260621 0.965441 0 -0.468909 0.883246 0 -0.468909 0.883246 0 -0.367082 0.930189 0 -0.367082 0.930189 0 0.184088 0.98291 0 0.184088 0.98291 0 0.292977 0.95612 0 0.292977 0.95612 0 0.88324 0.468922 0 0.88324 0.468922 0 0.825186 0.56486 0 0.825186 0.56486 0 -0.883243 -0.468916 0 -0.883243 -0.468916 0 -0.988551 -0.150885 0 -0.988551 -0.150885 0 -0.999229 -0.0392542 0 -0.999229 -0.0392542 0 0.988552 0.150883 0 0.988552 0.150883 0 0.999229 0.0392654 0 0.999229 0.0392654 0 -0.956122 0.29297 0 -0.956122 0.29297 0 -0.982911 0.184082 0 -0.982911 0.184082 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.564866 0.825182 0 -0.564866 0.825182 0 -0.653699 0.756755 0 -0.653699 0.756755 0 0.805703 -0.59232 0 0.805703 -0.59232 0 0.734318 -0.678805 0 0.734318 -0.678805 0 -0.965442 -0.26062 0 -0.965442 -0.26062 0 -0.930191 -0.367075 0 -0.930191 -0.367075 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.184081 -0.982911 0 -0.184081 -0.982911 0 0.367075 -0.930191 0 0.367075 -0.930191 0 0.468916 -0.883243 0 0.468916 -0.883243 0 -0.498384 -0.866956 0 -0.498384 -0.866956 0 -0.756755 -0.653699 0 -0.756755 -0.653699 0 -0.825187 -0.564859 0 -0.825187 -0.564859 0 -0.59232 -0.805703 0 -0.59232 -0.805703 0 -0.678805 -0.734318 0 -0.678805 -0.734318 0 0.930195 0.367065 0 0.930195 0.367065 0 0.96544 0.260625 0 0.96544 0.260625 0 -0.917305 0.398186 0 -0.917305 0.398186 0 -0.866957 0.498382 0 -0.866957 0.498382 0 -0.805702 0.592321 0 -0.805702 0.592321 0 -0.734316 0.678808 0 -0.734316 0.678808 0 -0.398184 -0.917306 0 -0.398184 -0.917306 0 -0.292972 -0.956121 0 -0.292972 -0.956121 0 0.917306 -0.398184 0 0.917306 -0.398184 0 0.866956 -0.498384 0 0.866956 -0.498384 0 0.564859 -0.825187 0 0.564859 -0.825187 0 0.653699 -0.756755 0 0.653699 -0.756755 0 0.150885 -0.988551 0 0.150885 -0.988551 0 0.26062 -0.965442 0 0.26062 -0.965442 0 0.0392542 -0.999229 0 0.0392542 -0.999229 0 -0.0728708 -0.997341 0 -0.0728708 -0.997341 + + + + + + + + + + + + + + +

15 0 109 0 6 0 6 1 5 1 15 1 2 2 72 2 71 2 2 3 71 3 1 3 72 4 11 4 10 4 2 5 11 5 72 5 115 6 0 6 114 6 114 7 0 7 3 7 15 8 118 8 108 8 15 9 108 9 109 9 9 10 8 10 115 10 0 11 115 11 8 11 111 12 66 12 109 12 111 13 110 13 159 13 79 14 78 14 170 14 69 15 57 15 70 15 70 16 57 16 35 16 75 17 70 17 14 17 70 18 35 18 14 18 14 19 4 19 7 19 74 20 29 20 31 20 23 21 21 21 94 21 11 22 2 22 37 22 22 23 20 23 125 23 125 24 20 24 124 24 124 25 20 25 25 25 112 26 26 26 28 26 113 27 26 27 112 27 30 28 26 28 113 28 124 29 25 29 32 29 14 30 7 30 87 30 14 31 87 31 75 31 40 32 39 32 91 32 33 33 73 33 18 33 18 34 73 34 17 34 27 35 88 35 39 35 39 36 88 36 91 36 29 37 88 37 27 37 29 38 74 38 88 38 86 39 98 39 85 39 159 40 157 40 111 40 66 41 111 41 157 41 109 42 65 42 6 42 66 43 65 43 109 43 77 44 101 44 104 44 101 45 77 45 100 45 12 46 76 46 10 46 76 47 72 47 10 47 81 48 77 48 104 48 153 49 93 49 84 49 153 50 150 50 93 50 16 51 127 51 19 51 32 52 19 52 127 52 32 53 127 53 124 53 74 54 31 54 47 54 74 55 47 55 73 55 73 56 47 56 17 56 123 57 49 57 51 57 123 58 51 58 125 58 125 59 51 59 22 59 15 60 34 60 118 60 8 61 36 61 0 61 112 62 28 62 38 62 112 63 38 63 119 63 119 64 38 64 41 64 119 65 41 65 43 65 119 66 43 66 126 66 126 67 43 67 45 67 91 68 42 68 40 68 85 69 42 69 91 69 44 70 42 70 85 70 24 71 82 71 33 71 82 72 73 72 33 72 23 73 82 73 24 73 23 74 94 74 82 74 126 75 97 75 110 75 85 76 96 76 44 76 98 77 96 77 85 77 12 78 165 78 76 78 76 79 165 79 77 79 77 80 165 80 100 80 81 81 104 81 167 81 84 82 83 82 147 82 84 83 145 83 153 83 84 84 147 84 145 84 150 85 151 85 93 85 93 86 151 86 90 86 90 87 151 87 54 87 58 88 57 88 69 88 106 89 58 89 69 89 90 90 53 90 69 90 53 91 106 91 69 91 90 92 54 92 53 92 113 93 46 93 30 93 127 94 46 94 113 94 127 95 16 95 46 95 92 96 48 96 50 96 94 97 48 97 92 97 21 98 48 98 94 98 9 99 128 99 13 99 9 100 115 100 128 100 130 101 131 101 143 101 78 102 171 102 170 102 117 103 52 103 116 103 116 104 52 104 55 104 34 105 56 105 118 105 118 106 56 106 117 106 117 107 56 107 59 107 137 108 132 108 133 108 163 109 137 109 133 109 62 110 63 110 80 110 80 111 63 111 71 111 71 112 63 112 1 112 120 113 60 113 61 113 114 114 60 114 120 114 114 115 3 115 60 115 87 116 7 116 64 116 67 117 87 117 64 117 67 118 68 118 87 118 68 119 158 119 86 119 45 120 95 120 126 120 97 121 126 121 95 121 81 122 142 122 89 122 167 123 142 123 81 123 142 124 141 124 89 124 79 125 136 125 83 125 135 126 136 126 79 126 102 127 99 127 129 127 130 128 103 128 129 128 129 129 103 129 102 129 89 130 139 130 78 130 139 131 171 131 78 131 141 132 139 132 89 132 117 133 59 133 105 133 105 134 52 134 117 134 169 135 107 135 132 135 140 136 131 136 107 136 134 137 132 137 137 137 131 138 138 138 143 138 140 139 138 139 131 139 121 140 144 140 133 140 144 141 163 141 133 141 121 142 146 142 144 142 122 143 148 143 149 143 116 144 148 144 122 144 116 145 55 145 148 145 122 146 152 146 121 146 149 147 152 147 122 147 121 148 152 148 146 148 92 149 50 149 155 149 92 150 155 150 80 150 155 151 62 151 80 151 123 152 154 152 49 152 120 153 154 153 123 153 61 154 154 154 120 154 68 155 156 155 158 155 68 156 67 156 156 156 158 157 161 157 86 157 86 158 161 158 98 158 110 159 160 159 159 159 97 160 160 160 110 160 83 161 162 161 147 161 136 162 162 162 83 162 128 163 164 163 13 163 129 164 164 164 128 164 99 165 164 165 129 165 130 166 143 166 166 166 166 167 103 167 130 167 168 168 107 168 169 168 107 169 168 169 140 169 132 170 173 170 169 170 134 171 173 171 132 171 79 172 170 172 172 172 135 173 79 173 172 173 1 174 0 174 2 174 3 175 0 175 1 175 4 176 5 176 6 176 7 177 4 177 6 177 9 178 10 178 8 178 11 179 8 179 10 179 9 180 12 180 10 180 12 181 9 181 13 181 4 182 14 182 5 182 5 183 14 183 15 183 18 184 17 184 16 184 18 185 16 185 19 185 21 186 20 186 22 186 21 187 23 187 20 187 24 188 20 188 23 188 20 189 24 189 25 189 28 190 26 190 27 190 29 191 27 191 26 191 30 192 31 192 26 192 29 193 26 193 31 193 18 194 19 194 32 194 18 195 32 195 33 195 24 196 32 196 25 196 24 197 33 197 32 197 14 198 35 198 34 198 14 199 34 199 15 199 0 200 36 200 2 200 37 201 2 201 36 201 8 202 11 202 36 202 37 203 36 203 11 203 27 204 38 204 28 204 39 205 38 205 27 205 40 206 41 206 38 206 39 207 40 207 38 207 45 208 42 208 44 208 43 209 42 209 45 209 40 210 42 210 41 210 42 211 43 211 41 211 30 212 46 212 31 212 47 213 31 213 46 213 16 214 17 214 46 214 47 215 46 215 17 215 48 216 49 216 50 216 48 217 51 217 49 217 22 218 48 218 21 218 51 219 48 219 22 219 55 220 52 220 54 220 53 221 54 221 52 221 59 222 56 222 58 222 58 223 56 223 57 223 56 224 34 224 35 224 57 225 56 225 35 225 61 226 60 226 62 226 63 227 62 227 60 227 1 228 60 228 3 228 63 229 60 229 1 229 64 230 65 230 66 230 67 231 64 231 66 231 7 232 6 232 64 232 65 233 64 233 6 233 69 234 70 234 68 234 71 235 72 235 68 235 73 236 68 236 74 236 75 237 68 237 70 237 76 238 77 238 68 238 78 239 79 239 68 239 80 240 71 240 68 240 81 241 68 241 77 241 82 242 68 242 73 242 83 243 84 243 68 243 85 244 68 244 86 244 87 245 68 245 75 245 88 246 74 246 68 246 78 247 68 247 89 247 90 248 69 248 68 248 85 249 91 249 68 249 92 250 80 250 68 250 88 251 68 251 91 251 76 252 68 252 72 252 81 253 89 253 68 253 84 254 93 254 68 254 90 255 68 255 93 255 92 256 68 256 94 256 82 257 94 257 68 257 83 258 68 258 79 258 44 259 95 259 45 259 96 260 95 260 44 260 97 261 95 261 98 261 98 262 95 262 96 262 101 263 100 263 99 263 99 264 102 264 101 264 102 265 103 265 101 265 101 266 103 266 104 266 58 267 105 267 59 267 58 268 106 268 105 268 52 269 105 269 53 269 53 270 105 270 106 270 108 271 107 271 109 271 110 272 111 272 107 272 109 273 107 273 111 273 112 274 107 274 113 274 114 275 107 275 115 275 116 276 107 276 117 276 108 277 118 277 107 277 119 278 107 278 112 278 120 279 107 279 114 279 121 280 107 280 122 280 123 281 107 281 120 281 124 282 107 282 125 282 110 283 107 283 126 283 127 284 107 284 124 284 128 285 107 285 129 285 123 286 125 286 107 286 119 287 126 287 107 287 127 288 113 288 107 288 130 289 129 289 107 289 117 290 107 290 118 290 128 291 115 291 107 291 130 292 107 292 131 292 116 293 122 293 107 293 132 294 107 294 133 294 121 295 133 295 107 295 136 296 134 296 137 296 136 297 135 297 134 297 139 298 138 298 140 298 139 299 141 299 138 299 143 300 138 300 142 300 142 301 138 301 141 301 145 302 144 302 146 302 145 303 147 303 144 303 149 304 148 304 150 304 151 305 150 305 148 305 54 306 148 306 55 306 151 307 148 307 54 307 145 308 152 308 153 308 146 309 152 309 145 309 150 310 153 310 152 310 149 311 150 311 152 311 49 312 154 312 50 312 155 313 50 313 154 313 61 314 62 314 154 314 155 315 154 315 62 315 66 316 156 316 67 316 157 317 156 317 66 317 158 318 156 318 159 318 157 319 159 319 156 319 159 320 160 320 158 320 160 321 161 321 158 321 98 322 160 322 97 322 161 323 160 323 98 323 144 324 147 324 162 324 144 325 162 325 163 325 162 326 136 326 137 326 163 327 162 327 137 327 164 328 12 328 13 328 12 329 164 329 165 329 99 330 100 330 164 330 165 331 164 331 100 331 142 332 167 332 166 332 142 333 166 333 143 333 103 334 166 334 104 334 167 335 104 335 166 335 169 336 170 336 168 336 171 337 168 337 170 337 139 338 140 338 168 338 139 339 168 339 171 339 169 340 172 340 170 340 173 341 172 341 169 341 134 342 135 342 172 342 173 343 134 343 172 343

+
+
+
+
+ + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae new file mode 100644 index 0000000..ba52bc9 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_85_outer_knuckle.dae @@ -0,0 +1,56 @@ + + + + + VCGLab + VCGLib | MeshLab + + Mon Dec 3 16:33:09 2018 GMT + Mon Dec 3 16:33:09 2018 GMT + Y_UP + + + + + + -5 31.6768 -9.08188 11.5 24.2004 9.27773 11.5 24.8506 9.36074 5 32.8239 -8.90321 -11.5 24.2004 9.27773 11.5 25.5 9.27188 -11.5 24.8506 9.36074 -5.5 -0.0514696 -7.49982 5 31.6768 -9.08188 5 32.2556 -9.02595 -11.5 26.1041 9.01725 -11.5 25.5 9.27188 11.5 26.1041 9.01725 5 35.9084 -6.4185 5 33.8989 -8.46482 5 33.3742 -8.71532 5 35.6077 -6.91613 5 34.8438 -7.79034 5 34.391 -8.1551 5 35.2512 -7.37548 -5 32.2556 -9.02595 -5 35.9084 -6.4185 -5 35.6077 -6.91613 -5 32.8239 -8.90321 -5 33.3742 -8.71532 -5 34.391 -8.1551 -5 33.8989 -8.46482 -5 35.2512 -7.37548 -5 34.8438 -7.79034 5.5 -0.0514696 -7.49982 -4.5 23.6897 12.7496 5.5 -1.3275 7.38158 4.5 23.6897 12.7496 -5.5 -1.3275 7.38158 4.5 31.1073 -10.0736 -4.5 31.1073 -10.0736 -4.5 31.7519 -10.0796 4.5 31.7519 -10.0796 4.5 24.3268 12.8388 -4.5 24.3268 12.8388 -4.5 25.6114 12.8109 4.5 33.5449 11.7815 -4.5 33.5449 11.7815 4.5 25.6114 12.8109 5.5 -7.47258 -0.640746 -5.5 -7.49982 0.0514696 -5.5 -7.47258 -0.640746 5.5 -7.49982 0.0514696 4.5 38.644 7.0678 -4.5 38.644 7.0678 -4.5 38.4687 7.71739 4.5 38.4687 7.71739 4.5 24.9699 12.8593 -4.5 24.9699 12.8593 4.5 38.2217 8.34326 -4.5 38.2217 8.34326 4.5 37.9062 8.93755 -4.5 37.9062 8.93755 4.5 32.3935 -10.0165 -4.5 32.3935 -10.0165 -5.5 -3.29689 6.73651 5.5 -3.90439 6.40357 5.5 -3.29689 6.73651 -5.5 -3.90439 6.40357 -5.5 -2.00292 7.22761 5.5 -2.00292 7.22761 4.5 34.2062 11.6576 -4.5 34.2062 11.6576 -4.5 34.8496 11.4605 4.5 34.8496 11.4605 -5.5 -7.38158 -1.3275 5.5 -7.38158 -1.3275 5.5 -7.22761 -2.00292 -5.5 -7.22761 -2.00292 -5.5 -7.01197 -2.66125 5.5 -7.01197 -2.66125 5.5 -7.46308 0.743246 -5.5 -7.46308 0.743246 5.5 -2.66125 7.01197 -5.5 -2.66125 7.01197 5.5 -6.73651 -3.29689 -5.5 -6.73651 -3.29689 5.5 -6.01601 -4.47858 -5.5 -6.01601 -4.47858 -5.5 -5.57711 -5.01456 5.5 -5.57711 -5.01456 -4.5 37.4362 -4.85759 -4.5 38.7229 5.05927 4.5 38.7229 5.05927 4.5 37.4362 -4.85759 12 26.8227 6.60341 12 26.7014 7.59074 12 26.8244 7.10474 12 26.1194 8.39748 12 25.697 8.66754 12 23.7734 8.55302 12 24.2277 8.76495 12 25.6848 5.04825 12 26.109 5.31545 12 24.7205 8.85723 12 23.762 5.17573 12 23.3768 5.49659 12 22.8393 6.86751 12 22.9039 7.36467 12 23.0835 5.90317 12 23.09 7.83017 12 26.4613 8.03087 12 26.6964 6.11825 12 26.4534 5.67974 12 22.9005 6.36992 12 23.386 8.23477 12 24.2149 4.96074 12 24.707 4.86515 12 25.2075 4.89494 12 25.2207 8.82406 4.5 37.5261 9.49277 -4.5 37.5261 9.49277 -4.5 37.0863 10.002 4.5 37.0863 10.002 4.5 35.4668 11.1926 -4.5 35.4668 11.1926 -4.5 36.0501 10.8572 4.5 36.0501 10.8572 4.5 36.5922 10.4587 -4.5 36.5922 10.4587 4.5 36.8848 -6.70353 -4.5 36.8848 -6.70353 -4.5 37.1345 -6.1092 4.5 37.1345 -6.1092 -4.5 36.5727 -7.26763 4.5 36.5727 -7.26763 4.5 36.202 -7.795 -4.5 36.202 -7.795 5.5 -6.34938 3.99191 -5.5 -6.34938 3.99191 -5.5 -5.95397 4.56073 5.5 -5.95397 4.56073 -5.5 -6.69063 3.38903 5.5 -6.69063 3.38903 5.5 -6.97478 2.75724 -5.5 -6.97478 2.75724 -5.5 -7.19944 2.10193 5.5 -7.19944 2.10193 -5.5 -5.50776 5.09063 5.5 -5.50776 5.09063 -5.5 -5.01456 5.57711 5.5 -5.01456 5.57711 -5.5 -6.40357 -3.90439 5.5 -6.40357 -3.90439 -5.5 -5.09063 -5.50776 5.5 -5.09063 -5.50776 -5.5 -4.56073 -5.95397 5.5 -4.56073 -5.95397 -5.5 -7.36267 1.42868 5.5 -7.36267 1.42868 -4.5 37.319 -5.49151 4.5 37.319 -5.49151 -12 26.8244 7.10474 -12 26.4534 5.67974 -12 26.6964 6.11825 -12 22.9039 7.36467 -12 22.8393 6.86751 -12 26.4613 8.03087 -12 26.1194 8.39748 -12 24.2277 8.76495 -12 24.7205 8.85723 -12 25.697 8.66754 -12 25.6848 5.04825 -12 25.2075 4.89494 -12 23.762 5.17573 -12 23.3768 5.49659 -12 23.0835 5.90317 -12 25.2207 8.82406 -12 24.707 4.86515 -12 23.386 8.23477 -12 23.09 7.83017 -12 26.7014 7.59074 -12 24.2149 4.96074 -12 22.9005 6.36992 -12 26.109 5.31545 -12 26.8227 6.60341 -12 23.7734 8.55302 -4.5 33.0246 -9.88491 4.5 33.0246 -9.88491 -5.5 -4.47858 6.01601 5.5 -4.47858 6.01601 5.5 -3.38903 -6.69063 5.5 -2.75724 -6.97478 -5.5 -2.75724 -6.97478 -5.5 -3.38903 -6.69063 -4.5 38.7456 6.40266 4.5 38.7456 6.40266 -4.5 33.6379 -9.68637 4.5 34.2264 -9.42318 -4.5 34.2264 -9.42318 4.5 33.6379 -9.68637 -4.5 34.7832 -9.09836 4.5 34.7832 -9.09836 4.5 35.302 -8.71568 -4.5 35.302 -8.71568 -4.5 35.7767 -8.27955 4.5 35.7767 -8.27955 5.5 -3.99191 -6.34938 -5.5 -3.99191 -6.34938 5.5 -0.743246 -7.46308 5.5 -1.42868 -7.36267 -5.5 -1.42868 -7.36267 -5.5 -0.743246 -7.46308 5.5 -2.10193 -7.19944 -5.5 -2.10193 -7.19944 -4.5 38.772 5.73033 4.5 38.772 5.73033 + + + + + + + + + + -0.894484 0.0430027 -0.445027 -0.447782 -0.170442 0.877748 -0.713416 -0.128977 0.688769 0.447782 -0.170442 0.877748 0.537566 -0.187414 0.82213 0.694759 -0.0910849 0.713452 0.95725 -0.233457 0.170794 -0.448148 -0.123954 0.885324 -0.446496 -0.0285076 0.894331 -0.448887 -0.113165 0.886394 -0.455042 0.120721 0.882249 -0.694759 -0.0910849 0.713452 -0.900953 0.0417347 -0.431906 0.978909 -0.190202 -0.0745734 -0.835282 0.530833 0.143252 -0.826042 0.524259 0.2069 -0.814469 0.512468 0.272061 0.448148 -0.123954 0.885324 0.448887 -0.113165 0.886394 0.449191 0.114963 0.886009 0.813244 0.510853 0.278682 0.627961 0.302278 0.717142 0.455042 0.120721 0.882249 0.692813 0.280089 0.6645 0.896122 0.388189 -0.215116 0.89876 0.375252 -0.226752 0.907202 0.0888135 -0.411213 0.911034 0.126097 -0.392577 0.914402 0.215752 -0.342522 0.894774 0.0942653 -0.436455 0.911469 0.13292 -0.389303 -0.8943 0.043796 -0.445319 0.895794 0.380412 -0.22987 -0.568019 0.241066 0.786919 -0.491271 0.160398 0.85611 -0.44697 0.0673006 0.892014 -0.449191 0.114963 0.886009 -0.813244 0.510853 0.278682 -0.772188 0.464678 0.433359 -0.894065 0.00159371 -0.447933 -0.898606 0.0260688 -0.437982 -0.892964 -0.00419001 -0.450108 -0.933962 -0.0681456 -0.350816 -0.925531 -0.0548863 -0.374674 -0.940666 -0.0799551 -0.329779 -0.96026 -0.11969 -0.25214 0.971579 -0.151503 -0.181882 -0.977228 -0.211894 0.0112539 -0.978719 -0.203669 -0.0250495 -0.978153 -0.207728 -0.00817461 0.974125 -0.219646 0.0532538 0.705014 -0.214325 0.676032 0.713416 -0.128977 0.688769 0.892165 -0.00867246 -0.451627 0.892964 -0.00419019 -0.450108 0.978153 -0.207728 -0.00817456 0.978719 -0.203669 -0.0250496 0.978758 -0.203243 -0.0269312 0.979029 -0.193598 -0.0634141 0.979027 -0.198636 -0.0452815 0.841428 0.534174 0.0815955 0.836503 0.531214 0.134442 0.835282 0.530833 0.143252 0.845681 0.533278 0.0209381 0.874172 0.465302 -0.138984 0.44697 0.0673008 0.892014 0.446496 -0.0285074 0.894331 0.826042 0.524259 0.206901 0.814469 0.512468 0.272061 -0.779385 0.474179 0.409529 -0.798729 0.496491 0.339895 -0.754503 0.445474 0.481953 -0.723643 0.408782 0.556091 0.772188 0.464678 0.433359 0.716752 0.375625 0.587514 0.71107 0.392536 0.583348 0.715872 0.217983 0.663333 0.714768 0.0462753 0.697829 0.693693 0.097647 0.713621 -0.913194 0.255654 -0.317361 -0.914402 0.215752 -0.342522 -0.907203 0.0888141 -0.411212 -0.911034 0.126097 -0.392576 -0.911469 0.13292 -0.389303 -0.886379 0.42682 -0.179322 0.895707 0.236846 -0.376314 0.9144 0.215629 -0.342602 0.913654 0.175131 -0.366832 0.893671 0.138201 -0.426911 0.895169 0.144022 -0.421817 0.8943 0.043796 -0.445319 0.89404 0.0914431 -0.438554 0.909979 0.301314 -0.284863 0.90569 0.334911 -0.259923 0.892965 0.267198 -0.362241 -0.813229 -0.231397 0.533961 -0.705014 -0.214325 0.676032 -0.717954 -0.216681 0.661507 -0.537566 -0.187414 0.82213 -0.958954 -0.232832 0.161851 -0.96447 -0.229915 0.13014 -0.968637 -0.226617 0.101922 -0.95725 -0.233457 0.170794 0.951379 -0.235614 0.198402 0.940866 -0.237905 0.241191 0.568019 0.241066 0.786919 0.491271 0.160398 0.85611 -0.715872 0.217983 0.663333 -0.714768 0.0462753 0.697829 -0.693693 0.097647 0.713621 -0.676114 -0.0390763 -0.73576 -0.892165 -0.00867247 -0.451627 -0.902991 -0.0227875 -0.429056 -0.978758 -0.203243 -0.0269316 -0.979027 -0.198636 -0.0452815 -0.979029 -0.193598 -0.0634141 -0.978909 -0.190202 -0.0745733 -0.978743 -0.188181 -0.08155 -0.976839 -0.173536 -0.125186 -0.975887 -0.168878 -0.13829 -0.958837 -0.116472 -0.258969 -0.951204 -0.100067 -0.291885 -0.971579 -0.151503 -0.181882 0.974088 -0.161019 -0.158825 0.971732 -0.152068 -0.18059 -0.971764 -0.223204 0.0765209 -0.970216 -0.224934 0.0899251 -0.976204 -0.215048 0.0279429 0.976204 -0.215047 0.0279423 0.975928 -0.215788 0.0316103 0.977228 -0.211894 0.0112537 0.903504 -0.239771 0.355232 0.869031 -0.237782 0.433872 0.833306 -0.233707 0.500982 0.926256 -0.239243 0.291227 0.925942 -0.239273 0.292198 0.717954 -0.216681 0.661507 0.813229 -0.231397 0.533961 0.894484 0.0430027 -0.445027 0.894065 0.001594 -0.447934 0.898606 0.0260688 -0.437982 0.900953 0.0417349 -0.431906 0.978743 -0.188181 -0.08155 0.978136 -0.182372 -0.099949 0.976839 -0.173536 -0.125186 0.977217 -0.17592 -0.11874 0.975887 -0.168878 -0.13829 -0.847998 0.525594 -0.0681953 0.869534 0.477943 -0.124422 0.85786 0.50532 -0.0934243 0.847998 0.525594 -0.0681952 0.847045 0.531518 -0.00180178 0.847624 0.529184 -0.038719 0.779385 0.474179 0.409529 0.798729 0.496491 0.339895 -0.683408 0.363906 0.632871 -0.716752 0.375625 0.587514 -0.71107 0.392536 0.583348 -0.692813 0.280089 0.6645 -0.627961 0.302278 0.717142 -0.63298 0.308247 0.710154 0.63298 0.308247 0.710154 0.683408 0.363906 0.632871 0.754503 0.445474 0.481953 0.723643 0.408783 0.556091 -0.913654 0.175131 -0.366832 -0.9144 0.215629 -0.342602 -0.895484 0.191761 -0.401666 -0.90998 0.301314 -0.284863 -0.910518 0.295007 -0.289704 -0.90569 0.334911 -0.259923 -0.895904 0.350954 -0.272373 -0.892911 0.368339 -0.258914 0.893044 0.393725 -0.217836 0.886379 0.42682 -0.179322 0.893984 0.397304 -0.207225 0.895484 0.191761 -0.401666 0.893364 0.183443 -0.410182 0.893132 0.226648 -0.388517 0.892859 0.338455 -0.29707 0.892911 0.368339 -0.258914 0.895904 0.350954 -0.272373 0.895854 0.278755 -0.346037 0.913194 0.255654 -0.317361 0.910518 0.295007 -0.289704 0.895913 0.316954 -0.311257 0.892874 0.304658 -0.331601 0.958954 -0.232832 0.161851 0.96447 -0.229915 0.13014 0.970215 -0.224934 0.0899255 0.968637 -0.226617 0.101922 0.971764 -0.223204 0.0765209 -0.951379 -0.235614 0.198402 -0.940866 -0.237905 0.241191 -0.869032 -0.237782 0.433871 -0.833306 -0.233707 0.500982 -0.926256 -0.239243 0.291227 -0.978136 -0.182372 -0.099949 -0.977217 -0.17592 -0.11874 -0.974088 -0.161019 -0.158825 -0.971732 -0.152068 -0.18059 -0.964391 -0.130282 -0.230167 -0.968557 -0.142006 -0.204284 -0.974125 -0.219646 0.0532533 -0.975928 -0.215788 0.0316111 -0.85786 0.505321 -0.0934236 -0.869534 0.477943 -0.124423 -0.874172 0.465302 -0.138984 -0.836503 0.531214 0.134442 -0.89404 0.0914431 -0.438554 -0.894774 0.0942653 -0.436455 -0.895854 0.278755 -0.346037 -0.896122 0.388189 -0.215116 -0.893044 0.393725 -0.217836 -0.893984 0.397304 -0.207225 -0.89876 0.375252 -0.226752 -0.895794 0.380412 -0.22987 -0.903504 -0.239771 0.355233 -0.925942 -0.239273 0.292198 0.96026 -0.11969 -0.25214 0.958837 -0.116472 -0.258969 0.933962 -0.0681458 -0.350815 -0.841428 0.534174 0.0815955 -0.895169 0.144022 -0.421817 -0.893671 0.138201 -0.426911 -0.893364 0.183443 -0.410182 -0.892965 0.267198 -0.362241 -0.895707 0.236846 -0.376314 -0.893132 0.226648 -0.388517 -0.895913 0.316954 -0.311257 -0.892874 0.304658 -0.331601 -0.892859 0.338455 -0.29707 0.968557 -0.142006 -0.204283 0.964391 -0.130282 -0.230167 0.676115 -0.0390762 -0.735759 0.902991 -0.0227872 -0.429056 0.925531 -0.0548863 -0.374674 0.951204 -0.100067 -0.291885 0.940666 -0.0799551 -0.329779 -0.847045 0.531518 -0.00180178 -0.845681 0.533278 0.0209381 -0.847624 0.529184 -0.0387184 0 -0.209798 0.977745 0 -0.209798 0.977745 0 -0.0093085 -0.999957 0 -0.0093085 -0.999957 0 -0.138657 0.99034 0 -0.138657 0.99034 0 0.128675 0.991687 0 0.128675 0.991687 0 -0.999227 -0.0393219 0 -0.999227 -0.0393219 0 0.965462 0.260543 0 0.965462 0.260543 0 0.0752342 0.997166 0 0.0752342 0.997166 0 -0.0318594 0.999492 0 -0.0318594 0.999492 0 0.930182 0.367099 0 0.930182 0.367099 0 0.88325 0.468902 0 0.88325 0.468902 0 0.0978752 -0.995199 0 0.0978752 -0.995199 0 -0.480604 0.876938 0 -0.480604 0.876938 0 -0.22226 0.974988 0 -0.22226 0.974988 0 0.292906 0.956141 0 0.292906 0.956141 0 0.184153 0.982898 0 0.184153 0.982898 0 -0.991335 -0.131359 0 -0.991335 -0.131359 0 -0.974988 -0.22226 0 -0.974988 -0.22226 0 -0.950318 -0.311282 0 -0.950318 -0.311282 0 -0.998593 0.0530353 0 -0.998593 0.0530353 0 -0.311282 0.950318 0 -0.311282 0.950318 0 -0.397627 0.917547 0 -0.397627 0.917547 0 -0.917547 -0.397627 0 -0.917547 -0.397627 0 -0.773695 -0.633558 0 -0.773695 -0.633558 0 0.991687 -0.12867 0 0.991687 -0.12867 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.756815 0.653629 0 0.756815 0.653629 0 0.82516 0.564899 0 0.82516 0.564899 0 0.398166 0.917313 0 0.398166 0.917313 0 0.498476 0.866903 0 0.498476 0.866903 0 0.678769 0.734352 0 0.678769 0.734352 0 0.592289 0.805726 0 0.592289 0.805726 0 0.921938 -0.387338 0 0.921938 -0.387338 0 0.875005 -0.484114 0 0.875005 -0.484114 0 0.818107 -0.575067 0 0.818107 -0.575067 0 -0.821102 0.570782 0 -0.821102 0.570782 0 -0.870259 0.492595 0 -0.870259 0.492595 0 -0.945954 0.324301 0 -0.945954 0.324301 0 -0.912005 0.410178 0 -0.912005 0.410178 0 -0.764927 0.644117 0 -0.764927 0.644117 0 -0.70224 0.71194 0 -0.70224 0.71194 0 -0.876938 -0.480604 0 -0.876938 -0.480604 0 -0.828861 -0.559455 0 -0.828861 -0.559455 0 -0.71194 -0.70224 0 -0.71194 -0.70224 0 -0.644117 -0.764927 0 -0.644117 -0.764927 0 -0.971844 0.235624 0 -0.971844 0.235624 0 -0.98944 0.144944 0 -0.98944 0.144944 0 0.958169 -0.286202 0 0.958169 -0.286202 0 0.983336 -0.181799 0 0.983336 -0.181799 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.20412 -0.978946 0 0.20412 -0.978946 0 -0.559455 0.828861 0 -0.559455 0.828861 0 -0.633558 0.773695 0 -0.633558 0.773695 0 -0.410178 -0.912005 0 -0.410178 -0.912005 0 0.988534 0.150999 0 0.988534 0.150999 0 0.408256 -0.912867 0 0.408256 -0.912867 0 0.307987 -0.95139 0 0.307987 -0.95139 0 0.503893 -0.863766 0 0.503893 -0.863766 0 0.593608 -0.804754 0 0.593608 -0.804754 0 0.751561 -0.659663 0 0.751561 -0.659663 0 0.676557 -0.73639 0 0.676557 -0.73639 0 -0.570782 -0.821102 0 -0.570782 -0.821102 0 -0.492595 -0.870259 0 -0.492595 -0.870259 0 -0.144944 -0.98944 0 -0.144944 -0.98944 0 -0.0816876 -0.996658 0 -0.0816876 -0.996658 0 -0.324301 -0.945954 0 -0.324301 -0.945954 0 -0.235624 -0.971844 0 -0.235624 -0.971844 0 0.997334 -0.0729712 0 0.997334 -0.0729712 0 0.99923 0.0392328 0 0.99923 0.0392328 + + + + + + + + + + + + + + +

0 0 20 0 36 0 30 1 4 1 33 1 164 2 4 2 165 2 1 3 32 3 31 3 1 4 31 4 65 4 1 5 99 5 2 5 136 6 105 6 110 6 39 7 4 7 30 7 6 8 39 8 53 8 39 9 6 9 4 9 6 10 42 10 11 10 4 11 6 11 165 11 168 12 20 12 0 12 109 13 75 13 104 13 49 14 176 14 50 14 50 15 176 15 55 15 176 16 57 16 55 16 32 17 1 17 38 17 38 18 1 18 2 18 41 19 43 19 2 19 106 20 91 20 56 20 5 21 12 21 69 21 5 22 41 22 2 22 5 23 94 23 12 23 13 24 107 24 108 24 16 25 13 25 108 25 9 26 3 26 113 26 97 27 113 27 3 27 97 28 18 28 98 28 183 29 3 29 9 29 15 30 97 30 3 30 59 31 36 31 20 31 130 32 13 32 16 32 11 33 67 33 68 33 67 34 11 34 42 34 40 35 6 35 53 35 6 36 40 36 42 36 162 37 57 37 176 37 162 38 163 38 117 38 173 39 0 39 36 39 173 40 168 40 0 40 36 41 35 41 173 41 173 42 206 42 177 42 173 43 207 43 206 43 209 44 177 44 206 44 177 45 189 45 169 45 152 46 100 46 101 46 161 47 45 47 77 47 161 48 178 48 46 48 161 49 46 49 45 49 103 50 142 50 154 50 96 51 1 51 65 51 99 52 1 52 96 52 112 53 29 53 34 53 112 54 34 54 37 54 44 55 102 55 47 55 44 56 109 56 102 56 44 57 71 57 109 57 72 58 75 58 109 58 72 59 109 59 71 59 191 60 48 60 92 60 48 61 91 61 92 61 48 62 51 62 91 62 211 63 191 63 92 63 156 64 107 64 128 64 2 65 43 65 52 65 52 66 38 66 2 66 54 67 91 67 51 67 54 68 56 68 91 68 116 69 162 69 117 69 57 70 162 70 116 70 163 71 124 71 117 71 124 72 163 72 121 72 93 73 106 73 118 73 94 74 93 74 12 74 93 75 122 75 12 75 114 76 94 76 5 76 99 77 114 77 2 77 114 78 5 78 2 78 25 79 179 79 28 79 179 80 25 80 167 80 168 81 23 81 20 81 23 82 168 82 167 82 23 83 167 83 24 83 126 84 159 84 127 84 14 85 197 85 18 85 97 86 14 86 18 86 14 87 97 87 15 87 183 88 195 88 3 88 195 89 15 89 3 89 58 90 9 90 37 90 58 91 183 91 9 91 98 92 19 92 108 92 19 93 16 93 108 93 198 94 18 94 197 94 60 95 79 95 164 95 164 96 64 96 4 96 79 97 64 97 164 97 4 98 64 98 33 98 175 99 134 99 135 99 134 100 175 100 137 100 140 101 137 101 175 101 174 102 175 102 135 102 144 103 136 103 110 103 146 104 144 104 110 104 66 105 5 105 69 105 41 106 5 106 66 106 166 107 172 107 11 107 165 108 6 108 172 108 172 109 6 109 11 109 35 110 207 110 7 110 7 111 173 111 35 111 173 112 7 112 207 112 178 113 70 113 46 113 70 114 178 114 73 114 74 115 73 115 178 115 74 116 178 116 171 116 74 117 171 117 81 117 83 118 171 118 170 118 83 119 170 119 84 119 188 120 189 120 177 120 209 121 188 121 177 121 151 122 170 122 169 122 150 123 101 123 85 123 150 124 152 124 101 124 141 125 140 125 160 125 160 126 140 126 175 126 160 127 161 127 77 127 76 128 102 128 103 128 103 129 154 129 76 129 47 130 102 130 76 130 95 131 61 131 185 131 95 132 62 132 61 132 95 133 96 133 62 133 95 134 146 134 110 134 95 135 185 135 146 135 78 136 96 136 65 136 62 137 96 137 78 137 37 138 9 138 8 138 8 139 112 139 37 139 112 140 8 140 113 140 8 141 9 141 113 141 80 142 104 142 75 142 80 143 148 143 104 143 82 144 101 144 104 144 148 145 82 145 104 145 101 146 82 146 85 146 87 147 86 147 180 147 107 148 156 148 90 148 90 149 156 149 89 149 90 150 89 150 88 150 90 151 211 151 92 151 90 152 88 152 211 152 115 153 118 153 106 153 106 154 56 154 115 154 10 155 120 155 121 155 10 156 163 156 166 156 10 157 121 157 163 157 10 158 166 158 11 158 10 159 11 159 68 159 120 160 10 160 68 160 69 161 12 161 119 161 12 162 122 162 119 162 123 163 93 163 118 163 93 164 123 164 122 164 26 165 24 165 167 165 26 166 167 166 25 166 26 167 194 167 24 167 27 168 179 168 158 168 27 169 28 169 179 169 27 170 158 170 22 170 132 171 27 171 22 171 129 172 132 172 22 172 130 173 125 173 13 173 107 174 125 174 128 174 13 175 125 175 107 175 193 176 14 176 15 176 195 177 193 177 15 177 14 178 193 178 197 178 131 179 19 179 201 179 131 180 130 180 16 180 19 181 131 181 16 181 17 182 18 182 198 182 17 183 98 183 18 183 17 184 19 184 98 184 17 185 201 185 19 185 17 186 198 186 201 186 133 187 105 187 136 187 133 188 138 188 105 188 139 189 103 189 105 189 139 190 105 190 138 190 139 191 142 191 103 191 143 192 174 192 135 192 145 193 174 193 143 193 63 194 60 194 181 194 181 195 60 195 164 195 181 196 174 196 145 196 81 197 171 197 147 197 83 198 147 198 171 198 84 199 170 199 149 199 151 200 149 200 170 200 203 201 169 201 189 201 203 202 151 202 169 202 141 203 160 203 153 203 153 204 160 204 77 204 155 205 180 205 86 205 155 206 159 206 180 206 127 207 159 207 155 207 176 208 49 208 157 208 182 209 59 209 20 209 20 210 23 210 182 210 199 211 25 211 28 211 21 212 158 212 159 212 21 213 126 213 129 213 21 214 159 214 126 214 22 215 158 215 21 215 21 216 129 216 22 216 63 217 181 217 184 217 184 218 181 218 145 218 186 219 111 219 100 219 186 220 187 220 111 220 205 221 112 221 111 221 190 222 157 222 49 222 192 223 23 223 24 223 192 224 182 224 23 224 24 225 194 225 192 225 199 226 196 226 25 226 196 227 26 227 25 227 26 228 196 228 194 228 28 229 27 229 200 229 200 230 199 230 28 230 200 231 27 231 132 231 100 232 152 232 202 232 202 233 186 233 100 233 204 234 34 234 29 234 29 235 112 235 204 235 112 236 205 236 204 236 111 237 187 237 208 237 208 238 205 238 111 238 180 239 157 239 210 239 210 240 157 240 190 240 87 241 180 241 210 241 30 242 31 242 32 242 33 243 31 243 30 243 34 244 35 244 36 244 34 245 36 245 37 245 38 246 30 246 32 246 38 247 39 247 30 247 40 248 41 248 42 248 43 249 41 249 40 249 44 250 45 250 46 250 45 251 44 251 47 251 48 252 49 252 50 252 48 253 50 253 51 253 43 254 40 254 52 254 52 255 40 255 53 255 38 256 52 256 39 256 53 257 39 257 52 257 54 258 51 258 50 258 50 259 55 259 54 259 54 260 57 260 56 260 54 261 55 261 57 261 58 262 37 262 36 262 59 263 58 263 36 263 60 264 61 264 62 264 60 265 63 265 61 265 64 266 31 266 33 266 65 267 31 267 64 267 67 268 66 268 68 268 66 269 69 269 68 269 42 270 41 270 66 270 66 271 67 271 42 271 70 272 44 272 46 272 44 273 70 273 71 273 70 274 72 274 71 274 70 275 73 275 72 275 74 276 72 276 73 276 75 277 72 277 74 277 76 278 45 278 47 278 76 279 77 279 45 279 65 280 64 280 78 280 78 281 64 281 79 281 78 282 60 282 62 282 60 283 78 283 79 283 74 284 80 284 75 284 80 285 74 285 81 285 82 286 83 286 84 286 82 287 84 287 85 287 86 288 87 288 88 288 86 289 88 289 89 289 90 290 92 290 91 290 90 291 93 291 94 291 96 292 95 292 90 292 90 293 97 293 98 293 99 294 96 294 90 294 100 295 90 295 101 295 90 296 103 296 102 296 90 297 104 297 101 297 90 298 105 298 103 298 90 299 91 299 106 299 108 300 107 300 90 300 90 301 98 301 108 301 90 302 102 302 109 302 110 303 105 303 90 303 90 304 100 304 111 304 109 305 104 305 90 305 90 306 112 306 113 306 90 307 113 307 97 307 94 308 114 308 90 308 112 309 90 309 111 309 106 310 93 310 90 310 90 311 114 311 99 311 90 312 95 312 110 312 115 313 116 313 117 313 115 314 117 314 118 314 115 315 56 315 57 315 57 316 116 316 115 316 119 317 68 317 69 317 119 318 120 318 68 318 121 319 120 319 119 319 119 320 122 320 121 320 123 321 118 321 117 321 124 322 123 322 117 322 123 323 121 323 122 323 123 324 124 324 121 324 125 325 126 325 127 325 125 326 127 326 128 326 129 327 125 327 130 327 125 328 129 328 126 328 131 329 129 329 130 329 132 330 129 330 131 330 134 331 133 331 135 331 136 332 135 332 133 332 133 333 134 333 137 333 137 334 138 334 133 334 139 335 140 335 141 335 139 336 141 336 142 336 139 337 138 337 137 337 140 338 139 338 137 338 143 339 135 339 136 339 136 340 144 340 143 340 146 341 145 341 143 341 143 342 144 342 146 342 147 343 80 343 81 343 148 344 80 344 147 344 147 345 83 345 82 345 147 346 82 346 148 346 85 347 84 347 149 347 149 348 150 348 85 348 149 349 151 349 152 349 152 350 150 350 149 350 153 351 142 351 141 351 153 352 154 352 142 352 153 353 77 353 76 353 153 354 76 354 154 354 128 355 127 355 155 355 155 356 156 356 128 356 155 357 86 357 89 357 155 358 89 358 156 358 159 359 158 359 157 359 161 360 160 360 157 360 163 361 162 361 157 361 157 362 164 362 165 362 157 363 166 363 163 363 157 364 167 364 168 364 157 365 169 365 170 365 170 366 171 366 157 366 157 367 172 367 166 367 173 368 157 368 168 368 175 369 174 369 157 369 157 370 162 370 176 370 157 371 173 371 177 371 157 372 171 372 178 372 177 373 169 373 157 373 178 374 161 374 157 374 179 375 167 375 157 375 157 376 158 376 179 376 157 377 180 377 159 377 165 378 172 378 157 378 157 379 160 379 175 379 174 380 181 380 157 380 157 381 181 381 164 381 182 382 58 382 59 382 183 383 58 383 182 383 184 384 61 384 63 384 185 385 61 385 184 385 184 386 145 386 146 386 184 387 146 387 185 387 186 388 188 388 187 388 189 389 188 389 186 389 49 390 48 390 190 390 190 391 48 391 191 391 194 392 193 392 192 392 192 393 193 393 195 393 183 394 182 394 192 394 192 395 195 395 183 395 196 396 193 396 194 396 196 397 197 397 193 397 196 398 198 398 197 398 196 399 199 399 198 399 132 400 131 400 200 400 200 401 131 401 201 401 200 402 198 402 199 402 198 403 200 403 201 403 152 404 151 404 202 404 151 405 203 405 202 405 186 406 202 406 189 406 202 407 203 407 189 407 204 408 205 408 206 408 207 409 204 409 206 409 35 410 34 410 204 410 204 411 207 411 35 411 208 412 187 412 188 412 208 413 188 413 209 413 208 414 206 414 205 414 208 415 209 415 206 415 88 416 87 416 210 416 210 417 211 417 88 417 210 418 190 418 191 418 191 419 211 419 210 419

+
+
+
+
+ + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl new file mode 100644 index 0000000..7eccbbb Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/collision/robotiq_arg2f_base_link.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_base_link.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_base_link.dae new file mode 100644 index 0000000..df98eae --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_base_link.dae @@ -0,0 +1,346 @@ + + + 2016-07-17T20:30:09.867788 + 2016-07-17T20:30:09.867797 + Z_UP + + + + + + + + 0.007843 0.007843 0.007843 1 + + + 0.08 0.08 0.08 1 + + + 0.08 0.08 0.08 1 + + + 0.312500 + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.000000 + + + + + + 0 + + + + + + + + + + 0.0 0.0 0.0 1.0 + + + 0.0 0.0 0.0 1.0 + + + 0.7 0.7 0.7 1.0 + + + 1 1 1 1.0 + + + 0.0 + + + 0.0 0.0 0.0 1.0 + + + 0.0 + + + 0.0 0.0 0.0 1.0 + + + 1.0 + + + + + + 0 + + + + + + + + + + 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 0.5 0.8660254 4.580709e-16 0.5 0.8660254 4.580709e-16 0.5 0.8660254 4.580709e-16 1 3.783721e-16 4.996004e-16 1 3.783721e-16 4.996004e-16 1 3.783721e-16 4.996004e-16 0.5 -0.8660254 4.152949e-17 0.5 -0.8660254 4.152949e-17 0.5 -0.8660254 4.152949e-17 -0.5 -0.8660254 -4.580709e-16 -0.5 -0.8660254 -4.580709e-16 -0.5 -0.8660254 -4.580709e-16 -1 -2.793499e-18 -4.996004e-16 -1 -2.793499e-18 -4.996004e-16 -1 -2.793499e-18 -4.996004e-16 -0.5 0.8660254 -4.152949e-17 -0.5 0.8660254 -4.152949e-17 -0.5 0.8660254 -4.152949e-17 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 + + + + + + + + + + -5 -11.5 88.5 -5.008555 -11.36947 88.5 -5.138293 -11.34806 88.42783 -5.261394 -11.36976 88.35566 -5.295231 -11.24348 88.35566 -5.425467 -11.01791 88.35566 -5.625 -10.85048 88.35566 -5.598258 -11.02122 88.28349 -5.75 -11.06699 88.21132 -5.616978 -11.17861 88.21132 -5.458734 -11.1875 88.28349 -6.043412 -11.2538 88.06699 -6.125 -11.28349 88.06699 -6.066013 -11.34696 88.01887 -6.028941 -11.33587 88.01887 -5.871742 -11.14762 88.13916 -5.913176 -11.0076 88.21132 -6 -11.125 88.13916 -5.956588 -11.2538 88.06699 -6.086824 -11.0076 88.21132 -5.786237 -10.91269 88.28349 -5.869764 -10.76139 88.35566 -6.128258 -11.14762 88.13916 -6.25 -11.06699 88.21132 -6 -10.875 88.28349 -6.130236 -10.76139 88.35566 -6.241045 -11.21273 88.13916 -6.383022 -11.17861 88.21132 -6.191511 -11.3393 88.06699 -6.213763 -10.91269 88.28349 -6.375 -10.85048 88.35566 -6.234923 -11.41449 88.06699 -6.32476 -11.3125 88.13916 -6.469846 -11.32899 88.21132 -6.401742 -11.02122 88.28349 -6.574533 -11.01791 88.35566 -6.369303 -11.43488 88.13916 -6.5 -11.5 88.21132 -6.25 -11.5 88.06699 -6.541266 -11.1875 88.28349 -6.704769 -11.24348 88.35566 -6.369303 -11.56512 88.13916 -6.234923 -11.58551 88.06699 -6.469846 -11.67101 88.21132 -6.75 -11.5 88.35566 -6.615505 -11.39147 88.28349 -6.32476 -11.6875 88.13916 -6.191511 -11.6607 88.06699 -6.383022 -11.82139 88.21132 -6.125 -11.71651 88.06699 -6.043412 -11.7462 88.06699 -6.066013 -11.65304 88.01887 -6.615505 -11.60853 88.28349 -6.704769 -11.75652 88.35566 -6.25 -11.93301 88.21132 -6.241045 -11.78727 88.13916 -6.028941 -11.66413 88.01887 -6.574533 -11.98209 88.35566 -6.541266 -11.8125 88.28349 -5.956588 -11.7462 88.06699 -5.990309 -11.66638 88.01887 -6 -11.625 87.99482 -5.978294 -11.6231 87.99482 -6.128258 -11.85238 88.13916 -6.086824 -11.9924 88.21132 -5.875 -11.71651 88.06699 -5.957247 -11.61746 87.99482 -6.401742 -11.97878 88.28349 -6.375 -12.14952 88.35566 -5.9375 -11.60825 87.99482 -6 -11.875 88.13916 -5.913176 -11.9924 88.21132 -5.808489 -11.6607 88.06699 -5.919652 -11.59576 87.99482 -6.213763 -12.08731 88.28349 -6.130236 -12.23861 88.35566 -5.904244 -11.58035 87.99482 -5.871742 -11.85238 88.13916 -5.75 -11.93301 88.21132 -5.765077 -11.58551 88.06699 -5.891747 -11.5625 87.99482 -6 -12.125 88.28349 -5.869764 -12.23861 88.35566 -5.882538 -11.54275 87.99482 -5.758955 -11.78727 88.13916 -5.616978 -11.82139 88.21132 -5.786237 -12.08731 88.28349 -5.625 -12.14952 88.35566 -5.67524 -11.6875 88.13916 -5.530154 -11.67101 88.21132 -5.753798 -11.54341 88.06699 -5.876899 -11.52171 87.99482 -6 -11.5 87.92265 -5.598258 -11.97878 88.28349 -5.425467 -11.98209 88.35566 -5.458734 -11.8125 88.28349 -5.295231 -11.75652 88.35566 -5.261394 -11.63024 88.35566 -5.008555 -11.63053 88.5 -5.138293 -11.65194 88.42783 -5.876899 -11.47829 87.99482 -5.882538 -11.45725 87.99482 -5.93963 -11.48382 87.95873 -5.941269 -11.47862 87.95873 -5.943356 -11.47359 87.95873 -5.891747 -11.4375 87.99482 -5.945873 -11.46875 87.95873 -5.904244 -11.41965 87.99482 -5.948803 -11.46415 87.95873 -5.952122 -11.45983 87.95873 -5.955806 -11.45581 87.95873 -5.919652 -11.40424 87.99482 -5.9375 -11.39175 87.99482 -5.626427 -11.46732 88.13916 -5.753798 -11.45659 88.06699 -5.765077 -11.41449 88.06699 -5.67524 -11.3125 88.13916 -5.530154 -11.32899 88.21132 -6.041667 -11.42783 87.97076 -5.034074 -11.24118 88.5 -5.119038 -11.17936 88.46392 -5.07612 -11.11732 88.5 -5.133975 -11 88.5 -6.151536 -11.35703 88.04293 -6.044194 -11.45581 87.95873 -6.17406 -11.38552 88.04293 -6.128573 -11.44747 88.00284 -6.194444 -11.5 88.03491 -6.166667 -11.5 88.01887 -6.142821 -11.52949 88.00685 -6.125 -11.5 87.99482 -5.292893 -10.79289 88.5 -5.391239 -10.70665 88.5 -6.132309 -11.57639 88.01086 -6.17406 -11.61448 88.04293 -6.151536 -11.64297 88.04293 -5.955806 -11.54419 87.95873 -5.952122 -11.54017 87.95873 -5.948803 -11.53585 87.95873 -5.945873 -11.53125 87.95873 -5.943356 -11.52641 87.95873 -5.5 -10.63397 88.5 -5.617317 -10.57612 88.5 -5.941269 -11.52138 87.95873 -5.93963 -11.51618 87.95873 -5.626427 -11.53268 88.13916 -5.133975 -12 88.5 -5.07612 -11.88268 88.5 -5.119038 -11.82064 88.46392 -5.034074 -11.75882 88.5 -5.988041 -11.47113 87.94069 -5.957247 -11.38254 87.99482 -5.978294 -11.3769 87.99482 -6 -11.375 87.99482 -5.990482 -11.42771 87.96475 -6 -11.4375 87.95873 -5.741181 -10.53407 88.5 -5.869474 -10.50856 88.5 -6 -10.5 88.5 -5.269291 -11.07813 88.40979 -5.206647 -10.89124 88.5 -6.072169 -11.54167 87.97076 -6.088388 -11.58839 87.99482 -6.044194 -11.54419 87.95873 -6.130526 -10.50856 88.5 -6.069444 -11.62028 88.00284 -6.258819 -10.53407 88.5 -6.382683 -10.57612 88.5 -6.011959 -11.52887 87.94069 -6.035877 -11.58661 87.97678 -6 -11.54167 87.94671 -5.292893 -12.20711 88.5 -5.206647 -12.10876 88.5 -5.269291 -11.92188 88.40979 -6.008681 -11.48701 87.93167 -6.028871 -11.48804 87.94069 -6.5 -10.63397 88.5 -6.608761 -10.70665 88.5 -6.072293 -11.49048 87.96475 -6.0625 -11.5 87.95873 -6.045974 -11.50914 87.94971 -6.707107 -10.79289 88.5 -6.793353 -10.89124 88.5 -6.866025 -11 88.5 -6.92388 -11.11732 88.5 -6.965926 -11.24118 88.5 -6.991445 -11.36947 88.5 -7 -11.5 88.5 -6.991445 -11.63053 88.5 -6.965926 -11.75882 88.5 -6.92388 -11.88268 88.5 -6.866025 -12 88.5 -6.793353 -12.10876 88.5 -6.707107 -12.20711 88.5 -6.608761 -12.29335 88.5 -6.5 -12.36603 88.5 -6.382683 -12.42388 88.5 -6.258819 -12.46593 88.5 -6.130526 -12.49144 88.5 -6 -12.5 88.5 -5.869474 -12.49144 88.5 -5.741181 -12.46593 88.5 -5.617317 -12.42388 88.5 -5.5 -12.36603 88.5 -5.391239 -12.29335 88.5 -5.808489 -11.3393 88.06699 -5.875 -11.28349 88.06699 -5.758955 -11.21273 88.13916 -5.990309 -11.33362 88.01887 -6.311787 -14.20074 89.83346 -6.441291 -14.14451 89.89132 -6.44748 -14.1816 89.83346 -6.314469 -14.22397 89.76854 -6.226438 -14.2327 89.76854 -4.068225 -9.640853 89.89132 -4.027467 -9.684155 89.89132 -4.041134 -9.61478 89.83346 -4.158689 -9.499803 89.83346 -4.024283 -9.598563 89.76854 -4.14285 -9.482597 89.76854 -6.500967 -14.08312 89.93905 -6.697233 -14.0372 89.93905 -6.510453 -14.13204 89.89132 -6.68149 -13.97991 89.97414 -4.015853 -9.863686 89.97414 -3.970457 -9.920343 89.97414 -3.923571 -9.883851 89.93905 -6.105029 -14.24005 89.76854 -6.105333 -14.24798 89.7 -3.970016 -9.825885 89.93905 -6.224507 -14.20939 89.83346 -4.064124 -9.717901 89.93905 -4.017461 -9.956928 89.99346 -4.066606 -9.995179 90 -3.945135 -10.05464 89.99346 -6.665707 -13.92247 89.99346 -6.601439 -13.87503 90 -6.795514 -13.81725 90 -6.849192 -13.8644 89.99346 -6.869325 -13.92046 89.97414 -4.315789 -9.336126 89.76854 -4.170354 -9.446979 89.7 -4.33288 -9.312945 89.7 -6.43309 -14.09537 89.93905 -4.104125 -9.675403 89.93905 -6.307475 -14.16339 89.89132 -4.184155 -9.527467 89.89132 -6 -14.24206 89.76854 -5.894667 -14.24798 89.7 -4.061806 -9.901583 89.99346 -4.197476 -9.84066 90 -6.489655 -14.0248 89.97414 -6.104133 -14.21668 89.83346 -4.107836 -9.75814 89.97414 -6.221402 -14.17192 89.89132 -4.330153 -9.354581 89.83346 -6.423311 -14.03676 89.97414 -6.301761 -14.11389 89.93905 -4.146934 -9.716603 89.97414 -4.217901 -9.564124 89.93905 -5.894971 -14.24005 89.76854 -4.151658 -9.798481 89.99346 -6 -14.21868 89.83346 -4.500233 -9.204435 89.76854 -4.505189 -9.191745 89.7 -6.478315 -13.96632 89.99346 -6.403257 -13.91659 90 -6.102693 -14.17911 89.89132 -4.353248 -9.384253 89.89132 -6.217287 -14.12227 89.93905 -4.18985 -9.757906 89.99346 -4.34066 -9.697476 90 -4.25814 -9.607836 89.97414 -6.413507 -13.97801 89.99346 -5.773562 -14.2327 89.76854 -5.684621 -14.23186 89.7 -4.513024 -9.224014 89.83346 -6.294947 -14.05487 89.97414 -4.383851 -9.423571 89.93905 -5.895867 -14.21668 89.83346 -4.298481 -9.651658 89.99346 -4.495179 -9.566606 90 -6 -14.18108 89.89132 -4.690061 -9.091063 89.76854 -4.68627 -9.084091 89.7 -4.875061 -8.990615 89.7 -6.100784 -14.12932 89.93905 -4.533589 -9.255491 89.89132 -5.685531 -14.22397 89.76854 -4.420343 -9.470457 89.97414 -6.212381 -14.06306 89.97414 -4.701234 -9.111608 89.83346 -6.288116 -13.9957 89.99346 -6.202319 -13.94163 90 -4.560841 -9.297203 89.93905 -5.775493 -14.20939 89.83346 -4.878307 -8.997856 89.76854 -5.070454 -8.911865 89.7 -5.897307 -14.17911 89.89132 -4.456928 -9.517461 89.99346 -4.659977 -9.448942 90 -6 -14.13125 89.93905 -4.719196 -9.14464 89.89132 -6.098508 -14.06995 89.97414 -4.593337 -9.346942 89.97414 -6.207462 -14.0037 89.99346 -4.887874 -9.019196 89.83346 -5.688213 -14.20074 89.83346 -4.742998 -9.188412 89.93905 -5.548671 -14.20467 89.76854 -5.476424 -14.1997 89.7 -5.073136 -8.919333 89.76854 -5.778598 -14.17192 89.89132 -5.271301 -8.848303 89.7 -4.625915 -9.396806 89.99346 -5.899216 -14.12932 89.93905 -4.903255 -9.053506 89.89132 -5.477935 -14.19191 89.76854 -4.771381 -9.240607 89.97414 -6 -14.07184 89.97414 -5.081041 -8.941343 89.83346 -6.096227 -14.01043 89.99346 -6 -13.95 90 -4.923637 -9.098972 89.93905 -5.692525 -14.16339 89.89132 -5.273404 -8.855955 89.76854 -5.476424 -8.800302 89.7 -5.55252 -14.1816 89.83346 -4.799836 -9.292934 89.99346 -4.833929 -9.345289 90 -5.782713 -14.12227 89.93905 -5.09375 -8.97673 89.89132 -5.901492 -14.06995 89.97414 -4.947941 -9.153187 89.97414 -5.482388 -14.16895 89.83346 -6 -14.01228 89.99346 -5.279601 -8.878505 89.83346 -5.326863 -14.15816 89.76854 -5.271301 -14.1517 89.7 -5.110592 -9.023622 89.93905 -5.698239 -14.11389 89.93905 -5.477935 -8.808092 89.76854 -4.972306 -9.207539 89.99346 -5.015846 -9.256355 90 -5.558709 -14.14451 89.89132 -5.289564 -8.914761 89.89132 -5.787619 -14.06306 89.97414 -5.903773 -14.01043 89.99346 -5.797681 -13.94163 90 -5.548671 -8.795334 89.76854 -5.684621 -8.768144 89.7 -5.130675 -9.079538 89.97414 -5.489547 -14.13204 89.89132 -5.332604 -14.13549 89.83346 -5.482388 -8.831051 89.83346 -5.705053 -14.05487 89.97414 -5.302767 -8.962805 89.93905 -5.56691 -14.09537 89.93905 -5.792538 -14.0037 89.99346 -5.55252 -8.818401 89.83346 -5.685531 -8.776027 89.76854 -5.109653 -14.09349 89.76854 -5.150808 -9.135596 89.99346 -5.204486 -9.182748 90 -5.070454 -14.08814 89.7 -5.489547 -8.867963 89.89132 -5.499033 -14.08312 89.93905 -5.773562 -8.767301 89.76854 -5.894667 -8.752018 89.7 -5.341834 -14.09904 89.89132 -5.711884 -13.9957 89.99346 -5.596743 -13.91659 90 -5.31851 -9.020094 89.97414 -5.576689 -14.03676 89.97414 -5.558709 -8.855488 89.89132 -5.117247 -14.07137 89.83346 -5.688213 -8.799259 89.83346 -5.499033 -8.916877 89.93905 -5.510345 -14.0248 89.97414 -5.354065 -14.05074 89.93905 -5.894971 -8.759948 89.76854 -5.586493 -13.97801 89.99346 -5.775493 -8.790607 89.83346 -5.334293 -9.077529 89.99346 -5.398561 -9.124969 90 -4.898525 -14.01111 89.76854 -4.875061 -14.00938 89.7 -5.129455 -14.03581 89.89132 -5.56691 -8.904633 89.93905 -5.692525 -8.836611 89.89132 -5.521685 -13.96632 89.99346 -5.398561 -13.87503 90 -6 -8.757935 89.76854 -5.368651 -13.99314 89.97414 -6.105333 -8.752018 89.7 -4.907919 -13.98969 89.83346 -5.510345 -8.975203 89.97414 -5.895867 -8.783317 89.83346 -5.145633 -13.98868 89.93905 -5.778598 -8.828079 89.89132 -5.383273 -13.9354 89.99346 -5.204486 -13.81725 90 -5.576689 -8.963237 89.97414 -4.694921 -13.91157 89.76854 -4.68627 -13.91591 89.7 -5.698239 -8.886107 89.93905 -6.105029 -8.759948 89.76854 -4.923023 -13.95526 89.89132 -6 -8.781322 89.83346 -5.164925 -13.93249 89.97414 -5.521685 -9.033677 89.99346 -5.596743 -9.083415 90 -4.706052 -13.89101 89.83346 -5.897307 -8.820889 89.89132 -4.943038 -13.90963 89.93905 -5.782713 -8.877734 89.93905 -5.586493 -9.021988 89.99346 -4.509503 -13.80159 89.76854 -4.505189 -13.80825 89.7 -4.33288 -13.68706 89.7 -6.226438 -8.767301 89.76854 -6.315379 -8.768144 89.7 -5.184265 -13.87615 89.99346 -5.015846 -13.74364 90 -5.705053 -8.945129 89.97414 -4.723948 -13.85794 89.89132 -6.104133 -8.783317 89.83346 -4.966904 -13.85522 89.97414 -6 -8.818922 89.89132 -4.522215 -13.78196 89.83346 -5.899216 -8.870677 89.93905 -4.747662 -13.81412 89.93905 -4.337691 -13.68074 89.76854 -6.314469 -8.776027 89.76854 -5.787619 -8.936944 89.97414 -4.99083 -13.80068 89.99346 -4.833929 -13.65471 90 -5.711884 -9.004299 89.99346 -4.542653 -13.7504 89.89132 -5.797681 -9.058368 90 -4.775939 -13.76187 89.97414 -6.224507 -8.790607 89.83346 -4.351868 -13.66215 89.83346 -6.102693 -8.820889 89.89132 -6 -8.868747 89.93905 -4.569736 -13.70858 89.93905 -5.901492 -8.930047 89.97414 -4.175634 -13.5471 89.76854 -5.792538 -8.996304 89.99346 -4.170354 -13.55302 89.7 -4.018566 -13.40694 89.7 -4.804289 -13.70948 89.99346 -6.311787 -8.799259 89.83346 -4.374662 -13.63224 89.89132 -6.451329 -8.795334 89.76854 -6.523576 -8.800302 89.7 -4.602031 -13.65871 89.97414 -6.221402 -8.828079 89.89132 -4.191193 -13.52964 89.83346 -6.100784 -8.870677 89.93905 -6.522065 -8.808092 89.76854 -4.404867 -13.59262 89.93905 -6 -8.92816 89.97414 -5.903773 -8.989567 89.99346 -4.024283 -13.40144 89.76854 -6 -9.05 90 -4.634408 -13.60872 89.99346 -4.659977 -13.55106 90 -6.307475 -8.836611 89.89132 -6.44748 -8.818401 89.83346 -3.982597 -13.35715 89.76854 -3.878405 -13.24967 89.7 -4.21621 -13.50157 89.89132 -6.217287 -8.877734 89.93905 -6.098508 -8.930047 89.97414 -4.440885 -13.54537 89.97414 -6.517612 -8.831051 89.83346 -4.041134 -13.38522 89.83346 -6 -8.987723 89.99346 -6.673137 -8.841842 89.76854 -3.999803 -13.34131 89.83346 -6.728699 -8.848303 89.7 -4.249359 -13.46437 89.93905 -6.301761 -8.886107 89.93905 -6.441291 -8.855488 89.89132 -3.884527 -13.24462 89.76854 -4.476994 -13.498 89.99346 -4.495179 -13.43339 90 -6.212381 -8.936944 89.97414 -6.096227 -8.989567 89.99346 -6.202319 -9.058368 90 -4.068225 -13.35915 89.89132 -6.510453 -8.867963 89.89132 -6.667396 -8.864513 89.83346 -3.836126 -13.18421 89.76854 -3.750694 -13.08213 89.7 -6.294947 -8.945129 89.97414 -4.027467 -13.31584 89.89132 -4.288889 -13.42002 89.97414 -6.43309 -8.904633 89.93905 -6.207462 -8.996304 89.99346 -3.902569 -13.22974 89.83346 -6.890347 -8.906508 89.76854 -6.929546 -8.911865 89.7 -4.104125 -13.3246 89.93905 -3.757185 -13.07756 89.76854 -6.500967 -8.916877 89.93905 -6.658166 -8.900962 89.89132 -3.854581 -13.16985 89.83346 -4.328518 -13.37555 89.99346 -4.34066 -13.30252 90 -6.288116 -9.004299 89.99346 -6.403257 -9.083415 90 -6.423311 -8.963237 89.97414 -4.064124 -13.2821 89.93905 -6.882753 -8.928627 89.83346 -3.931577 -13.20582 89.89132 -6.489655 -8.975203 89.97414 -3.704435 -12.99977 89.76854 -3.636184 -12.9053 89.7 -4.146934 -13.2834 89.97414 -6.645935 -8.949262 89.93905 -6.413507 -9.021988 89.99346 -3.776313 -13.06411 89.83346 -7.101475 -8.98889 89.76854 -7.124939 -8.990615 89.7 -3.884253 -13.14675 89.89132 -6.870545 -8.96419 89.89132 -4.107836 -13.24186 89.97414 -3.970016 -13.17412 89.93905 -6.478315 -9.033677 89.99346 -6.601439 -9.124969 90 -6.631349 -9.006858 89.97414 -3.643005 -12.90125 89.76854 -7.092081 -9.010307 89.83346 -3.724014 -12.98698 89.83346 -4.18985 -13.24209 89.99346 -4.197476 -13.15934 90 -6.854367 -9.011315 89.93905 -6.616727 -9.064598 89.99346 -6.795514 -9.182748 90 -3.807067 -13.04247 89.89132 -3.923571 -13.11615 89.93905 -7.305079 -9.088426 89.76854 -7.31373 -9.084091 89.7 -4.151658 -13.20152 89.99346 -7.076977 -9.04474 89.89132 -3.588426 -12.80508 89.76854 -6.835075 -9.067509 89.97414 -3.535545 -12.72023 89.7 -4.015853 -13.13631 89.97414 -7.293948 -9.108994 89.83346 -3.663107 -12.8893 89.83346 -3.755491 -12.96641 89.89132 -7.056962 -9.090368 89.93905 -3.847821 -13.01381 89.93905 -7.490497 -9.198406 89.76854 -7.494811 -9.191745 89.7 -7.66712 -9.312945 89.7 -3.970457 -13.07966 89.97414 -6.815735 -9.123845 89.99346 -6.984154 -9.256355 90 -3.542656 -12.71671 89.76854 -7.276052 -9.142062 89.89132 -3.608994 -12.79395 89.83346 -7.033096 -9.144778 89.97414 -4.061806 -13.09842 89.99346 -4.066606 -13.00482 90 -8.742065 -11.5 89.76854 -8.741931 -11.28949 89.7 -8.75 -11.5 89.7 -7.477785 -9.218035 89.83346 -3.695427 -12.87008 89.89132 -3.797203 -12.93916 89.93905 -7.252338 -9.185882 89.93905 -4.017461 -13.04307 89.99346 -7.662309 -9.319256 89.76854 -7.829646 -9.446979 89.7 -3.896417 -12.97963 89.97414 -7.00917 -9.199324 89.99346 -7.166071 -9.345289 90 -3.48889 -12.60147 89.76854 -3.449368 -12.528 89.7 -7.457347 -9.249596 89.89132 -3.563614 -12.70633 89.83346 -7.224061 -9.238134 89.97414 -3.642062 -12.77605 89.89132 -7.648132 -9.337855 89.83346 -8.45 -11.5 90 -8.441632 -11.29768 90 -8.512276 -11.5 89.99347 -3.738255 -12.84462 89.93905 -8.734019 -11.7099 89.76854 -7.430264 -9.291417 89.93905 -8.741931 -11.71051 89.7 -8.717771 -11.91979 89.7 -3.456728 -12.52503 89.76854 -8.710701 -11.70811 89.83346 -8.718678 -11.5 89.83346 -7.824366 -9.452903 89.76854 -7.981434 -9.593061 89.7 -3.846942 -12.90666 89.97414 -7.195711 -9.290519 89.99346 -3.945135 -12.94536 89.99346 -3.948942 -12.84002 90 -8.709929 -11.91857 89.76854 -7.625338 -9.367758 89.89132 -3.510307 -12.59208 89.83346 -8.673211 -11.70523 89.89132 -8.681078 -11.5 89.89132 -3.59731 -12.68965 89.89132 -7.397969 -9.341286 89.97414 -8.686817 -11.915 89.83346 -3.685882 -12.75234 89.93905 -7.808807 -9.470362 89.83346 -3.789325 -12.81426 89.97414 -8.623533 -11.70142 89.93905 -8.631254 -11.5 89.93905 -7.595133 -9.407383 89.93905 -8.669936 -12.12479 89.76854 -3.896806 -12.87409 89.99346 -7.975717 -9.598563 89.76854 -8.677662 -12.1266 89.7 -8.62184 -12.32973 89.7 -3.478419 -12.51629 89.83346 -8.649657 -11.90926 89.89132 -7.365592 -9.391282 89.99346 -7.340023 -9.448942 90 -3.406508 -12.39035 89.76854 -8.564294 -11.69687 89.97414 -8.57184 -11.5 89.97414 -8.017403 -9.64285 89.76854 -8.121595 -9.750333 89.7 -3.37816 -12.32973 89.7 -8.647165 -12.11946 89.83346 -3.54474 -12.57698 89.89132 -7.78379 -9.498432 89.89132 -7.559115 -9.454634 89.97414 -8.600416 -11.90166 89.93905 -3.641961 -12.66754 89.93905 -3.385725 -12.32734 89.76854 -8.614275 -12.32734 89.76854 -7.958866 -9.61478 89.83346 -3.738134 -12.72406 89.97414 -8.504905 -11.69231 89.99346 -8.441632 -11.70232 90 -3.840523 -12.78382 89.99346 -3.845289 -12.66607 90 -8.000197 -9.658689 89.83346 -8.610554 -12.11089 89.89132 -8.593492 -12.39035 89.76854 -7.750641 -9.535629 89.93905 -3.513293 -12.50223 89.89132 -3.428627 -12.38275 89.83346 -8.550632 -12.528 89.7 -8.115473 -9.755382 89.76854 -8.541699 -11.89259 89.97414 -7.523006 -9.502004 89.99346 -7.504821 -9.566606 90 -8.591978 -12.32028 89.83346 -3.590368 -12.55696 89.93905 -8.562039 -12.09954 89.93905 -7.931775 -9.640853 89.89132 -3.695206 -12.64118 89.97414 -8.163874 -9.815789 89.76854 -3.408022 -12.32028 89.83346 -8.249306 -9.917874 89.7 -8.571373 -12.38275 89.83346 -3.790519 -12.69571 89.99346 -7.972533 -9.684155 89.89132 -8.543272 -12.52503 89.76854 -3.341842 -12.17314 89.76854 -3.322338 -12.1266 89.7 -7.711111 -9.579985 89.97414 -8.482834 -11.8835 89.99346 -8.416585 -11.90326 90 -8.55613 -12.30894 89.89132 -3.559506 -12.48361 89.93905 -8.097431 -9.770261 89.83346 -8.51111 -12.60147 89.76854 -7.895875 -9.675403 89.93905 -3.46419 -12.37054 89.89132 -8.464455 -12.72023 89.7 -3.748584 -12.61475 89.99346 -8.504189 -12.086 89.97414 -3.756355 -12.48415 90 -3.644778 -12.5331 89.97414 -8.242815 -9.922439 89.76854 -8.53581 -12.37054 89.89132 -8.145419 -9.830153 89.83346 -3.44387 -12.30894 89.89132 -3.364513 -12.1674 89.83346 -8.521581 -12.51629 89.83346 -7.671482 -9.624452 89.99346 -7.65934 -9.697476 90 -7.935876 -9.717901 89.93905 -8.508628 -12.2939 89.93905 -3.614612 -12.4614 89.97414 -8.068423 -9.794184 89.89132 -8.457344 -12.71671 89.76854 -3.511315 -12.35437 89.93905 -8.295565 -10.00023 89.76854 -8.489693 -12.59208 89.83346 -8.363816 -10.0947 89.7 -3.699324 -12.50917 89.99346 -7.853066 -9.716603 89.97414 -8.446192 -12.07243 89.99346 -3.295334 -11.95133 89.76854 -3.282229 -11.91979 89.7 -8.375031 -12.10144 90 -8.488685 -12.35437 89.93905 -8.223687 -9.935894 89.83346 -8.486707 -12.50223 89.89132 -3.491372 -12.2939 89.93905 -8.115747 -9.853248 89.89132 -3.400962 -12.15817 89.89132 -7.892164 -9.75814 89.97414 -3.669857 -12.43913 89.99346 -8.411574 -12.80508 89.76854 -8.363816 -12.9053 89.7 -3.682748 -12.29551 90 -8.029984 -9.825885 89.93905 -8.451983 -12.27598 89.97414 -3.567509 -12.33508 89.97414 -8.436386 -12.70633 89.83346 -8.356995 -10.09875 89.76854 -3.318401 -11.94748 89.83346 -8.275986 -10.01302 89.83346 -3.548017 -12.27598 89.97414 -8.45526 -12.57698 89.89132 -7.81015 -9.757906 89.99346 -8.432491 -12.33508 89.97414 -7.802524 -9.84066 90 -8.192933 -9.957526 89.89132 -8.440494 -12.48361 89.93905 -3.449262 -12.14593 89.93905 -3.623845 -12.31573 89.99346 -8.076429 -9.883851 89.93905 -8.356995 -12.90125 89.76854 -7.848342 -9.798481 89.99346 -8.391006 -12.79395 89.83346 -3.267301 -11.72644 89.76854 -3.258069 -11.71051 89.7 -8.411574 -10.19492 89.76854 -8.464455 -10.27977 89.7 -3.355488 -11.94129 89.89132 -8.395195 -12.25801 89.99346 -8.317252 -12.29551 90 -8.40269 -12.68965 89.89132 -7.984147 -9.863686 89.97414 -3.604805 -12.25801 89.99346 -3.624969 -12.10144 90 -8.409632 -12.55696 89.93905 -3.506858 -12.13135 89.97414 -8.336893 -10.1107 89.83346 -3.290607 -11.72451 89.83346 -8.376155 -12.31573 89.99346 -8.244509 -10.03359 89.89132 -8.152179 -9.986191 89.93905 -8.295565 -12.99977 89.76854 -8.249306 -13.08213 89.7 -3.404633 -11.93309 89.93905 -8.029543 -9.920343 89.97414 -8.385388 -12.4614 89.97414 -3.564598 -12.11673 89.99346 -8.336893 -12.8893 89.83346 -3.583415 -11.90326 90 -8.457344 -10.28329 89.76854 -8.391006 -10.20605 89.83346 -8.357938 -12.77605 89.89132 -3.257935 -11.5 89.76854 -3.25 -11.5 89.7 -7.938194 -9.901583 89.99346 -7.933394 -9.995179 90 -8.358039 -12.66754 89.93905 -3.328079 -11.7214 89.89132 -8.304573 -10.12992 89.89132 -3.463237 -11.92331 89.97414 -8.355222 -12.5331 89.97414 -8.202797 -10.06084 89.93905 -8.242815 -13.07756 89.76854 -3.281322 -11.5 89.83346 -7.982539 -9.956928 89.99346 -8.330143 -12.43913 89.99346 -8.243645 -12.48415 90 -3.377734 -11.71729 89.93905 -8.275986 -12.98698 89.83346 -8.103583 -10.02037 89.97414 -8.304573 -12.87008 89.89132 -8.51111 -10.39853 89.76854 -8.550632 -10.472 89.7 -3.265981 -11.2901 89.76854 -3.258069 -11.28949 89.7 -3.282229 -11.08021 89.7 -8.436386 -10.29367 89.83346 -8.314118 -12.75234 89.93905 -3.521988 -11.91351 89.99346 -3.558368 -11.70232 90 -8.357938 -10.22395 89.89132 -8.300676 -12.50917 89.99346 -3.318922 -11.5 89.89132 -8.304794 -12.64118 89.97414 -3.436944 -11.71238 89.97414 -8.261745 -10.15538 89.93905 -8.163874 -13.18421 89.76854 -8.121595 -13.24967 89.7 -3.289299 -11.29189 89.83346 -8.543272 -10.47497 89.76854 -8.153058 -10.09334 89.97414 -8.223687 -13.06411 89.83346 -8.054865 -10.05464 89.99346 -8.244509 -12.96641 89.89132 -3.368747 -11.5 89.93905 -8.051058 -10.15998 90 -8.489693 -10.40792 89.83346 -8.261745 -12.84462 89.93905 -3.290071 -11.08143 89.76854 -3.322338 -10.8734 89.7 -3.496304 -11.70746 89.99346 -3.55 -11.5 90 -8.115473 -13.24462 89.76854 -8.40269 -10.31035 89.89132 -3.326789 -11.29477 89.89132 -8.261866 -12.72406 89.97414 -8.314118 -10.24766 89.93905 -3.42816 -11.5 89.97414 -8.210675 -10.18574 89.97414 -8.251416 -12.61475 89.99346 -8.154711 -12.66607 90 -8.103194 -10.12591 89.99346 -8.145419 -13.16985 89.83346 -3.313183 -11.085 89.83346 -8.521581 -10.48371 89.83346 -8.192933 -13.04247 89.89132 -3.376467 -11.29858 89.93905 -8.593492 -10.60965 89.76854 -8.62184 -10.67027 89.7 -3.330064 -10.87521 89.76854 -8.202797 -12.93916 89.93905 -8.45526 -10.42302 89.89132 -8.210675 -12.81426 89.97414 -3.487723 -11.5 89.99346 -8.358039 -10.33246 89.93905 -8.097431 -13.22974 89.83346 -3.350343 -11.09074 89.89132 -3.435706 -11.30313 89.97414 -8.209481 -12.69571 89.99346 -8.614275 -10.67266 89.76854 -8.261866 -10.27594 89.97414 -8.017403 -13.35715 89.76854 -7.981434 -13.40694 89.7 -8.115747 -13.14675 89.89132 -3.352835 -10.88054 89.83346 -8.159477 -10.21618 89.99346 -8.154711 -10.33393 90 -3.399584 -11.09834 89.93905 -8.486707 -10.49777 89.89132 -8.152179 -13.01381 89.93905 -3.385725 -10.67266 89.76854 -3.37816 -10.67027 89.7 -8.571373 -10.61725 89.83346 -3.495095 -11.30769 89.99346 -3.558368 -11.29768 90 -7.975717 -13.40144 89.76854 -8.409632 -10.44304 89.93905 -3.389446 -10.88911 89.89132 -8.153058 -12.90666 89.97414 -8.159477 -12.78382 89.99346 -3.406508 -10.60965 89.76854 -8.304794 -10.35882 89.97414 -8.051058 -12.84002 90 -3.449368 -10.472 89.7 -8.068423 -13.20582 89.89132 -3.458301 -11.10741 89.97414 -8.591978 -10.67972 89.83346 -8.209481 -10.30429 89.99346 -8.000197 -13.34131 89.83346 -3.408022 -10.67972 89.83346 -8.658158 -10.82686 89.76854 -8.677662 -10.8734 89.7 -8.076429 -13.11615 89.93905 -8.440494 -10.51639 89.93905 -3.437961 -10.90046 89.93905 -8.103583 -12.97963 89.97414 -3.428627 -10.61725 89.83346 -7.958866 -13.38522 89.83346 -3.456728 -10.47497 89.76854 -8.53581 -10.62946 89.89132 -8.103194 -12.87409 89.99346 -8.251416 -10.38525 89.99346 -8.243645 -10.51585 90 -3.517166 -11.1165 89.99346 -3.583415 -11.09674 90 -3.44387 -10.69106 89.89132 -8.355222 -10.4669 89.97414 -7.85715 -13.5174 89.76854 -7.829646 -13.55302 89.7 -8.029984 -13.17412 89.93905 -3.48889 -10.39853 89.76854 -7.972533 -13.31584 89.89132 -3.535545 -10.27977 89.7 -8.55613 -10.69106 89.89132 -3.495811 -10.914 89.97414 -8.635487 -10.8326 89.83346 -8.054865 -12.94536 89.99346 -3.46419 -10.62946 89.89132 -8.385388 -10.5386 89.97414 -7.933394 -13.00482 90 -8.029543 -13.07966 89.97414 -3.478419 -10.48371 89.83346 -8.488685 -10.64563 89.93905 -7.931775 -13.35915 89.89132 -8.300676 -10.49083 89.99346 -3.491372 -10.7061 89.93905 -7.841311 -13.5002 89.83346 -8.704666 -11.04867 89.76854 -8.717771 -11.08021 89.7 -7.984147 -13.13631 89.97414 -3.542656 -10.28329 89.76854 -8.508628 -10.7061 89.93905 -7.935876 -13.2821 89.93905 -3.510307 -10.40792 89.83346 -3.553808 -10.92757 89.99346 -3.624969 -10.89856 90 -8.599038 -10.84183 89.89132 -7.982539 -13.04307 89.99346 -3.511315 -10.64563 89.93905 -8.330143 -10.56087 89.99346 -8.317252 -10.70449 90 -7.684211 -13.66387 89.76854 -3.513293 -10.49777 89.89132 -8.432491 -10.66492 89.97414 -7.66712 -13.68706 89.7 -7.895875 -13.3246 89.93905 -3.588426 -10.19492 89.76854 -3.636184 -10.0947 89.7 -8.681599 -11.05252 89.83346 -3.548017 -10.72402 89.97414 -7.815845 -13.47253 89.89132 -8.451983 -10.72402 89.97414 -7.938194 -13.09842 89.99346 -8.550738 -10.85407 89.93905 -7.802524 -13.15934 90 -3.563614 -10.29367 89.83346 -7.892164 -13.24186 89.97414 -8.376155 -10.68427 89.99346 -3.54474 -10.42302 89.89132 -3.567509 -10.66492 89.97414 -7.669847 -13.64542 89.83346 -8.732699 -11.27356 89.76854 -7.853066 -13.2834 89.97414 -3.559506 -10.51639 89.93905 -8.644512 -11.05871 89.89132 -7.782099 -13.43588 89.93905 -3.643005 -10.09875 89.76854 -8.395195 -10.74199 89.99346 -7.848342 -13.20152 89.99346 -8.375031 -10.89856 90 -3.608994 -10.20605 89.83346 -8.493142 -10.86865 89.97414 -7.499767 -13.79556 89.76854 -3.604805 -10.74199 89.99346 -3.682748 -10.70449 90 -8.709393 -11.27549 89.83346 -7.494811 -13.80825 89.7 -3.59731 -10.31035 89.89132 -7.646752 -13.61575 89.89132 -8.595367 -11.06691 89.93905 -7.81015 -13.24209 89.99346 -3.590368 -10.44304 89.93905 -7.65934 -13.30252 90 -7.74186 -13.39216 89.97414 -8.435402 -10.88327 89.99346 -3.623845 -10.68427 89.99346 -8.416585 -11.09674 90 -3.704435 -10.00023 89.76854 -3.750694 -9.917874 89.7 -8.671921 -11.2786 89.89132 -7.486976 -13.77599 89.83346 -8.536763 -11.07669 89.97414 -3.614612 -10.5386 89.97414 -7.616149 -13.57643 89.93905 -3.663107 -10.1107 89.83346 -8.622266 -11.28271 89.93905 -7.701519 -13.34834 89.99346 -3.642062 -10.22395 89.89132 -7.504821 -13.43339 90 -8.478012 -11.08649 89.99346 -7.309939 -13.90894 89.76854 -3.641961 -10.33246 89.93905 -7.31373 -13.91591 89.7 -7.124939 -14.00938 89.7 -8.563056 -11.28762 89.97414 -7.466411 -13.74451 89.89132 -3.644778 -10.4669 89.97414 -8.503696 -11.29254 89.99346 -7.579657 -13.52954 89.97414 -3.757185 -9.922439 89.76854 -7.298766 -13.88839 89.83346 -3.669857 -10.56087 89.99346 -3.756355 -10.51585 90 -3.724014 -10.01302 89.83346 -7.439159 -13.7028 89.93905 -3.695427 -10.12992 89.89132 -7.121693 -14.00214 89.76854 -6.929546 -14.08814 89.7 -7.543072 -13.48254 89.99346 -7.340023 -13.55106 90 -3.685882 -10.24766 89.93905 -3.699324 -10.49083 89.99346 -7.280804 -13.85536 89.89132 -3.695206 -10.35882 89.97414 -7.406663 -13.65306 89.97414 -3.836126 -9.815789 89.76854 -3.878405 -9.750333 89.7 -7.112126 -13.9808 89.83346 -3.776313 -9.935894 89.83346 -3.755491 -10.03359 89.89132 -7.257002 -13.81159 89.93905 -6.926864 -14.08067 89.76854 -3.738255 -10.15538 89.93905 -7.374085 -13.60319 89.99346 -3.884527 -9.755382 89.76854 -7.096745 -13.94649 89.89132 -3.738134 -10.27594 89.97414 -3.748584 -10.38525 89.99346 -3.845289 -10.33393 90 -7.228619 -13.75939 89.97414 -3.854581 -9.830153 89.83346 -6.918959 -14.05866 89.83346 -3.807067 -9.957526 89.89132 -7.076363 -13.90103 89.93905 -3.797203 -10.06084 89.93905 -6.726596 -14.14405 89.76854 -6.728699 -14.1517 89.7 -6.523576 -14.1997 89.7 -3.789325 -10.18574 89.97414 -7.200164 -13.70707 89.99346 -7.166071 -13.65471 90 -3.902569 -9.770261 89.83346 -6.90625 -14.02327 89.89132 -3.790519 -10.30429 89.99346 -7.052059 -13.84681 89.97414 -3.982597 -9.64285 89.76854 -4.018566 -9.593061 89.7 -6.720399 -14.1215 89.83346 -3.884253 -9.853248 89.89132 -3.847821 -9.986191 89.93905 -6.889408 -13.97638 89.93905 -6.522065 -14.19191 89.76854 -7.027694 -13.79246 89.99346 -6.984154 -13.74364 90 -3.846942 -10.09334 89.97414 -3.840523 -10.21618 89.99346 -3.948942 -10.15998 90 -6.710436 -14.08524 89.89132 -3.931577 -9.794184 89.89132 -6.451329 -14.20467 89.76854 -6.315379 -14.23186 89.7 -3.999803 -9.658689 89.83346 -6.517612 -14.16895 89.83346 -3.896417 -10.02037 89.97414 -3.896806 -10.12591 89.99346 -6.386311 -12.99202 87.9809 -6.320438 -13.00754 87.9809 -6.391452 -13.01188 87.99239 -5.094093 -10.25313 87.9809 -5.184749 -10.19205 87.9809 -5.082037 -10.23653 87.99239 -5.1739 -10.17465 87.99239 -4.700962 -10.75 87.9 -4.786475 -10.61832 87.9 -4.784239 -10.6167 87.92334 -4.883229 -10.49446 87.92334 -6.614538 -12.88028 87.9454 -6.529279 -12.9291 87.96494 -6.61985 -12.89221 87.96494 -6.242284 -13.08155 88 -6.401044 -13.04892 88 -6.328603 -13.04595 87.99808 -4.980272 -10.36748 87.96494 -4.968722 -10.35465 87.9809 -6.324702 -13.0276 87.99239 -6.23933 -13.06227 87.99808 -6.23649 -13.04372 87.99239 -6.476264 -12.96579 87.9809 -6.535274 -12.94528 87.9809 -4.877183 -10.48901 87.9454 -4.989011 -10.37718 87.9454 -4.867477 -10.48027 87.96494 -5.163977 -10.15873 87.99808 -5.071011 -10.22136 87.99808 -6.751382 -12.80143 87.92334 -6.665391 -12.85649 87.9454 -6.75545 -12.80848 87.9454 -5.153658 -10.14217 88 -6.794908 -12.77531 87.92334 -5.02063 -10.23476 88 -4.777657 -10.61192 87.9454 -6.671143 -12.86822 87.96494 -4.629682 -10.8899 87.9 -4.698569 -10.74862 87.92334 -6.881678 -12.71353 87.9 -6.883302 -12.71576 87.92334 -6.482602 -12.9853 87.99239 -4.954998 -10.33941 87.99239 -6.396154 -13.03004 87.99808 -4.854649 -10.46872 87.9809 -6.799211 -12.78222 87.9454 -4.767091 -10.60424 87.96494 -6.626871 -12.90798 87.9809 -4.942445 -10.32547 87.99808 -6.542398 -12.96452 87.99239 -4.897653 -10.34033 88 -4.691523 -10.74455 87.9454 -6.76198 -12.81979 87.96494 -6.678745 -12.88372 87.9809 -4.627158 -10.88877 87.92334 -6.555688 -13.0004 88 -6.488399 -13.00314 87.99808 -4.839407 -10.455 87.99239 -6.888084 -12.72234 87.9454 -4.753126 -10.59409 87.9809 -6.80612 -12.7933 87.96494 -4.680212 -10.73802 87.96494 -7.003696 -12.61472 87.9 -7.005545 -12.61677 87.92334 -7.114717 -12.5037 87.9 -4.825466 -10.44245 87.99808 -4.785987 -10.4578 88 -6.635213 -12.92671 87.99239 -6.548913 -12.98211 87.99808 -4.619725 -10.88546 87.9454 -6.770611 -12.83474 87.9809 -4.736533 -10.58204 87.99239 -6.687777 -12.90213 87.99239 -4.570787 -11.03562 87.92334 -4.573415 -11.03647 87.9 -4.532779 -11.18813 87.9 -6.895761 -12.73291 87.96494 -4.665263 -10.72939 87.9809 -6.815251 -12.80795 87.9809 -6.704631 -12.93649 88 -6.642844 -12.94385 87.99808 -4.607794 -10.88015 87.96494 -7.010989 -12.62282 87.9454 -4.721356 -10.57101 87.99808 -4.686778 -10.58597 88 -6.696039 -12.91897 87.99808 -4.563049 -11.03311 87.9454 -6.780866 -12.8525 87.99239 -7.116771 -12.50554 87.92334 -7.213525 -12.38168 87.9 -4.647501 -10.71913 87.99239 -4.530076 -11.18756 87.92334 -6.905907 -12.74687 87.9809 -6.8261 -12.82535 87.99239 -4.592024 -10.87313 87.9809 -7.019728 -12.63252 87.96494 -4.550628 -11.02907 87.96494 -6.846342 -12.85783 88 -6.790245 -12.86875 87.99808 -4.631255 -10.70975 87.99808 -7.122817 -12.51099 87.9454 -4.601045 -10.72352 88 -6.836023 -12.84127 87.99808 -4.522117 -11.18587 87.9454 -6.917963 -12.76347 87.99239 -4.573287 -10.86479 87.99239 -4.505469 -11.34292 87.92334 -4.508217 -11.34321 87.9 -7.299038 -12.25 87.9 -7.215761 -12.3833 87.92334 -4.5 -11.5 87.9 -4.497239 -11.5 87.92335 -4.489102 -11.5 87.9454 -4.534211 -11.02374 87.9809 -7.031278 -12.64535 87.9809 -4.509343 -11.18315 87.96494 -7.132523 -12.51973 87.96494 -4.529668 -10.86903 88 -4.55615 -10.85716 87.99808 -6.97937 -12.76524 88 -6.928989 -12.77864 87.99808 -4.497378 -11.34207 87.9454 -7.222343 -12.38808 87.9454 -4.514705 -11.0174 87.99239 -7.045002 -12.66059 87.99239 -4.492458 -11.17956 87.9809 -7.370318 -12.1101 87.9 -7.301431 -12.25138 87.92334 -4.484389 -11.3407 87.96494 -4.476039 -11.5 87.96494 -4.458778 -11.5 87.9809 -4.496864 -11.0116 87.99808 -7.145351 -12.53128 87.9809 -4.473377 -11.02102 88 -4.472396 -11.1753 87.99239 -7.232909 -12.39576 87.96494 -4.467221 -11.3389 87.9809 -7.102347 -12.65967 88 -7.057555 -12.67453 87.99808 -4.454047 -11.1714 87.99808 -7.308477 -12.25545 87.9454 -4.432752 -11.17792 88 -4.446824 -11.33675 87.99239 -4.43827 -11.5 87.99239 -4.419511 -11.5 87.99808 -7.372842 -12.11123 87.92334 -4.408209 -11.33813 88 -4.428167 -11.33479 87.99808 -7.160593 -12.545 87.99239 -7.246874 -12.40591 87.9809 -7.319788 -12.26198 87.96494 -7.214013 -12.5422 88 -7.174534 -12.55755 87.99808 -7.380275 -12.11454 87.9454 -7.426585 -11.96353 87.9 -7.429213 -11.96438 87.92334 -7.467221 -11.81187 87.9 -7.263467 -12.41796 87.99239 -7.334737 -12.27061 87.9809 -7.392206 -12.11985 87.96494 -7.313222 -12.41403 88 -7.278644 -12.42899 87.99808 -7.436951 -11.96689 87.9454 -7.491783 -11.65679 87.9 -7.469924 -11.81244 87.92334 -7.352499 -12.28087 87.99239 -7.407976 -12.12687 87.9809 -7.449372 -11.97093 87.96494 -7.398955 -12.27648 88 -7.368745 -12.29025 87.99808 -7.477883 -11.81413 87.9454 -7.494531 -11.65708 87.92334 -7.426713 -12.13521 87.99239 -7.465789 -11.97626 87.9809 -7.490657 -11.81685 87.96494 -7.470332 -12.13097 88 -7.44385 -12.14284 87.99808 -7.502622 -11.65793 87.9454 -7.5 -11.5 87.9 -7.502763 -11.5 87.92334 -7.485295 -11.9826 87.99239 -7.507542 -11.82044 87.9809 -7.515611 -11.6593 87.96494 -7.526623 -11.97898 88 -7.503136 -11.9884 87.99808 -7.510899 -11.5 87.9454 -7.491783 -11.34321 87.9 -7.495053 -11.34797 87.92334 -7.527604 -11.8247 87.99239 -7.532779 -11.6611 87.9809 -7.523959 -11.5 87.96494 -7.567248 -11.82208 88 -7.545953 -11.8286 87.99808 -7.503147 -11.34714 87.9454 -7.467221 -11.18813 87.9 -7.472001 -11.1975 87.92334 -7.553176 -11.66325 87.99239 -7.541221 -11.5 87.9809 -7.51614 -11.34582 87.96494 -7.571833 -11.66521 87.99808 -7.591791 -11.66187 88 -7.479971 -11.19586 87.9454 -7.426585 -11.03647 87.9 -7.433845 -11.05013 87.92334 -7.561732 -11.5 87.99239 -7.533314 -11.34408 87.9809 -7.492764 -11.19323 87.96494 -7.580491 -11.5 87.99808 -7.6 -11.5 88 -7.441608 -11.04769 87.9454 -7.380976 -10.90738 87.92334 -7.370318 -10.8899 87.9 -7.553719 -11.342 87.99239 -7.509673 -11.18975 87.9809 -7.454069 -11.04378 87.96494 -7.572382 -11.3401 87.99808 -7.591791 -11.33813 88 -7.388453 -10.90417 87.9454 -7.313936 -10.77071 87.92334 -7.299038 -10.75 87.9 -7.529763 -11.18563 87.99239 -7.47054 -11.03862 87.9809 -7.400454 -10.89902 87.96494 -7.548138 -11.18185 87.99808 -7.567248 -11.17792 88 -7.32105 -10.76676 87.9454 -7.213525 -10.61832 87.9 -7.233413 -10.64152 87.92334 -7.490109 -11.03248 87.99239 -7.416318 -10.89221 87.9809 -7.332469 -10.76042 87.96494 -7.508008 -11.02686 87.99808 -7.526623 -11.02102 88 -7.240091 -10.63687 87.9454 -7.140234 -10.52114 87.92334 -7.114717 -10.4963 87.9 -7.435166 -10.88412 87.99239 -7.347562 -10.75204 87.9809 -4.4 -11.5 88 -4.508217 -11.65679 87.9 -4.504947 -11.65203 87.92334 -7.25081 -10.62941 87.96494 -7.452405 -10.87672 87.99808 -4.496853 -11.65286 87.9454 -7.470332 -10.86903 88 -7.146407 -10.51584 87.9454 -4.532779 -11.81187 87.9 -4.527999 -11.8025 87.92334 -7.035354 -10.41081 87.92334 -7.003696 -10.38528 87.9 -4.48386 -11.65418 87.96494 -7.365495 -10.74209 87.99239 -4.520029 -11.80414 87.9454 -7.264978 -10.61955 87.9809 -4.573415 -11.96353 87.9 -4.566155 -11.94987 87.92334 -7.156317 -10.50733 87.96494 -7.381897 -10.73298 87.99808 -4.466686 -11.65592 87.9809 -7.398955 -10.72352 88 -7.04096 -10.40491 87.9454 -4.507236 -11.80677 87.96494 -6.91985 -10.31165 87.92334 -4.558392 -11.95231 87.9454 -6.881678 -10.28647 87.9 -4.629682 -12.1101 87.9 -4.619024 -12.09262 87.92334 -7.281812 -10.60783 87.99239 -7.169414 -10.49609 87.9809 -4.446281 -11.658 87.99239 -7.049958 -10.39545 87.96494 -4.490327 -11.81025 87.9809 -7.297209 -10.59712 87.99808 -7.313222 -10.58597 88 -4.545931 -11.95622 87.96494 -6.924831 -10.30522 87.9454 -4.427618 -11.6599 87.99808 -4.408209 -11.66187 88 -6.794908 -10.22469 87.92334 -6.75 -10.20096 87.9 -4.611547 -12.09583 87.9454 -7.184977 -10.48273 87.99239 -4.700962 -12.25 87.9 -4.686064 -12.22929 87.92334 -7.061851 -10.38293 87.9809 -4.470237 -11.81437 87.99239 -4.52946 -11.96138 87.9809 -6.751382 -10.19857 87.92334 -6.932825 -10.29489 87.96494 -4.599546 -12.10098 87.96494 -7.19921 -10.47051 87.99808 -4.451862 -11.81815 87.99808 -4.432752 -11.82208 88 -7.214013 -10.4578 88 -6.799211 -10.21778 87.9454 -4.67895 -12.23324 87.9454 -6.610105 -10.12968 87.9 -6.661808 -10.15081 87.92334 -4.786475 -12.38168 87.9 -4.766587 -12.35848 87.92334 -7.075981 -10.36807 87.99239 -4.509891 -11.96752 87.99239 -6.75545 -10.19152 87.9454 -6.943391 -10.28124 87.9809 -4.583682 -12.10779 87.9809 -6.611229 -10.12716 87.92334 -4.667531 -12.23958 87.96494 -4.473377 -11.97898 88 -4.491992 -11.97314 87.99808 -6.80612 -10.2067 87.96494 -4.759909 -12.36313 87.9454 -7.088906 -10.35447 87.99808 -4.885283 -12.5037 87.9 -4.859766 -12.47886 87.92334 -7.102347 -10.34033 88 -6.665391 -10.14351 87.9454 -4.564834 -12.11588 87.99239 -6.76198 -10.18021 87.96494 -6.463525 -10.07342 87.9 -6.521917 -10.09078 87.92334 -4.652438 -12.24796 87.9809 -6.955945 -10.26502 87.99239 -4.74919 -12.37059 87.96494 -4.529668 -12.13097 88 -4.547595 -12.12328 87.99808 -6.614538 -10.11972 87.9454 -4.853593 -12.48416 87.9454 -6.815251 -10.19205 87.9809 -4.996304 -12.61472 87.9 -4.964646 -12.58919 87.92334 -6.464379 -10.07079 87.92334 -4.634505 -12.25791 87.99239 -4.735022 -12.38045 87.9809 -6.671143 -10.13178 87.96494 -6.770611 -10.16526 87.9809 -6.967428 -10.25019 87.99808 -4.843683 -12.49267 87.96494 -6.97937 -10.23476 88 -4.601045 -12.27648 88 -4.618103 -12.26702 87.99808 -6.524743 -10.08315 87.9454 -4.95904 -12.59509 87.9454 -6.61985 -10.10779 87.96494 -5.118322 -12.71353 87.9 -5.08015 -12.68835 87.92334 -6.376671 -10.04521 87.92334 -6.311868 -10.03278 87.9 -6.8261 -10.17465 87.99239 -4.718188 -12.39217 87.99239 -6.466894 -10.06305 87.9454 -4.830586 -12.50391 87.9809 -6.678745 -10.11628 87.9809 -4.950042 -12.60455 87.96494 -6.312442 -10.03008 87.92334 -4.702791 -12.40288 87.99808 -4.686778 -12.41403 88 -6.780866 -10.1475 87.99239 -5.075169 -12.69478 87.9454 -5.25 -12.79904 87.9 -5.205092 -12.77531 87.92334 -6.529279 -10.0709 87.96494 -6.626871 -10.09202 87.9809 -4.815023 -12.51727 87.99239 -6.836023 -10.15873 87.99808 -6.846342 -10.14217 88 -6.378711 -10.03733 87.9454 -4.938149 -12.61707 87.9809 -6.470929 -10.05063 87.96494 -5.248618 -12.80143 87.92334 -6.22756 -10.01457 87.92334 -5.067175 -12.70511 87.96494 -6.156793 -10.00822 87.9 -4.785987 -12.5422 88 -4.80079 -12.52949 87.99808 -6.790245 -10.13125 87.99808 -6.704631 -10.06351 88 -6.687777 -10.09787 87.99239 -5.200789 -12.78222 87.9454 -6.314134 -10.02212 87.9454 -5.389895 -12.87032 87.9 -5.338192 -12.84919 87.92334 -6.535274 -10.05472 87.9809 -4.924019 -12.63193 87.99239 -6.635213 -10.07329 87.99239 -5.24455 -12.80848 87.9454 -5.056609 -12.71876 87.9809 -6.157082 -10.00547 87.92334 -6.381984 -10.02469 87.96494 -6.476264 -10.03421 87.9809 -5.388771 -12.87284 87.92334 -5.19388 -12.7933 87.96494 -6.696039 -10.08103 87.99808 -4.911094 -12.64553 87.99808 -6.228792 -10.00652 87.9454 -4.897653 -12.65967 88 -6.316849 -10.00934 87.96494 -5.334609 -12.85649 87.9454 -6.076114 -9.999166 87.92334 -6 -10 87.9 -5.23802 -12.81979 87.96494 -6.542398 -10.03548 87.99239 -5.536475 -12.92658 87.9 -5.478083 -12.90922 87.92334 -6.642844 -10.05615 87.99808 -5.044055 -12.73498 87.99239 -6.555688 -9.999597 88 -6.157932 -9.997378 87.9454 -5.385462 -12.88028 87.9454 -6.386311 -10.00798 87.9809 -5.184749 -12.80795 87.9809 -6.482602 -10.0147 87.99239 -5.535621 -12.92921 87.92334 -5.328857 -12.86822 87.96494 -6 -9.997237 87.92334 -6.23077 -9.993614 87.96494 -5.229389 -12.83474 87.9809 -6.548913 -10.01789 87.99808 -5.02063 -12.76524 88 -5.032572 -12.74981 87.99808 -6.320438 -9.992458 87.9809 -5.475257 -12.91685 87.9454 -6.076526 -9.99104 87.9454 -5.38015 -12.89221 87.96494 -5.923886 -9.999166 87.92334 -5.688132 -12.96722 87.9 -5.623329 -12.95479 87.92334 -5.843207 -10.00822 87.9 -6.159297 -9.984389 87.96494 -5.1739 -12.82535 87.99239 -6.391452 -9.988123 87.99239 -5.533106 -12.93695 87.9454 -6.488399 -9.996864 87.99808 -5.321255 -12.88372 87.9809 -6.401044 -9.951077 88 -6 -9.989101 87.9454 -5.219134 -12.8525 87.99239 -5.687558 -12.96992 87.92334 -6.233384 -9.976551 87.9809 -6.324702 -9.972396 87.99239 -5.470721 -12.9291 87.96494 -5.842918 -10.00547 87.92334 -5.373129 -12.90798 87.9809 -6.077187 -9.977997 87.96494 -5.153658 -12.85783 88 -5.163977 -12.84127 87.99808 -6.396154 -9.969963 87.99808 -5.621289 -12.96267 87.9454 -5.923474 -9.99104 87.9454 -5.529071 -12.94937 87.96494 -6.161102 -9.967221 87.9809 -5.843207 -12.99178 87.9 -5.77244 -12.98543 87.92334 -5.77244 -10.01457 87.92334 -5.688132 -10.03278 87.9 -5.209755 -12.86875 87.99808 -5.295369 -12.93649 88 -5.312223 -12.90213 87.99239 -6 -9.976041 87.96494 -5.685866 -12.97788 87.9454 -6.23649 -9.956278 87.99239 -6.328603 -9.954047 87.99808 -5.464726 -12.94528 87.9809 -6.242284 -9.918451 88 -5.842068 -9.997378 87.9454 -5.842918 -12.99453 87.92334 -6.078062 -9.960757 87.9809 -5.364787 -12.92671 87.99239 -5.618016 -12.97531 87.96494 -5.922813 -9.977997 87.96494 -5.523736 -12.96579 87.9809 -5.687558 -10.03008 87.92334 -5.303961 -12.91897 87.99808 -6.163245 -9.946824 87.99239 -6.23933 -9.937735 87.99808 -5.771208 -12.99348 87.9454 -5.683151 -12.99066 87.96494 -5.771208 -10.00652 87.9454 -6 -9.958779 87.9809 -6 -13 87.9 -5.923886 -13.00083 87.92334 -5.536475 -10.07342 87.9 -5.623329 -10.04521 87.92334 -5.457602 -12.96452 87.99239 -5.840703 -9.984389 87.96494 -5.444312 -13.0004 88 -5.357156 -12.94385 87.99808 -5.842068 -13.00262 87.9454 -6.0791 -9.940273 87.99239 -6.165206 -9.928167 87.99808 -5.613689 -12.99202 87.9809 -6.081039 -9.902054 88 -5.921938 -9.960757 87.9809 -6 -13.00276 87.92334 -5.517398 -12.9853 87.99239 -5.685866 -10.02212 87.9454 -5.76923 -13.00639 87.96494 -5.76923 -9.993614 87.96494 -5.451087 -12.98211 87.99808 -5.535621 -10.07079 87.92334 -5.679562 -13.00754 87.9809 -6 -9.938268 87.99239 -6.080051 -9.921538 87.99808 -5.923474 -13.00896 87.9454 -6.156793 -12.99178 87.9 -6.076114 -13.00083 87.92334 -5.621289 -10.03733 87.9454 -5.840703 -13.01561 87.96494 -5.838898 -9.967221 87.9809 -5.608548 -13.01188 87.99239 -5.389895 -10.12968 87.9 -5.478083 -10.09078 87.92334 -5.511601 -13.00314 87.99808 -5.598956 -13.04892 88 -5.9209 -9.940273 87.99239 -5.683151 -10.00934 87.96494 -6 -13.0109 87.9454 -6 -9.919509 87.99808 -5.918961 -9.902054 88 -5.766616 -13.02345 87.9809 -5.766616 -9.976551 87.9809 -6.157082 -12.99453 87.92334 -5.533106 -10.06305 87.9454 -5.675298 -13.0276 87.99239 -5.618016 -10.02469 87.96494 -5.922813 -13.022 87.96494 -5.836755 -9.946824 87.99239 -5.603846 -13.03004 87.99808 -5.388771 -10.12716 87.92334 -6.076526 -13.00896 87.9454 -5.838898 -13.03278 87.9809 -5.919949 -9.921538 87.99808 -5.475257 -10.08315 87.9454 -6.311868 -12.96722 87.9 -6.22756 -12.98543 87.92334 -5.679562 -9.992458 87.9809 -6 -13.02396 87.96494 -5.338192 -10.15081 87.92334 -5.25 -10.20096 87.9 -5.76351 -13.04372 87.99239 -5.76351 -9.956278 87.99239 -5.671397 -13.04595 87.99808 -5.757716 -13.08155 88 -5.529071 -10.05063 87.96494 -6.157932 -13.00262 87.9454 -5.834794 -9.928167 87.99808 -5.757716 -9.918451 88 -5.613689 -10.00798 87.9809 -5.921938 -13.03924 87.9809 -6.077187 -13.022 87.96494 -5.385462 -10.11972 87.9454 -6.312442 -12.96992 87.92334 -5.470721 -10.0709 87.96494 -5.836755 -13.05318 87.99239 -5.675298 -9.972396 87.99239 -5.76067 -13.06227 87.99808 -5.248618 -10.19857 87.92334 -6.228792 -12.99348 87.9454 -5.76067 -9.937735 87.99808 -6 -13.04122 87.9809 -5.334609 -10.14351 87.9454 -6.463525 -12.92658 87.9 -6.376671 -12.95479 87.92334 -5.523736 -10.03421 87.9809 -6.159297 -13.01561 87.96494 -5.118322 -10.28647 87.9 -5.205092 -10.22469 87.92334 -5.9209 -13.05973 87.99239 -5.608548 -9.988123 87.99239 -5.918961 -13.09795 88 -5.834794 -13.07183 87.99808 -5.38015 -10.10779 87.96494 -6.078062 -13.03924 87.9809 -5.671397 -9.954047 87.99808 -5.598956 -9.951077 88 -6.314134 -12.97788 87.9454 -5.464726 -10.05472 87.9809 -6.23077 -13.00639 87.96494 -5.24455 -10.19152 87.9454 -6 -13.06173 87.99239 -5.328857 -10.13178 87.96494 -6.464379 -12.92921 87.92334 -4.996304 -10.38528 87.9 -5.116698 -10.28424 87.92334 -5.919949 -13.07846 87.99808 -5.517398 -10.0147 87.99239 -6.378711 -12.96267 87.9454 -5.603846 -9.969963 87.99808 -6.161102 -13.03278 87.9809 -6.610105 -12.87032 87.9 -6.521917 -12.90922 87.92334 -5.200789 -10.21778 87.9454 -5.373129 -10.09202 87.9809 -6.0791 -13.05973 87.99239 -6.316849 -12.99066 87.96494 -5.457602 -10.03548 87.99239 -5.23802 -10.18021 87.96494 -6.081039 -13.09795 88 -6 -13.08049 87.99808 -5.321255 -10.11628 87.9809 -6.233384 -13.02345 87.9809 -5.511601 -9.996864 87.99808 -5.444312 -9.999597 88 -6.466894 -12.93695 87.9454 -5.111916 -10.27766 87.9454 -6.381984 -12.97531 87.96494 -5.19388 -10.2067 87.96494 -6.163245 -13.05318 87.99239 -4.994455 -10.38323 87.92334 -5.364787 -10.07329 87.99239 -6.611229 -12.87284 87.92334 -6.080051 -13.07846 87.99808 -5.451087 -10.01789 87.99808 -6.524743 -12.91685 87.9454 -5.229389 -10.16526 87.9809 -5.312223 -10.09787 87.99239 -6.661808 -12.84919 87.92334 -5.104239 -10.26709 87.96494 -6.75 -12.79904 87.9 -6.470929 -12.94937 87.96494 -5.357156 -10.05615 87.99808 -6.165206 -13.07183 87.99808 -5.295369 -10.06351 88 -5.303961 -10.08103 87.99808 -5.219134 -10.1475 87.99239 -4.885283 -10.4963 87.9 -5.209755 -10.13125 87.99808 -8.75 -11.5 88 -8.741931 -11.71051 88 -8.717771 -11.91979 88 -8.677662 -12.1266 88 -8.62184 -12.32973 88 -8.550632 -12.528 88 -8.464455 -12.72023 88 -8.363816 -12.9053 88 -8.249306 -13.08213 88 -8.121595 -13.24967 88 -7.981434 -13.40694 88 -7.829646 -13.55302 88 -7.66712 -13.68706 88 -7.494811 -13.80825 88 -7.31373 -13.91591 88 -7.124939 -14.00938 88 -6.929546 -14.08814 88 -6.728699 -14.1517 88 -6.523576 -14.1997 88 -6.315379 -14.23186 88 -6.105333 -14.24798 88 -5.894667 -14.24798 88 -5.684621 -14.23186 88 -5.476424 -14.1997 88 -5.271301 -14.1517 88 -5.070454 -14.08814 88 -4.875061 -14.00938 88 -4.68627 -13.91591 88 -4.505189 -13.80825 88 -4.33288 -13.68706 88 -4.170354 -13.55302 88 -4.018566 -13.40694 88 -3.878405 -13.24967 88 -3.750694 -13.08213 88 -3.636184 -12.9053 88 -3.535545 -12.72023 88 -3.449368 -12.528 88 -3.37816 -12.32973 88 -3.322338 -12.1266 88 -3.282229 -11.91979 88 -3.258069 -11.71051 88 -3.25 -11.5 88 -3.258069 -11.28949 88 -3.282229 -11.08021 88 -3.322338 -10.8734 88 -3.37816 -10.67027 88 -3.449368 -10.472 88 -3.535545 -10.27977 88 -3.636184 -10.0947 88 -3.750694 -9.917874 88 -3.878405 -9.750333 88 -4.018566 -9.593061 88 -4.170354 -9.446979 88 -4.33288 -9.312945 88 -4.505189 -9.191745 88 -4.68627 -9.084091 88 -4.875061 -8.990615 88 -5.070454 -8.911865 88 -5.271301 -8.848303 88 -5.476424 -8.800302 88 -5.684621 -8.768144 88 -5.894667 -8.752018 88 -6.105333 -8.752018 88 -6.315379 -8.768144 88 -6.523576 -8.800302 88 -6.728699 -8.848303 88 -6.929546 -8.911865 88 -7.124939 -8.990615 88 -7.31373 -9.084091 88 -7.494811 -9.191745 88 -7.66712 -9.312945 88 -7.829646 -9.446979 88 -7.981434 -9.593061 88 -8.121595 -9.750333 88 -8.249306 -9.917874 88 -8.363816 -10.0947 88 -8.464455 -10.27977 88 -8.550632 -10.472 88 -8.62184 -10.67027 88 -8.677662 -10.8734 88 -8.717771 -11.08021 88 -8.741931 -11.28949 88 -7.5 -11.5 78.2805 -7.491783 -11.65679 78.2805 -7.467221 -11.81187 78.2805 -7.426585 -11.96353 78.2805 -7.370318 -12.1101 78.2805 -7.299038 -12.25 78.2805 -7.213525 -12.38168 78.2805 -7.114717 -12.5037 78.2805 -7.003696 -12.61472 78.2805 -6.881678 -12.71353 78.2805 -6.75 -12.79904 78.2805 -6.610105 -12.87032 78.2805 -6.463525 -12.92658 78.2805 -6.311868 -12.96722 78.2805 -6.156793 -12.99178 78.2805 -6 -13 78.2805 -5.843207 -12.99178 78.2805 -5.688132 -12.96722 78.2805 -5.536475 -12.92658 78.2805 -5.389895 -12.87032 78.2805 -5.25 -12.79904 78.2805 -5.118322 -12.71353 78.2805 -4.996304 -12.61472 78.2805 -4.885283 -12.5037 78.2805 -4.786475 -12.38168 78.2805 -4.700962 -12.25 78.2805 -4.629682 -12.1101 78.2805 -4.573415 -11.96353 78.2805 -4.532779 -11.81187 78.2805 -4.508217 -11.65679 78.2805 -4.5 -11.5 78.2805 -4.508217 -11.34321 78.2805 -4.532779 -11.18813 78.2805 -4.573415 -11.03647 78.2805 -4.629682 -10.8899 78.2805 -4.700962 -10.75 78.2805 -4.786475 -10.61832 78.2805 -4.885283 -10.4963 78.2805 -4.996304 -10.38528 78.2805 -5.118322 -10.28647 78.2805 -5.25 -10.20096 78.2805 -5.389895 -10.12968 78.2805 -5.536475 -10.07342 78.2805 -5.688132 -10.03278 78.2805 -5.843207 -10.00822 78.2805 -6 -10 78.2805 -6.156793 -10.00822 78.2805 -6.311868 -10.03278 78.2805 -6.463525 -10.07342 78.2805 -6.610105 -10.12968 78.2805 -6.75 -10.20096 78.2805 -6.881678 -10.28647 78.2805 -7.003696 -10.38528 78.2805 -7.114717 -10.4963 78.2805 -7.213525 -10.61832 78.2805 -7.299038 -10.75 78.2805 -7.370318 -10.8899 78.2805 -7.426585 -11.03647 78.2805 -7.467221 -11.18813 78.2805 -7.491783 -11.34321 78.2805 -7.2195 -11.5 78 -7.211254 -11.64158 78 -7.186628 -11.78124 78 -7.145955 -11.91709 78 -7.089785 -12.04731 78 -7.018877 -12.17013 78 -6.934191 -12.28388 78 -6.836872 -12.38703 78 -6.728235 -12.47819 78 -6.60975 -12.55612 78 -6.483019 -12.61976 78 -6.349757 -12.66827 78 -6.211764 -12.70097 78 -6.070908 -12.71744 78 -5.929092 -12.71744 78 -5.788236 -12.70097 78 -5.650243 -12.66827 78 -5.516981 -12.61976 78 -5.39025 -12.55612 78 -5.271765 -12.47819 78 -5.163128 -12.38703 78 -5.065809 -12.28388 78 -4.981123 -12.17013 78 -4.910215 -12.04731 78 -4.854045 -11.91709 78 -4.813372 -11.78124 78 -4.788746 -11.64158 78 -4.7805 -11.5 78 -4.788746 -11.35842 78 -4.813372 -11.21876 78 -4.854045 -11.08291 78 -4.910215 -10.95269 78 -4.981123 -10.82987 78 -5.065809 -10.71612 78 -5.163128 -10.61297 78 -5.271765 -10.52181 78 -5.39025 -10.44388 78 -5.516981 -10.38024 78 -5.650243 -10.33173 78 -5.788236 -10.29903 78 -5.929092 -10.28256 78 -6.070908 -10.28256 78 -6.211764 -10.29903 78 -6.349757 -10.33173 78 -6.483019 -10.38024 78 -6.60975 -10.44388 78 -6.728235 -10.52181 78 -6.836872 -10.61297 78 -6.934191 -10.71612 78 -7.018877 -10.82987 78 -7.089785 -10.95269 78 -7.145955 -11.08291 78 -7.186628 -11.21876 78 -7.211254 -11.35842 78 -6 -10.3453 90 -6 -12.6547 90 -7 -12.07735 90 -5 -12.07735 90 -5 -10.92265 90 -7 -10.92265 90 -7 -12.07735 88.5 -6 -12.6547 88.5 -7 -10.92265 88.5 -6 -10.3453 88.5 -5 -10.92265 88.5 -5 -12.07735 88.5 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 0 1 2 1 4 2 3 2 2 2 5 3 6 3 7 3 8 4 9 4 7 4 9 5 10 5 7 5 10 6 5 6 7 6 11 7 12 7 13 7 14 8 11 8 13 8 15 9 16 9 17 9 11 10 18 10 17 10 16 11 19 11 17 11 18 12 15 12 17 12 8 13 7 13 20 13 6 14 21 14 20 14 7 15 6 15 20 15 16 16 8 16 20 16 11 17 17 17 22 17 19 18 23 18 22 18 17 19 19 19 22 19 12 20 11 20 22 20 20 21 21 21 24 21 16 22 20 22 24 22 21 23 25 23 24 23 19 24 16 24 24 24 22 25 23 25 26 25 12 26 22 26 26 26 23 27 27 27 26 27 28 28 12 28 26 28 23 29 19 29 29 29 25 30 30 30 29 30 24 31 25 31 29 31 19 32 24 32 29 32 31 33 28 33 32 33 28 34 26 34 32 34 26 35 27 35 32 35 27 36 33 36 32 36 29 37 30 37 34 37 23 38 29 38 34 38 30 39 35 39 34 39 27 40 23 40 34 40 32 41 33 41 36 41 31 42 32 42 36 42 33 43 37 43 36 43 38 44 31 44 36 44 34 45 35 45 39 45 27 46 34 46 39 46 33 47 27 47 39 47 35 48 40 48 39 48 38 49 36 49 41 49 36 50 37 50 41 50 42 51 38 51 41 51 37 52 43 52 41 52 40 53 44 53 45 53 33 54 39 54 45 54 39 55 40 55 45 55 37 56 33 56 45 56 42 57 41 57 46 57 41 58 43 58 46 58 47 59 42 59 46 59 43 60 48 60 46 60 49 61 50 61 51 61 37 62 45 62 52 62 45 63 44 63 52 63 43 64 37 64 52 64 44 65 53 65 52 65 48 66 54 66 55 66 47 67 46 67 55 67 46 68 48 68 55 68 49 69 47 69 55 69 51 70 50 70 56 70 53 71 57 71 58 71 43 72 52 72 58 72 52 73 53 73 58 73 48 74 43 74 58 74 50 75 59 75 60 75 56 76 50 76 60 76 61 77 56 77 60 77 61 78 60 78 62 78 60 79 59 79 62 79 55 80 54 80 63 80 54 81 64 81 63 81 49 82 55 82 63 82 50 83 49 83 63 83 59 84 65 84 66 84 62 85 59 85 66 85 54 86 48 86 67 86 57 87 68 87 67 87 48 88 58 88 67 88 58 89 57 89 67 89 66 90 65 90 69 90 59 91 50 91 70 91 64 92 71 92 70 92 63 93 64 93 70 93 50 94 63 94 70 94 65 95 72 95 73 95 69 96 65 96 73 96 64 97 54 97 74 97 68 98 75 98 74 98 54 99 67 99 74 99 67 100 68 100 74 100 73 101 72 101 76 101 65 102 59 102 77 102 71 103 78 103 77 103 59 104 70 104 77 104 70 105 71 105 77 105 72 106 79 106 80 106 76 107 72 107 80 107 64 108 74 108 81 108 71 109 64 109 81 109 75 110 82 110 81 110 74 111 75 111 81 111 80 112 79 112 83 112 72 113 65 113 84 113 65 114 77 114 84 114 78 115 85 115 84 115 77 116 78 116 84 116 71 117 81 117 86 117 81 118 82 118 86 118 78 119 71 119 86 119 82 120 87 120 86 120 84 121 85 121 88 121 79 122 72 122 88 122 72 123 84 123 88 123 85 124 89 124 88 124 83 125 79 125 90 125 90 126 91 126 92 126 91 127 83 127 90 127 78 128 86 128 93 128 86 129 87 129 93 129 85 130 78 130 93 130 87 131 94 131 93 131 85 132 93 132 95 132 93 133 94 133 95 133 89 134 85 134 95 134 94 135 96 135 95 135 89 136 95 136 97 136 95 137 96 137 97 137 98 138 0 138 99 138 0 139 97 139 99 139 97 140 96 140 99 140 100 141 101 141 102 141 92 142 100 142 102 142 102 143 101 143 103 143 92 144 102 144 103 144 103 145 101 145 104 145 92 146 103 146 104 146 101 147 105 147 104 147 104 148 105 148 106 148 92 149 104 149 106 149 105 150 107 150 108 150 92 151 106 151 108 151 106 152 105 152 108 152 108 153 107 153 109 153 92 154 108 154 109 154 109 155 107 155 110 155 107 156 111 156 110 156 111 157 112 157 110 157 92 158 0 158 113 158 114 159 92 159 113 159 115 160 114 160 113 160 116 161 115 161 113 161 0 162 3 162 113 162 3 163 117 163 113 163 117 164 116 164 113 164 14 165 13 165 118 165 1 166 119 166 120 166 119 167 121 167 120 167 121 168 122 168 120 168 2 169 1 169 120 169 13 170 12 170 123 170 118 171 13 171 123 171 124 172 118 172 123 172 12 173 28 173 123 173 28 174 31 174 125 174 123 175 28 175 125 175 124 176 123 176 125 176 124 177 125 177 126 177 125 178 31 178 126 178 126 179 31 179 127 179 31 180 38 180 127 180 128 181 126 181 127 181 38 182 42 182 129 182 130 183 128 183 129 183 127 184 38 184 129 184 128 185 127 185 129 185 131 186 132 186 5 186 129 187 42 187 133 187 42 188 47 188 134 188 133 189 42 189 134 189 47 190 49 190 135 190 134 191 47 191 135 191 66 192 69 192 136 192 69 193 73 193 136 193 73 194 76 194 136 194 92 195 136 195 137 195 136 196 76 196 137 196 92 197 137 197 138 197 137 198 76 198 138 198 76 199 80 199 138 199 92 200 138 200 139 200 138 201 80 201 139 201 80 202 83 202 140 202 92 203 139 203 140 203 139 204 80 204 140 204 141 205 142 205 6 205 140 206 83 206 143 206 92 207 140 207 143 207 5 208 132 208 6 208 143 209 83 209 144 209 132 210 141 210 6 210 91 211 92 211 144 211 92 212 143 212 144 212 83 213 91 213 144 213 92 214 90 214 145 214 79 215 88 215 145 215 88 216 89 216 145 216 89 217 97 217 145 217 90 218 79 218 145 218 97 219 0 219 145 219 0 220 92 220 145 220 146 221 147 221 148 221 147 222 149 222 148 222 149 223 98 223 148 223 98 224 99 224 148 224 109 225 110 225 150 225 92 226 109 226 150 226 110 227 112 227 150 227 112 228 151 228 150 228 152 229 153 229 154 229 150 230 151 230 154 230 151 231 152 231 154 231 150 232 154 232 155 232 142 233 156 233 21 233 154 234 153 234 155 234 156 235 157 235 21 235 157 236 158 236 21 236 153 237 14 237 155 237 14 238 118 238 155 238 2 239 120 239 159 239 4 240 2 240 159 240 6 241 142 241 21 241 131 242 5 242 159 242 122 243 160 243 159 243 160 244 131 244 159 244 5 245 4 245 159 245 120 246 122 246 159 246 129 247 133 247 161 247 161 248 133 248 162 248 163 249 161 249 162 249 133 250 134 250 162 250 134 251 135 251 162 251 158 252 164 252 25 252 162 253 135 253 165 253 164 254 166 254 25 254 135 255 49 255 165 255 166 256 167 256 25 256 49 257 51 257 165 257 21 258 158 258 25 258 168 259 163 259 165 259 163 260 162 260 165 260 165 261 51 261 169 261 168 262 165 262 169 262 51 263 56 263 169 263 136 264 92 264 170 264 92 265 168 265 170 265 169 266 56 266 170 266 56 267 61 267 170 267 168 268 169 268 170 268 61 269 62 269 170 269 62 270 66 270 170 270 66 271 136 271 170 271 171 272 172 272 173 272 172 273 146 273 173 273 146 274 148 274 173 274 148 275 99 275 173 275 94 276 171 276 173 276 99 277 96 277 173 277 96 278 94 278 173 278 150 279 155 279 174 279 155 280 118 280 174 280 168 281 92 281 174 281 92 282 150 282 174 282 118 283 124 283 174 283 174 284 124 284 175 284 176 285 177 285 30 285 124 286 126 286 175 286 168 287 174 287 175 287 167 288 176 288 30 288 25 289 167 289 30 289 175 290 126 290 178 290 128 291 130 291 178 291 126 292 128 292 178 292 175 293 178 293 179 293 178 294 130 294 179 294 129 295 161 295 180 295 168 296 175 296 180 296 175 297 179 297 180 297 179 298 130 298 180 298 163 299 168 299 180 299 161 300 163 300 180 300 130 301 129 301 180 301 30 302 177 302 35 302 177 303 181 303 35 303 181 304 182 304 35 304 182 305 183 305 35 305 183 306 184 306 40 306 184 307 185 307 40 307 185 308 186 308 40 308 35 309 183 309 40 309 187 310 188 310 44 310 186 311 187 311 44 311 40 312 186 312 44 312 188 313 189 313 53 313 189 314 190 314 53 314 190 315 191 315 53 315 44 316 188 316 53 316 191 317 192 317 57 317 192 318 193 318 57 318 193 319 194 319 57 319 53 320 191 320 57 320 57 321 194 321 68 321 195 322 196 322 68 322 194 323 195 323 68 323 196 324 197 324 75 324 197 325 198 325 75 325 198 326 199 326 75 326 68 327 196 327 75 327 199 328 200 328 82 328 200 329 201 329 82 329 201 330 202 330 82 330 75 331 199 331 82 331 203 332 204 332 87 332 202 333 203 333 87 333 82 334 202 334 87 334 204 335 171 335 94 335 87 336 204 336 94 336 100 337 115 337 101 337 115 338 100 338 114 338 114 339 92 339 100 339 101 340 115 340 105 340 115 341 205 341 105 341 105 342 205 342 107 342 205 343 206 343 111 343 107 344 205 344 111 344 111 345 206 345 112 345 117 346 9 346 116 346 205 347 115 347 116 347 112 348 206 348 151 348 206 349 18 349 151 349 151 350 18 350 152 350 116 351 9 351 207 351 206 352 205 352 207 352 9 353 8 353 207 353 205 354 116 354 207 354 153 355 152 355 208 355 18 356 11 356 208 356 152 357 18 357 208 357 9 358 117 358 10 358 4 359 5 359 10 359 117 360 3 360 10 360 3 361 4 361 10 361 206 362 207 362 15 362 207 363 8 363 15 363 18 364 206 364 15 364 8 365 16 365 15 365 153 366 208 366 14 366 208 367 11 367 14 367 209 368 210 368 211 368 209 369 212 369 213 369 209 370 211 370 212 370 214 371 215 371 216 371 217 372 218 372 219 372 220 373 221 373 222 373 220 374 223 374 221 374 217 375 216 375 218 375 224 376 225 376 226 376 227 377 213 377 228 377 224 378 226 378 229 378 230 379 209 379 213 379 231 380 229 380 215 380 232 381 233 381 234 381 235 382 236 382 237 382 232 383 234 383 225 383 235 384 237 384 238 384 235 385 239 385 223 385 235 386 238 386 239 386 240 387 219 387 241 387 240 388 241 388 242 388 243 389 222 389 210 389 243 390 220 390 222 390 244 391 215 391 214 391 245 392 210 392 209 392 245 393 209 393 230 393 244 394 231 394 215 394 246 395 214 395 216 395 247 396 228 396 248 396 246 397 216 397 217 397 247 398 227 398 228 398 249 399 225 399 224 399 249 400 250 400 233 400 251 401 223 401 220 401 251 402 235 402 223 402 249 403 233 403 232 403 249 404 232 404 225 404 252 405 213 405 227 405 253 406 224 406 229 406 252 407 230 407 213 407 253 408 229 408 231 408 254 409 245 409 230 409 255 410 217 410 219 410 255 411 219 411 240 411 256 412 220 412 243 412 256 413 251 413 220 413 257 414 256 414 243 414 258 415 231 415 244 415 257 416 210 416 245 416 258 417 253 417 231 417 257 418 243 418 210 418 259 419 214 419 246 419 259 420 244 420 214 420 260 421 247 421 248 421 261 422 224 422 253 422 261 423 249 423 224 423 261 424 250 424 249 424 262 425 227 425 247 425 262 426 252 426 227 426 263 427 242 427 264 427 265 428 266 428 236 428 263 429 255 429 240 429 265 430 236 430 235 430 265 431 235 431 251 431 263 432 240 432 242 432 267 433 254 433 230 433 268 434 217 434 255 434 268 435 246 435 217 435 267 436 230 436 252 436 269 437 245 437 254 437 269 438 257 438 245 438 270 439 271 439 250 439 270 440 250 440 261 440 270 441 253 441 258 441 270 442 261 442 253 442 272 443 258 443 244 443 273 444 265 444 251 444 273 445 266 445 265 445 272 446 244 446 259 446 273 447 251 447 256 447 274 448 260 448 248 448 274 449 248 449 275 449 276 450 268 450 255 450 276 451 255 451 263 451 277 452 257 452 269 452 277 453 273 453 256 453 278 454 246 454 268 454 277 455 256 455 257 455 279 456 247 456 260 456 278 457 259 457 246 457 280 458 270 458 258 458 280 459 281 459 271 459 279 460 262 460 247 460 280 461 271 461 270 461 280 462 258 462 272 462 282 463 252 463 262 463 282 464 267 464 252 464 283 465 284 465 285 465 283 466 264 466 284 466 286 467 269 467 254 467 283 468 263 468 264 468 283 469 276 469 263 469 286 470 254 470 267 470 287 471 278 471 268 471 287 472 268 472 276 472 288 473 274 473 275 473 289 474 272 474 259 474 289 475 259 475 278 475 289 476 280 476 272 476 290 477 277 477 269 477 291 478 276 478 283 478 291 479 287 479 276 479 292 480 293 480 266 480 292 481 273 481 277 481 292 482 266 482 273 482 294 483 289 483 278 483 294 484 278 484 287 484 295 485 279 485 260 485 295 486 260 486 274 486 295 487 274 487 288 487 296 488 285 488 297 488 298 489 262 489 279 489 296 490 283 490 285 490 299 491 280 491 289 491 299 492 300 492 281 492 298 493 282 493 262 493 299 494 281 494 280 494 301 495 267 495 282 495 301 496 286 496 267 496 302 497 287 497 291 497 303 498 269 498 286 498 304 499 299 499 289 499 303 500 290 500 269 500 304 501 289 501 294 501 305 502 293 502 292 502 305 503 277 503 290 503 306 504 283 504 296 504 305 505 292 505 277 505 307 506 295 506 288 506 306 507 291 507 283 507 308 508 304 508 294 508 308 509 294 509 287 509 309 510 288 510 275 510 309 511 275 511 310 511 308 512 287 512 302 512 311 513 296 513 297 513 312 514 295 514 307 514 312 515 279 515 295 515 311 516 297 516 313 516 312 517 298 517 279 517 314 518 300 518 299 518 314 519 299 519 304 519 315 520 282 520 298 520 316 521 302 521 291 521 316 522 291 522 306 522 315 523 301 523 282 523 317 524 309 524 310 524 318 525 304 525 308 525 319 526 286 526 301 526 320 527 306 527 296 527 319 528 303 528 286 528 320 529 296 529 311 529 321 530 322 530 293 530 321 531 293 531 305 531 321 532 290 532 303 532 321 533 305 533 290 533 323 534 308 534 302 534 323 535 302 535 316 535 324 536 312 536 307 536 325 537 313 537 326 537 327 538 288 538 309 538 325 539 311 539 313 539 327 540 307 540 288 540 328 541 314 541 304 541 328 542 300 542 314 542 328 543 304 543 318 543 328 544 329 544 300 544 330 545 315 545 298 545 330 546 298 546 312 546 331 547 316 547 306 547 331 548 306 548 320 548 331 549 323 549 316 549 332 550 301 550 315 550 333 551 308 551 323 551 332 552 319 552 301 552 333 553 318 553 308 553 334 554 327 554 309 554 334 555 309 555 317 555 335 556 322 556 321 556 335 557 303 557 319 557 336 558 311 558 325 558 335 559 321 559 303 559 336 560 320 560 311 560 337 561 310 561 338 561 337 562 317 562 310 562 339 563 323 563 331 563 340 564 312 564 324 564 341 565 325 565 326 565 340 566 330 566 312 566 342 567 328 567 318 567 342 568 343 568 329 568 342 569 329 569 328 569 342 570 318 570 333 570 344 571 324 571 307 571 344 572 307 572 327 572 345 573 320 573 336 573 345 574 331 574 320 574 346 575 315 575 330 575 346 576 332 576 315 576 347 577 335 577 319 577 347 578 348 578 322 578 349 579 326 579 350 579 347 580 322 580 335 580 349 581 341 581 326 581 347 582 319 582 332 582 351 583 333 583 323 583 352 584 344 584 327 584 351 585 323 585 339 585 352 586 327 586 334 586 353 587 317 587 337 587 354 588 336 588 325 588 353 589 334 589 317 589 354 590 325 590 341 590 355 591 330 591 340 591 354 592 341 592 349 592 355 593 346 593 330 593 356 594 339 594 331 594 356 595 331 595 345 595 357 596 340 596 324 596 357 597 324 597 344 597 358 598 332 598 346 598 359 599 354 599 349 599 358 600 347 600 332 600 358 601 348 601 347 601 360 602 349 602 350 602 361 603 337 603 338 603 362 604 343 604 342 604 362 605 363 605 343 605 362 606 333 606 351 606 361 607 338 607 364 607 362 608 342 608 333 608 365 609 345 609 336 609 366 610 357 610 344 610 365 611 336 611 354 611 366 612 344 612 352 612 365 613 354 613 359 613 367 614 350 614 368 614 369 615 352 615 334 615 369 616 334 616 353 616 367 617 360 617 350 617 370 618 371 618 348 618 372 619 339 619 356 619 370 620 348 620 358 620 370 621 358 621 346 621 372 622 351 622 339 622 370 623 346 623 355 623 373 624 340 624 357 624 373 625 355 625 340 625 374 626 365 626 359 626 375 627 353 627 337 627 375 628 337 628 361 628 376 629 359 629 349 629 376 630 349 630 360 630 376 631 360 631 367 631 377 632 365 632 374 632 378 633 357 633 366 633 378 634 373 634 357 634 377 635 356 635 345 635 379 636 366 636 352 636 377 637 345 637 365 637 379 638 352 638 369 638 380 639 367 639 368 639 381 640 371 640 370 640 382 641 376 641 367 641 381 642 370 642 355 642 381 643 355 643 373 643 382 644 367 644 380 644 383 645 384 645 363 645 385 646 361 646 364 646 383 647 363 647 362 647 383 648 362 648 351 648 385 649 364 649 386 649 383 650 351 650 372 650 387 651 369 651 353 651 388 652 377 652 374 652 387 653 353 653 375 653 389 654 374 654 359 654 390 655 391 655 371 655 390 656 373 656 378 656 390 657 371 657 381 657 389 658 359 658 376 658 390 659 381 659 373 659 389 660 376 660 382 660 392 661 380 661 368 661 393 662 378 662 366 662 393 663 366 663 379 663 392 664 368 664 394 664 395 665 375 665 361 665 396 666 356 666 377 666 396 667 377 667 388 667 395 668 361 668 385 668 396 669 372 669 356 669 397 670 380 670 392 670 397 671 382 671 380 671 398 672 379 672 369 672 399 673 389 673 382 673 398 674 369 674 387 674 400 675 401 675 391 675 399 676 382 676 397 676 400 677 378 677 393 677 400 678 391 678 390 678 400 679 390 679 378 679 402 680 396 680 388 680 403 681 386 681 404 681 403 682 385 682 386 682 405 683 388 683 374 683 405 684 374 684 389 684 406 685 392 685 394 685 407 686 387 686 375 686 407 687 375 687 395 687 408 688 392 688 406 688 409 689 393 689 379 689 408 690 397 690 392 690 409 691 379 691 398 691 409 692 400 692 393 692 410 693 372 693 396 693 410 694 411 694 384 694 410 695 384 695 383 695 410 696 396 696 402 696 410 697 383 697 372 697 412 698 395 698 385 698 413 699 397 699 408 699 412 700 385 700 403 700 413 701 399 701 397 701 414 702 398 702 387 702 414 703 387 703 407 703 415 704 405 704 389 704 415 705 389 705 399 705 416 706 410 706 402 706 417 707 418 707 419 707 416 708 411 708 410 708 417 709 404 709 418 709 417 710 403 710 404 710 420 711 394 711 421 711 422 712 423 712 401 712 420 713 406 713 394 713 422 714 401 714 400 714 422 715 400 715 409 715 424 716 388 716 405 716 424 717 402 717 388 717 425 718 407 718 395 718 425 719 395 719 412 719 426 720 406 720 420 720 426 721 408 721 406 721 427 722 409 722 398 722 427 723 398 723 414 723 427 724 422 724 409 724 428 725 408 725 426 725 428 726 413 726 408 726 429 727 412 727 403 727 429 728 403 728 417 728 430 729 399 729 413 729 430 730 415 730 399 730 430 731 413 731 428 731 431 732 407 732 425 732 431 733 414 733 407 733 432 734 417 734 419 734 433 735 420 735 421 735 434 736 424 736 405 736 434 737 405 737 415 737 435 738 422 738 427 738 435 739 436 739 423 739 435 740 423 740 422 740 434 741 415 741 430 741 437 742 402 742 424 742 438 743 425 743 412 743 437 744 439 744 411 744 437 745 416 745 402 745 437 746 411 746 416 746 438 747 412 747 429 747 440 748 414 748 431 748 441 749 426 749 420 749 440 750 427 750 414 750 442 751 417 751 432 751 443 752 428 752 426 752 443 753 426 753 441 753 444 754 430 754 428 754 442 755 429 755 417 755 445 756 425 756 438 756 444 757 428 757 443 757 445 758 431 758 425 758 446 759 434 759 430 759 446 760 430 760 444 760 447 761 432 761 419 761 448 762 439 762 437 762 448 763 424 763 434 763 448 764 437 764 424 764 447 765 449 765 450 765 447 766 419 766 449 766 451 767 435 767 427 767 452 768 420 768 433 768 451 769 436 769 435 769 452 770 441 770 420 770 451 771 427 771 440 771 453 772 438 772 429 772 454 773 421 773 455 773 454 774 433 774 421 774 454 775 452 775 433 775 453 776 429 776 442 776 456 777 440 777 431 777 456 778 451 778 440 778 457 779 443 779 441 779 456 780 431 780 445 780 458 781 442 781 432 781 459 782 444 782 443 782 458 783 432 783 447 783 460 784 454 784 455 784 461 785 445 785 438 785 462 786 444 786 459 786 461 787 438 787 453 787 462 788 446 788 444 788 463 789 446 789 462 789 464 790 447 790 450 790 463 791 465 791 439 791 463 792 439 792 448 792 463 793 434 793 446 793 463 794 448 794 434 794 466 795 467 795 436 795 468 796 457 796 441 796 466 797 451 797 456 797 466 798 436 798 451 798 468 799 441 799 452 799 469 800 452 800 454 800 470 801 464 801 450 801 470 802 450 802 471 802 472 803 442 803 458 803 469 804 454 804 460 804 469 805 468 805 452 805 472 806 453 806 442 806 473 807 443 807 457 807 473 808 459 808 443 808 474 809 462 809 459 809 475 810 445 810 461 810 475 811 456 811 445 811 474 812 459 812 473 812 476 813 469 813 460 813 477 814 458 814 447 814 477 815 447 815 464 815 477 816 464 816 470 816 478 817 462 817 474 817 478 818 463 818 462 818 478 819 465 819 463 819 479 820 460 820 455 820 480 821 477 821 470 821 479 822 455 822 481 822 482 823 453 823 472 823 483 824 473 824 457 824 482 825 461 825 453 825 483 826 457 826 468 826 484 827 468 827 469 827 484 828 483 828 468 828 484 829 469 829 476 829 485 830 470 830 471 830 486 831 487 831 467 831 488 832 474 832 473 832 486 833 467 833 466 833 486 834 466 834 456 834 486 835 456 835 475 835 489 836 478 836 474 836 489 837 465 837 478 837 489 838 490 838 465 838 491 839 472 839 458 839 491 840 458 840 477 840 491 841 477 841 480 841 492 842 484 842 476 842 493 843 460 843 479 843 494 844 471 844 495 844 494 845 485 845 471 845 493 846 476 846 460 846 496 847 488 847 473 847 497 848 491 848 480 848 496 849 473 849 483 849 498 850 475 850 461 850 499 851 483 851 484 851 498 852 461 852 482 852 499 853 484 853 492 853 499 854 496 854 483 854 500 855 489 855 474 855 501 856 480 856 470 856 500 857 474 857 488 857 501 858 470 858 485 858 500 859 490 859 489 859 502 860 481 860 503 860 502 861 479 861 481 861 504 862 472 862 491 862 504 863 482 863 472 863 505 864 494 864 495 864 506 865 499 865 492 865 507 866 492 866 476 866 507 867 476 867 493 867 508 868 494 868 505 868 508 869 485 869 494 869 508 870 501 870 485 870 509 871 510 871 487 871 511 872 488 872 496 872 511 873 512 873 490 873 511 874 500 874 488 874 509 875 487 875 486 875 509 876 486 876 475 876 511 877 490 877 500 877 509 878 475 878 498 878 513 879 496 879 499 879 513 880 499 880 506 880 513 881 511 881 496 881 514 882 491 882 497 882 514 883 504 883 491 883 515 884 479 884 502 884 515 885 493 885 479 885 516 886 480 886 501 886 516 887 497 887 480 887 517 888 513 888 506 888 518 889 495 889 519 889 518 890 505 890 495 890 520 891 482 891 504 891 521 892 506 892 492 892 520 893 498 893 482 893 521 894 492 894 507 894 522 895 512 895 511 895 523 896 505 896 518 896 522 897 511 897 513 897 522 898 513 898 517 898 523 899 508 899 505 899 524 900 503 900 525 900 524 901 502 901 503 901 526 902 501 902 508 902 526 903 516 903 501 903 526 904 508 904 523 904 527 905 493 905 515 905 527 906 507 906 493 906 528 907 520 907 504 907 528 908 504 908 514 908 529 909 514 909 497 909 530 910 531 910 512 910 530 911 512 911 522 911 530 912 522 912 517 912 529 913 497 913 516 913 532 914 506 914 521 914 532 915 517 915 506 915 533 916 518 916 519 916 534 917 502 917 524 917 534 918 515 918 502 918 535 919 518 919 533 919 535 920 523 920 518 920 536 921 509 921 498 921 536 922 537 922 510 922 536 923 498 923 520 923 536 924 510 924 509 924 538 925 521 925 507 925 538 926 507 926 527 926 539 927 530 927 517 927 539 928 540 928 531 928 541 929 523 929 535 929 539 930 531 930 530 930 541 931 526 931 523 931 539 932 517 932 532 932 542 933 516 933 526 933 543 934 525 934 544 934 542 935 529 935 516 935 543 936 524 936 525 936 542 937 526 937 541 937 545 938 520 938 528 938 545 939 537 939 536 939 545 940 536 940 520 940 546 941 515 941 534 941 547 942 533 942 519 942 546 943 527 943 515 943 548 944 532 944 521 944 547 945 519 945 549 945 550 946 514 946 529 946 550 947 528 947 514 947 548 948 521 948 538 948 550 949 545 949 528 949 551 950 524 950 543 950 552 951 533 951 547 951 552 952 535 952 533 952 553 953 541 953 535 953 551 954 534 954 524 954 554 955 527 955 546 955 553 956 535 956 552 956 554 957 538 957 527 957 555 958 542 958 541 958 556 959 557 959 558 959 556 960 544 960 557 960 556 961 551 961 543 961 559 962 529 962 542 962 559 963 550 963 529 963 556 964 543 964 544 964 559 965 542 965 555 965 560 966 540 966 539 966 560 967 539 967 532 967 560 968 561 968 540 968 560 969 532 969 548 969 562 970 547 970 549 970 563 971 534 971 551 971 564 972 552 972 547 972 563 973 546 973 534 973 565 974 538 974 554 974 564 975 547 975 562 975 565 976 548 976 538 976 566 977 537 977 545 977 566 978 567 978 537 978 566 979 545 979 550 979 568 980 569 980 570 980 571 981 563 981 551 981 572 982 553 982 552 982 572 983 552 983 564 983 573 984 541 984 553 984 571 985 551 985 556 985 573 986 555 986 541 986 574 987 554 987 546 987 574 988 546 988 563 988 575 989 567 989 566 989 575 990 566 990 550 990 575 991 550 991 559 991 576 992 558 992 577 992 576 993 556 993 558 993 578 994 559 994 555 994 578 995 575 995 559 995 579 996 548 996 565 996 579 997 560 997 548 997 579 998 561 998 560 998 579 999 580 999 561 999 581 1000 549 1000 582 1000 583 1001 563 1001 571 1001 581 1002 562 1002 549 1002 584 1003 564 1003 562 1003 585 1004 565 1004 554 1004 584 1005 562 1005 581 1005 585 1006 554 1006 574 1006 585 1007 579 1007 565 1007 586 1008 572 1008 564 1008 586 1009 564 1009 584 1009 587 1010 571 1010 556 1010 588 1011 589 1011 590 1011 591 1012 573 1012 553 1012 592 1013 568 1013 570 1013 591 1014 553 1014 572 1014 587 1015 556 1015 576 1015 593 1016 585 1016 574 1016 593 1017 563 1017 583 1017 592 1018 594 1018 595 1018 592 1019 570 1019 594 1019 593 1020 574 1020 563 1020 596 1021 581 1021 582 1021 597 1022 598 1022 568 1022 599 1023 577 1023 600 1023 601 1024 555 1024 573 1024 599 1025 587 1025 576 1025 599 1026 576 1026 577 1026 601 1027 578 1027 555 1027 597 1028 568 1028 592 1028 601 1029 573 1029 591 1029 602 1030 579 1030 585 1030 603 1031 604 1031 567 1031 602 1032 580 1032 579 1032 605 1033 597 1033 592 1033 603 1034 567 1034 575 1034 605 1035 592 1035 595 1035 603 1036 575 1036 578 1036 606 1037 583 1037 571 1037 607 1038 584 1038 581 1038 606 1039 571 1039 587 1039 608 1040 598 1040 597 1040 608 1041 609 1041 598 1041 610 1042 584 1042 607 1042 611 1043 585 1043 593 1043 612 1044 597 1044 605 1044 610 1045 586 1045 584 1045 612 1046 608 1046 597 1046 613 1047 586 1047 610 1047 613 1048 572 1048 586 1048 614 1049 606 1049 587 1049 614 1050 587 1050 599 1050 613 1051 591 1051 572 1051 615 1052 601 1052 591 1052 616 1053 617 1053 609 1053 618 1054 593 1054 583 1054 616 1055 609 1055 608 1055 618 1056 583 1056 606 1056 619 1057 605 1057 595 1057 620 1058 578 1058 601 1058 620 1059 604 1059 603 1059 621 1060 599 1060 600 1060 619 1061 622 1061 623 1061 620 1062 603 1062 578 1062 619 1063 595 1063 622 1063 624 1064 607 1064 581 1064 625 1065 616 1065 608 1065 626 1066 627 1066 580 1066 625 1067 608 1067 612 1067 624 1068 581 1068 596 1068 626 1069 585 1069 611 1069 626 1070 602 1070 585 1070 626 1071 580 1071 602 1071 628 1072 624 1072 596 1072 629 1073 630 1073 617 1073 631 1074 600 1074 632 1074 629 1075 590 1075 630 1075 628 1076 582 1076 633 1076 628 1077 596 1077 582 1077 631 1078 621 1078 600 1078 629 1079 617 1079 616 1079 634 1080 612 1080 605 1080 635 1081 610 1081 607 1081 636 1082 606 1082 614 1082 636 1083 618 1083 606 1083 634 1084 605 1084 619 1084 637 1085 593 1085 618 1085 638 1086 629 1086 616 1086 638 1087 616 1087 625 1087 639 1088 613 1088 610 1088 637 1089 611 1089 593 1089 640 1090 628 1090 633 1090 641 1091 619 1091 623 1091 642 1092 614 1092 599 1092 642 1093 599 1093 621 1093 643 1094 613 1094 639 1094 641 1095 634 1095 619 1095 644 1096 590 1096 629 1096 643 1097 591 1097 613 1097 644 1098 588 1098 590 1098 643 1099 615 1099 591 1099 644 1100 645 1100 588 1100 646 1101 601 1101 615 1101 646 1102 647 1102 604 1102 646 1103 620 1103 601 1103 648 1104 642 1104 621 1104 649 1105 625 1105 612 1105 646 1106 604 1106 620 1106 648 1107 621 1107 631 1107 649 1108 612 1108 634 1108 650 1109 641 1109 623 1109 651 1110 637 1110 618 1110 652 1111 635 1111 607 1111 652 1112 607 1112 624 1112 651 1113 618 1113 636 1113 653 1114 652 1114 624 1114 650 1115 623 1115 654 1115 655 1116 648 1116 631 1116 656 1117 644 1117 629 1117 653 1118 628 1118 640 1118 655 1119 631 1119 632 1119 656 1120 629 1120 638 1120 653 1121 624 1121 628 1121 657 1122 658 1122 627 1122 659 1123 634 1123 641 1123 659 1124 649 1124 634 1124 660 1125 610 1125 635 1125 657 1126 627 1126 626 1126 657 1127 626 1127 611 1127 659 1128 641 1128 650 1128 657 1129 611 1129 637 1129 660 1130 639 1130 610 1130 661 1131 638 1131 625 1131 662 1132 614 1132 642 1132 663 1133 643 1133 639 1133 662 1134 636 1134 614 1134 663 1135 639 1135 660 1135 661 1136 625 1136 649 1136 664 1137 655 1137 632 1137 665 1138 653 1138 640 1138 664 1139 632 1139 666 1139 667 1140 659 1140 650 1140 668 1141 647 1141 646 1141 668 1142 646 1142 615 1142 669 1143 662 1143 642 1143 670 1144 650 1144 654 1144 668 1145 615 1145 643 1145 668 1146 643 1146 663 1146 671 1147 640 1147 633 1147 669 1148 642 1148 648 1148 670 1149 667 1149 650 1149 671 1150 633 1150 672 1150 673 1151 657 1151 637 1151 674 1152 645 1152 644 1152 674 1153 675 1153 645 1153 674 1154 644 1154 656 1154 673 1155 637 1155 651 1155 676 1156 659 1156 667 1156 677 1157 635 1157 652 1157 676 1158 649 1158 659 1158 678 1159 655 1159 664 1159 677 1160 660 1160 635 1160 678 1161 669 1161 648 1161 676 1162 661 1162 649 1162 679 1163 670 1163 654 1163 678 1164 648 1164 655 1164 680 1165 636 1165 662 1165 681 1166 653 1166 665 1166 680 1167 651 1167 636 1167 679 1168 654 1168 682 1168 681 1169 652 1169 653 1169 683 1170 668 1170 663 1170 684 1171 656 1171 638 1171 683 1172 685 1172 647 1172 683 1173 647 1173 668 1173 684 1174 638 1174 661 1174 686 1175 683 1175 663 1175 686 1176 663 1176 660 1176 687 1177 664 1177 666 1177 688 1178 676 1178 667 1178 689 1179 678 1179 664 1179 689 1180 664 1180 687 1180 690 1181 681 1181 665 1181 691 1182 665 1182 640 1182 692 1183 667 1183 670 1183 693 1184 694 1184 658 1184 692 1185 688 1185 667 1185 691 1186 640 1186 671 1186 693 1187 657 1187 673 1187 693 1188 658 1188 657 1188 692 1189 670 1189 679 1189 695 1190 662 1190 669 1190 696 1191 684 1191 661 1191 696 1192 661 1192 676 1192 695 1193 680 1193 662 1193 697 1194 660 1194 677 1194 698 1195 669 1195 678 1195 697 1196 686 1196 660 1196 698 1197 695 1197 669 1197 699 1198 679 1198 682 1198 700 1199 677 1199 652 1199 698 1200 678 1200 689 1200 700 1201 652 1201 681 1201 701 1202 687 1202 666 1202 702 1203 692 1203 679 1203 700 1204 681 1204 690 1204 700 1205 697 1205 677 1205 701 1206 666 1206 703 1206 704 1207 685 1207 683 1207 704 1208 683 1208 686 1208 705 1209 651 1209 680 1209 706 1210 674 1210 656 1210 706 1211 675 1211 674 1211 707 1212 672 1212 708 1212 706 1213 709 1213 675 1213 706 1214 656 1214 684 1214 705 1215 673 1215 651 1215 707 1216 671 1216 672 1216 710 1217 696 1217 676 1217 711 1218 687 1218 701 1218 711 1219 689 1219 687 1219 710 1220 676 1220 688 1220 712 1221 710 1221 688 1221 713 1222 700 1222 690 1222 712 1223 692 1223 702 1223 714 1224 689 1224 711 1224 712 1225 688 1225 692 1225 714 1226 698 1226 689 1226 715 1227 665 1227 691 1227 715 1228 690 1228 665 1228 716 1229 680 1229 695 1229 716 1230 705 1230 680 1230 717 1231 685 1231 704 1231 718 1232 682 1232 719 1232 717 1233 720 1233 685 1233 718 1234 699 1234 682 1234 717 1235 686 1235 697 1235 721 1236 695 1236 698 1236 717 1237 704 1237 686 1237 721 1238 716 1238 695 1238 722 1239 684 1239 696 1239 723 1240 697 1240 700 1240 722 1241 706 1241 684 1241 723 1242 700 1242 713 1242 724 1243 699 1243 718 1243 724 1244 702 1244 679 1244 724 1245 679 1245 699 1245 725 1246 701 1246 703 1246 726 1247 691 1247 671 1247 727 1248 711 1248 701 1248 726 1249 671 1249 707 1249 728 1250 723 1250 713 1250 727 1251 701 1251 725 1251 729 1252 712 1252 702 1252 730 1253 694 1253 693 1253 730 1254 673 1254 705 1254 731 1255 696 1255 710 1255 730 1256 732 1256 694 1256 730 1257 693 1257 673 1257 731 1258 722 1258 696 1258 733 1259 714 1259 711 1259 734 1260 710 1260 712 1260 735 1261 713 1261 690 1261 734 1262 731 1262 710 1262 735 1263 690 1263 715 1263 733 1264 711 1264 727 1264 734 1265 712 1265 729 1265 736 1266 717 1266 697 1266 737 1267 698 1267 714 1267 738 1268 718 1268 719 1268 736 1269 697 1269 723 1269 737 1270 721 1270 698 1270 736 1271 723 1271 728 1271 736 1272 720 1272 717 1272 739 1273 705 1273 716 1273 740 1274 724 1274 718 1274 739 1275 730 1275 705 1275 741 1276 708 1276 742 1276 739 1277 732 1277 730 1277 741 1278 707 1278 708 1278 743 1279 703 1279 744 1279 745 1280 691 1280 726 1280 746 1281 709 1281 706 1281 746 1282 706 1282 722 1282 743 1283 725 1283 703 1283 746 1284 747 1284 709 1284 745 1285 715 1285 691 1285 748 1286 729 1286 702 1286 749 1287 739 1287 716 1287 748 1288 702 1288 724 1288 749 1289 716 1289 721 1289 750 1290 720 1290 736 1290 748 1291 724 1291 740 1291 750 1292 751 1292 720 1292 750 1293 736 1293 728 1293 752 1294 734 1294 729 1294 753 1295 713 1295 735 1295 754 1296 727 1296 725 1296 754 1297 725 1297 743 1297 753 1298 728 1298 713 1298 755 1299 707 1299 741 1299 756 1300 746 1300 722 1300 757 1301 733 1301 727 1301 756 1302 747 1302 746 1302 756 1303 722 1303 731 1303 757 1304 727 1304 754 1304 758 1305 714 1305 733 1305 758 1306 737 1306 714 1306 759 1307 719 1307 760 1307 755 1308 726 1308 707 1308 759 1309 738 1309 719 1309 761 1310 715 1310 745 1310 761 1311 735 1311 715 1311 762 1312 721 1312 737 1312 763 1313 734 1313 752 1313 763 1314 756 1314 731 1314 762 1315 749 1315 721 1315 763 1316 731 1316 734 1316 764 1317 750 1317 728 1317 765 1318 718 1318 738 1318 764 1319 751 1319 750 1319 765 1320 740 1320 718 1320 764 1321 766 1321 751 1321 764 1322 728 1322 753 1322 767 1323 743 1323 744 1323 765 1324 738 1324 759 1324 768 1325 754 1325 743 1325 769 1326 748 1326 740 1326 770 1327 742 1327 771 1327 770 1328 741 1328 742 1328 768 1329 743 1329 767 1329 772 1330 773 1330 732 1330 774 1331 752 1331 729 1331 772 1332 732 1332 739 1332 772 1333 739 1333 749 1333 775 1334 726 1334 755 1334 774 1335 729 1335 748 1335 775 1336 745 1336 726 1336 776 1337 754 1337 768 1337 777 1338 735 1338 761 1338 778 1339 763 1339 752 1339 776 1340 757 1340 754 1340 777 1341 764 1341 753 1341 779 1342 757 1342 776 1342 780 1343 759 1343 760 1343 779 1344 758 1344 733 1344 777 1345 753 1345 735 1345 781 1346 755 1346 741 1346 779 1347 733 1347 757 1347 781 1348 741 1348 770 1348 782 1349 772 1349 749 1349 783 1350 747 1350 756 1350 783 1351 784 1351 747 1351 782 1352 773 1352 772 1352 783 1353 763 1353 778 1353 782 1354 749 1354 762 1354 783 1355 756 1355 763 1355 785 1356 761 1356 745 1356 786 1357 765 1357 759 1357 786 1358 759 1358 780 1358 787 1359 762 1359 737 1359 785 1360 745 1360 775 1360 787 1361 737 1361 758 1361 788 1362 765 1362 786 1362 788 1363 769 1363 740 1363 789 1364 744 1364 790 1364 791 1365 770 1365 771 1365 789 1366 767 1366 744 1366 788 1367 740 1367 765 1367 791 1368 792 1368 793 1368 791 1369 771 1369 792 1369 794 1370 768 1370 767 1370 795 1371 774 1371 748 1371 795 1372 748 1372 769 1372 796 1373 797 1373 766 1373 794 1374 767 1374 789 1374 796 1375 766 1375 764 1375 796 1376 764 1376 777 1376 798 1377 776 1377 768 1377 799 1378 783 1378 778 1378 799 1379 784 1379 783 1379 800 1380 775 1380 755 1380 800 1381 755 1381 781 1381 798 1382 768 1382 794 1382 801 1383 752 1383 774 1383 802 1384 796 1384 777 1384 801 1385 778 1385 752 1385 802 1386 761 1386 785 1386 802 1387 777 1387 761 1387 803 1388 779 1388 776 1388 804 1389 780 1389 760 1389 804 1390 760 1390 805 1390 806 1391 770 1391 791 1391 807 1392 789 1392 790 1392 806 1393 781 1393 770 1393 808 1394 758 1394 779 1394 809 1395 786 1395 780 1395 808 1396 779 1396 803 1396 808 1397 787 1397 758 1397 810 1398 773 1398 782 1398 811 1399 788 1399 786 1399 810 1400 782 1400 762 1400 812 1401 785 1401 775 1401 810 1402 762 1402 787 1402 811 1403 786 1403 809 1403 812 1404 775 1404 800 1404 810 1405 813 1405 773 1405 814 1406 794 1406 789 1406 815 1407 795 1407 769 1407 816 1408 793 1408 817 1408 815 1409 769 1409 788 1409 814 1410 789 1410 807 1410 816 1411 791 1411 793 1411 818 1412 819 1412 797 1412 818 1413 796 1413 802 1413 820 1414 804 1414 805 1414 818 1415 797 1415 796 1415 821 1416 794 1416 814 1416 821 1417 798 1417 794 1417 822 1418 800 1418 781 1418 823 1419 801 1419 774 1419 822 1420 781 1420 806 1420 824 1421 776 1421 798 1421 823 1422 774 1422 795 1422 824 1423 803 1423 776 1423 825 1424 802 1424 785 1424 826 1425 808 1425 803 1425 827 1426 778 1426 801 1426 825 1427 785 1427 812 1427 827 1428 784 1428 799 1428 827 1429 799 1429 778 1429 825 1430 818 1430 802 1430 827 1431 828 1431 784 1431 829 1432 787 1432 808 1432 830 1433 809 1433 780 1433 829 1434 810 1434 787 1434 829 1435 813 1435 810 1435 830 1436 804 1436 820 1436 829 1437 808 1437 826 1437 831 1438 806 1438 791 1438 830 1439 780 1439 804 1439 831 1440 791 1440 816 1440 832 1441 814 1441 807 1441 833 1442 811 1442 809 1442 834 1443 800 1443 822 1443 834 1444 812 1444 800 1444 835 1445 790 1445 836 1445 837 1446 816 1446 817 1446 838 1447 815 1447 788 1447 835 1448 807 1448 790 1448 839 1449 814 1449 832 1449 839 1450 821 1450 814 1450 838 1451 788 1451 811 1451 837 1452 831 1452 816 1452 840 1453 823 1453 795 1453 841 1454 819 1454 818 1454 840 1455 795 1455 815 1455 841 1456 818 1456 825 1456 842 1457 824 1457 798 1457 843 1458 830 1458 820 1458 844 1459 822 1459 806 1459 844 1460 806 1460 831 1460 842 1461 798 1461 821 1461 845 1462 825 1462 812 1462 846 1463 828 1463 827 1463 845 1464 812 1464 834 1464 847 1465 835 1465 836 1465 846 1466 801 1466 823 1466 846 1467 827 1467 801 1467 848 1468 803 1468 824 1468 849 1469 820 1469 805 1469 848 1470 826 1470 803 1470 848 1471 824 1471 842 1471 849 1472 805 1472 850 1472 851 1473 809 1473 830 1473 852 1474 831 1474 837 1474 853 1475 813 1475 829 1475 851 1476 830 1476 843 1476 852 1477 844 1477 831 1477 853 1478 829 1478 826 1478 853 1479 854 1479 813 1479 851 1480 833 1480 809 1480 855 1481 834 1481 822 1481 856 1482 839 1482 832 1482 855 1483 822 1483 844 1483 857 1484 811 1484 833 1484 857 1485 838 1485 811 1485 858 1486 817 1486 859 1486 860 1487 832 1487 807 1487 858 1488 837 1488 817 1488 860 1489 807 1489 835 1489 861 1490 862 1490 819 1490 860 1491 835 1491 847 1491 863 1492 849 1492 850 1492 861 1493 825 1493 845 1493 864 1494 821 1494 839 1494 861 1495 819 1495 841 1495 864 1496 842 1496 821 1496 861 1497 841 1497 825 1497 865 1498 855 1498 844 1498 866 1499 840 1499 815 1499 866 1500 815 1500 838 1500 867 1501 828 1501 846 1501 865 1502 844 1502 852 1502 867 1503 823 1503 840 1503 868 1504 858 1504 859 1504 869 1505 848 1505 842 1505 867 1506 846 1506 823 1506 867 1507 870 1507 828 1507 868 1508 859 1508 871 1508 872 1509 851 1509 843 1509 873 1510 834 1510 855 1510 874 1511 860 1511 847 1511 875 1512 826 1512 848 1512 876 1513 843 1513 820 1513 873 1514 845 1514 834 1514 875 1515 853 1515 826 1515 876 1516 820 1516 849 1516 877 1517 852 1517 837 1517 875 1518 854 1518 853 1518 876 1519 849 1519 863 1519 877 1520 837 1520 858 1520 877 1521 858 1521 868 1521 878 1522 836 1522 879 1522 880 1523 857 1523 833 1523 880 1524 851 1524 872 1524 878 1525 847 1525 836 1525 881 1526 864 1526 839 1526 880 1527 833 1527 851 1527 882 1528 873 1528 855 1528 882 1529 855 1529 865 1529 883 1530 866 1530 838 1530 884 1531 877 1531 868 1531 881 1532 839 1532 856 1532 883 1533 838 1533 857 1533 885 1534 876 1534 863 1534 886 1535 868 1535 871 1535 887 1536 856 1536 832 1536 887 1537 860 1537 874 1537 887 1538 832 1538 860 1538 888 1539 840 1539 866 1539 889 1540 890 1540 854 1540 888 1541 867 1541 840 1541 891 1542 861 1542 845 1542 889 1543 875 1543 848 1543 888 1544 870 1544 867 1544 891 1545 892 1545 862 1545 889 1546 848 1546 869 1546 889 1547 854 1547 875 1547 891 1548 862 1548 861 1548 891 1549 845 1549 873 1549 893 1550 865 1550 852 1550 894 1551 842 1551 864 1551 895 1552 863 1552 850 1552 893 1553 877 1553 884 1553 894 1554 864 1554 881 1554 894 1555 869 1555 842 1555 895 1556 850 1556 896 1556 897 1557 880 1557 872 1557 893 1558 852 1558 877 1558 898 1559 886 1559 871 1559 899 1560 876 1560 885 1560 898 1561 871 1561 900 1561 901 1562 887 1562 874 1562 899 1563 872 1563 843 1563 899 1564 843 1564 876 1564 902 1565 873 1565 882 1565 903 1566 874 1566 847 1566 902 1567 891 1567 873 1567 903 1568 847 1568 878 1568 904 1569 888 1569 866 1569 905 1570 893 1570 884 1570 904 1571 866 1571 883 1571 906 1572 894 1572 881 1572 904 1573 870 1573 888 1573 904 1574 907 1574 870 1574 908 1575 883 1575 857 1575 908 1576 857 1576 880 1576 908 1577 880 1577 897 1577 909 1578 868 1578 886 1578 910 1579 856 1579 887 1579 910 1580 881 1580 856 1580 911 1581 899 1581 885 1581 909 1582 884 1582 868 1582 912 1583 889 1583 869 1583 909 1584 886 1584 898 1584 913 1585 865 1585 893 1585 913 1586 882 1586 865 1586 912 1587 890 1587 889 1587 912 1588 869 1588 894 1588 914 1589 885 1589 863 1589 914 1590 863 1590 895 1590 915 1591 879 1591 916 1591 915 1592 878 1592 879 1592 917 1593 908 1593 897 1593 918 1594 898 1594 900 1594 919 1595 910 1595 887 1595 920 1596 897 1596 872 1596 920 1597 872 1597 899 1597 921 1598 909 1598 898 1598 919 1599 887 1599 901 1599 922 1600 923 1600 892 1600 924 1601 901 1601 874 1601 922 1602 892 1602 891 1602 922 1603 891 1603 902 1603 925 1604 883 1604 908 1604 925 1605 908 1605 917 1605 925 1606 904 1606 883 1606 925 1607 907 1607 904 1607 924 1608 874 1608 903 1608 926 1609 913 1609 893 1609 927 1610 890 1610 912 1610 926 1611 893 1611 905 1611 927 1612 912 1612 894 1612 927 1613 928 1613 890 1613 929 1614 914 1614 895 1614 927 1615 894 1615 906 1615 930 1616 884 1616 909 1616 930 1617 905 1617 884 1617 931 1618 881 1618 910 1618 929 1619 896 1619 932 1619 929 1620 895 1620 896 1620 931 1621 927 1621 906 1621 930 1622 909 1622 921 1622 931 1623 906 1623 881 1623 933 1624 920 1624 899 1624 934 1625 900 1625 935 1625 933 1626 899 1626 911 1626 934 1627 918 1627 900 1627 936 1628 903 1628 878 1628 937 1629 882 1629 913 1629 938 1630 933 1630 911 1630 936 1631 878 1631 915 1631 938 1632 911 1632 885 1632 939 1633 910 1633 919 1633 938 1634 885 1634 914 1634 937 1635 902 1635 882 1635 940 1636 907 1636 925 1636 939 1637 931 1637 910 1637 940 1638 925 1638 917 1638 941 1639 919 1639 901 1639 940 1640 942 1640 907 1640 943 1641 898 1641 918 1641 943 1642 921 1642 898 1642 943 1643 918 1643 934 1643 944 1644 917 1644 897 1644 944 1645 897 1645 920 1645 941 1646 901 1646 924 1646 945 1647 928 1647 927 1647 946 1648 930 1648 921 1648 945 1649 927 1649 931 1649 947 1650 913 1650 926 1650 948 1651 938 1651 914 1651 949 1652 916 1652 569 1652 947 1653 937 1653 913 1653 949 1654 915 1654 916 1654 948 1655 914 1655 929 1655 949 1656 568 1656 598 1656 950 1657 944 1657 920 1657 950 1658 920 1658 933 1658 951 1659 905 1659 930 1659 949 1660 569 1660 568 1660 951 1661 926 1661 905 1661 952 1662 924 1662 903 1662 953 1663 933 1663 938 1663 952 1664 903 1664 936 1664 954 1665 934 1665 935 1665 955 1666 928 1666 945 1666 956 1667 942 1667 940 1667 955 1668 931 1668 939 1668 956 1669 917 1669 944 1669 955 1670 945 1670 931 1670 956 1671 940 1671 917 1671 955 1672 957 1672 928 1672 958 1673 943 1673 934 1673 959 1674 919 1674 941 1674 958 1675 934 1675 954 1675 959 1676 939 1676 919 1676 960 1677 929 1677 932 1677 961 1678 962 1678 923 1678 961 1679 923 1679 922 1679 961 1680 922 1680 902 1680 961 1681 902 1681 937 1681 963 1682 915 1682 949 1682 963 1683 936 1683 915 1683 960 1684 932 1684 964 1684 963 1685 949 1685 598 1685 965 1686 921 1686 943 1686 965 1687 946 1687 921 1687 963 1688 598 1688 609 1688 966 1689 953 1689 938 1689 965 1690 943 1690 958 1690 967 1691 924 1691 952 1691 966 1692 938 1692 948 1692 968 1693 942 1693 956 1693 968 1694 944 1694 950 1694 967 1695 941 1695 924 1695 969 1696 930 1696 946 1696 968 1697 956 1697 944 1697 969 1698 951 1698 930 1698 968 1699 970 1699 942 1699 971 1700 950 1700 933 1700 971 1701 933 1701 953 1701 972 1702 939 1702 959 1702 973 1703 962 1703 961 1703 972 1704 955 1704 939 1704 972 1705 957 1705 955 1705 973 1706 937 1706 947 1706 973 1707 961 1707 937 1707 972 1708 974 1708 957 1708 975 1709 935 1709 976 1709 977 1710 936 1710 963 1710 978 1711 929 1711 960 1711 977 1712 952 1712 936 1712 978 1713 948 1713 929 1713 975 1714 954 1714 935 1714 977 1715 963 1715 609 1715 979 1716 959 1716 941 1716 979 1717 941 1717 967 1717 980 1718 947 1718 926 1718 980 1719 926 1719 951 1719 981 1720 953 1720 966 1720 981 1721 971 1721 953 1721 980 1722 951 1722 969 1722 982 1723 954 1723 975 1723 983 1724 967 1724 952 1724 984 1725 950 1725 971 1725 984 1726 968 1726 950 1726 982 1727 958 1727 954 1727 984 1728 970 1728 968 1728 983 1729 952 1729 977 1729 985 1730 958 1730 982 1730 983 1731 977 1731 609 1731 984 1732 986 1732 970 1732 983 1733 609 1733 617 1733 983 1734 617 1734 630 1734 987 1735 959 1735 979 1735 988 1736 960 1736 964 1736 985 1737 965 1737 958 1737 987 1738 972 1738 959 1738 987 1739 589 1739 974 1739 989 1740 965 1740 985 1740 987 1741 974 1741 972 1741 988 1742 990 1742 991 1742 988 1743 964 1743 990 1743 989 1744 946 1744 965 1744 992 1745 979 1745 967 1745 992 1746 983 1746 630 1746 989 1747 969 1747 946 1747 992 1748 967 1748 983 1748 993 1749 948 1749 978 1749 994 1750 980 1750 969 1750 993 1751 966 1751 948 1751 995 1752 590 1752 589 1752 995 1753 979 1753 992 1753 995 1754 987 1754 979 1754 995 1755 589 1755 987 1755 996 1756 984 1756 971 1756 995 1757 992 1757 630 1757 995 1758 630 1758 590 1758 996 1759 971 1759 981 1759 997 1760 975 1760 976 1760 998 1761 978 1761 960 1761 999 1762 973 1762 947 1762 998 1763 960 1763 988 1763 999 1764 1000 1764 962 1764 999 1765 962 1765 973 1765 999 1766 947 1766 980 1766 1001 1767 982 1767 975 1767 1001 1768 975 1768 997 1768 1002 1769 981 1769 966 1769 1002 1770 966 1770 993 1770 1003 1771 985 1771 982 1771 1003 1772 982 1772 1001 1772 1004 1773 988 1773 991 1773 1004 1774 991 1774 1005 1774 1006 1775 1007 1775 986 1775 1006 1776 984 1776 996 1776 1008 1777 989 1777 985 1777 1009 1778 980 1778 994 1778 1006 1779 986 1779 984 1779 1009 1780 1000 1780 999 1780 1009 1781 999 1781 980 1781 1010 1782 993 1782 978 1782 1011 1783 969 1783 989 1783 1010 1784 978 1784 998 1784 1011 1785 989 1785 1008 1785 1011 1786 994 1786 969 1786 1012 1787 996 1787 981 1787 1013 1788 997 1788 976 1788 1012 1789 981 1789 1002 1789 1012 1790 1006 1790 996 1790 1013 1791 976 1791 1014 1791 1015 1792 988 1792 1004 1792 1016 1793 1001 1793 997 1793 1015 1794 998 1794 988 1794 1016 1795 997 1795 1013 1795 1017 1796 1003 1796 1001 1796 1018 1797 1002 1797 993 1797 1017 1798 1001 1798 1016 1798 1018 1799 993 1799 1010 1799 1019 1800 1015 1800 1004 1800 1020 1801 985 1801 1003 1801 1020 1802 1008 1802 985 1802 1019 1803 1004 1803 1005 1803 1021 1804 1007 1804 1006 1804 1022 1805 1013 1805 1014 1805 1021 1806 1006 1806 1012 1806 1023 1807 1010 1807 998 1807 1024 1808 1011 1808 1008 1808 1024 1809 1008 1809 1020 1809 1023 1810 998 1810 1015 1810 1025 1811 1009 1811 994 1811 1025 1812 1026 1812 1000 1812 1025 1813 1000 1813 1009 1813 1027 1814 1012 1814 1002 1814 1025 1815 994 1815 1011 1815 1025 1816 1011 1816 1024 1816 1027 1817 1002 1817 1018 1817 1028 1818 1016 1818 1013 1818 1029 1819 1015 1819 1019 1819 1029 1820 1023 1820 1015 1820 1030 1821 1017 1821 1016 1821 1030 1822 1016 1822 1028 1822 1031 1823 1018 1823 1010 1823 1032 1824 1003 1824 1017 1824 1031 1825 1010 1825 1023 1825 1032 1826 1020 1826 1003 1826 1033 1827 1034 1827 1035 1827 1033 1828 1005 1828 1034 1828 1033 1829 1019 1829 1005 1829 1036 1830 1024 1830 1020 1830 1037 1831 1038 1831 1007 1831 1037 1832 1012 1832 1027 1832 1037 1833 1007 1833 1021 1833 1037 1834 1021 1834 1012 1834 1039 1835 1013 1835 1022 1835 1039 1836 1028 1836 1013 1836 1040 1837 1023 1837 1029 1837 1040 1838 1031 1838 1023 1838 1041 1839 1026 1839 1025 1839 1041 1840 1025 1840 1024 1840 1042 1841 1027 1841 1018 1841 1043 1842 1014 1842 1044 1842 1042 1843 1018 1843 1031 1843 1043 1844 1022 1844 1014 1844 1045 1845 1029 1845 1019 1845 1046 1846 1030 1846 1028 1846 1047 1847 1032 1847 1017 1847 1045 1848 1019 1848 1033 1848 1047 1849 1017 1849 1030 1849 1048 1850 1042 1850 1031 1850 1048 1851 1031 1851 1040 1851 1049 1852 1045 1852 1033 1852 1049 1853 1033 1853 1035 1853 218 1854 1043 1854 1044 1854 1050 1855 1051 1855 1038 1855 1052 1856 1020 1856 1032 1856 1052 1857 1032 1857 1047 1857 1050 1858 1037 1858 1027 1858 1050 1859 1038 1859 1037 1859 1052 1860 1036 1860 1020 1860 1050 1861 1027 1861 1042 1861 1053 1862 1054 1862 1026 1862 1053 1863 1026 1863 1041 1863 1053 1864 1024 1864 1036 1864 1053 1865 1041 1865 1024 1865 1055 1866 1040 1866 1029 1866 1055 1867 1029 1867 1045 1867 1056 1868 1028 1868 1039 1868 1056 1869 1046 1869 1028 1869 1057 1870 1049 1870 1035 1870 1057 1871 1035 1871 1058 1871 1059 1872 1039 1872 1022 1872 239 1873 1042 1873 1048 1873 239 1874 1050 1874 1042 1874 1059 1875 1022 1875 1043 1875 1059 1876 1043 1876 218 1876 1060 1877 1045 1877 1049 1877 226 1878 1030 1878 1046 1878 1060 1879 1049 1879 1057 1879 226 1880 1047 1880 1030 1880 1060 1881 1055 1881 1045 1881 221 1882 1048 1882 1040 1882 221 1883 1040 1883 1055 1883 1061 1884 1052 1884 1047 1884 216 1885 1059 1885 218 1885 211 1886 1060 1886 1057 1886 1062 1887 1054 1887 1053 1887 212 1888 1057 1888 1058 1888 1062 1889 1036 1889 1052 1889 212 1890 211 1890 1057 1890 1062 1891 1053 1891 1036 1891 238 1892 237 1892 1051 1892 219 1893 1044 1893 241 1893 238 1894 1051 1894 1050 1894 219 1895 218 1895 1044 1895 238 1896 1050 1896 239 1896 229 1897 226 1897 1046 1897 222 1898 1055 1898 1060 1898 222 1899 221 1899 1055 1899 222 1900 1060 1900 211 1900 229 1901 1046 1901 1056 1901 213 1902 212 1902 1058 1902 215 1903 1059 1903 216 1903 215 1904 229 1904 1056 1904 213 1905 1058 1905 228 1905 215 1906 1039 1906 1059 1906 215 1907 1056 1907 1039 1907 223 1908 239 1908 1048 1908 234 1909 1052 1909 1061 1909 223 1910 1048 1910 221 1910 234 1911 1054 1911 1062 1911 234 1912 233 1912 1054 1912 234 1913 1062 1913 1052 1913 225 1914 1047 1914 226 1914 225 1915 1061 1915 1047 1915 225 1916 234 1916 1061 1916 210 1917 222 1917 211 1917 1063 1918 1064 1918 1065 1918 1066 1919 1067 1919 1068 1919 1067 1920 1069 1920 1068 1920 1070 1921 1071 1921 1072 1921 1071 1922 1073 1922 1072 1922 1074 1923 1075 1923 1076 1923 1077 1924 1078 1924 1079 1924 1080 1925 1066 1925 1081 1925 1065 1926 1082 1926 1079 1926 1083 1927 1077 1927 1079 1927 1082 1928 1084 1928 1079 1928 1084 1929 1083 1929 1079 1929 1075 1930 1085 1930 1086 1930 1066 1931 1068 1931 1081 1931 1076 1932 1075 1932 1086 1932 1087 1933 1088 1933 1089 1933 1088 1934 1080 1934 1089 1934 1069 1935 1090 1935 1091 1935 1092 1936 1093 1936 1094 1936 1090 1937 1095 1937 1091 1937 1068 1938 1069 1938 1091 1938 1096 1939 1092 1939 1094 1939 1095 1940 1097 1940 1091 1940 1072 1941 1073 1941 1098 1941 1093 1942 1074 1942 1099 1942 1074 1943 1076 1943 1099 1943 1094 1944 1093 1944 1099 1944 1073 1945 1087 1945 1098 1945 1100 1946 1070 1946 1101 1946 1102 1947 1096 1947 1103 1947 1070 1948 1072 1948 1101 1948 1086 1949 1085 1949 1104 1949 1081 1950 1068 1950 1105 1950 1085 1951 1063 1951 1104 1951 1068 1952 1091 1952 1105 1952 1063 1953 1065 1953 1104 1953 1065 1954 1079 1954 1106 1954 1080 1955 1081 1955 1107 1955 1079 1956 1078 1956 1106 1956 1089 1957 1080 1957 1107 1957 1096 1958 1094 1958 1108 1958 1103 1959 1096 1959 1108 1959 1098 1960 1087 1960 1109 1960 1076 1961 1086 1961 1110 1961 1099 1962 1076 1962 1110 1962 1087 1963 1089 1963 1109 1963 1091 1964 1097 1964 1111 1964 1086 1965 1104 1965 1112 1965 1105 1966 1091 1966 1111 1966 1110 1967 1086 1967 1112 1967 1097 1968 1113 1968 1111 1968 1101 1969 1072 1969 1114 1969 1094 1970 1099 1970 1115 1970 1099 1971 1110 1971 1116 1971 1072 1972 1098 1972 1114 1972 1101 1973 1114 1973 1117 1973 1115 1974 1099 1974 1116 1974 1078 1975 1118 1975 1119 1975 1106 1976 1078 1976 1119 1976 1104 1977 1065 1977 1119 1977 1100 1978 1101 1978 1117 1978 1065 1979 1106 1979 1119 1979 1112 1980 1104 1980 1119 1980 1107 1981 1081 1981 1120 1981 1103 1982 1108 1982 1121 1982 1081 1983 1105 1983 1120 1983 1109 1984 1089 1984 1122 1984 1089 1985 1107 1985 1122 1985 1108 1986 1094 1986 1123 1986 1094 1987 1115 1987 1123 1987 1098 1988 1109 1988 1124 1988 1125 1989 1102 1989 1126 1989 1127 1990 1125 1990 1126 1990 1102 1991 1103 1991 1126 1991 1114 1992 1098 1992 1124 1992 1120 1993 1105 1993 1128 1993 1105 1994 1111 1994 1128 1994 1111 1995 1113 1995 1128 1995 1113 1996 1129 1996 1128 1996 1110 1997 1112 1997 1130 1997 1112 1998 1119 1998 1131 1998 1114 1999 1124 1999 1132 1999 1130 2000 1112 2000 1131 2000 1119 2001 1118 2001 1131 2001 1115 2002 1116 2002 1133 2002 1117 2003 1114 2003 1132 2003 1107 2004 1120 2004 1134 2004 1123 2005 1115 2005 1133 2005 1122 2006 1107 2006 1134 2006 1110 2007 1130 2007 1135 2007 1116 2008 1110 2008 1135 2008 1133 2009 1116 2009 1135 2009 1100 2010 1117 2010 1136 2010 1137 2011 1100 2011 1136 2011 1138 2012 1137 2012 1136 2012 1121 2013 1108 2013 1139 2013 1108 2014 1123 2014 1139 2014 1109 2015 1122 2015 1140 2015 1124 2016 1109 2016 1140 2016 1123 2017 1133 2017 1141 2017 1139 2018 1123 2018 1141 2018 1118 2019 1142 2019 1143 2019 1132 2020 1124 2020 1144 2020 1131 2021 1118 2021 1143 2021 1130 2022 1131 2022 1143 2022 1124 2023 1140 2023 1144 2023 1135 2024 1130 2024 1143 2024 1103 2025 1121 2025 1145 2025 1134 2026 1120 2026 1146 2026 1120 2027 1128 2027 1146 2027 1126 2028 1103 2028 1145 2028 1128 2029 1129 2029 1146 2029 1129 2030 1147 2030 1146 2030 1135 2031 1143 2031 1148 2031 1136 2032 1117 2032 1149 2032 1143 2033 1142 2033 1148 2033 1133 2034 1135 2034 1150 2034 1117 2035 1132 2035 1149 2035 1135 2036 1148 2036 1150 2036 1127 2037 1126 2037 1151 2037 1126 2038 1145 2038 1151 2038 1152 2039 1127 2039 1151 2039 1140 2040 1122 2040 1153 2040 1122 2041 1134 2041 1153 2041 1138 2042 1136 2042 1154 2042 1139 2043 1141 2043 1155 2043 1136 2044 1149 2044 1154 2044 1141 2045 1133 2045 1156 2045 1144 2046 1140 2046 1157 2046 1133 2047 1150 2047 1156 2047 1145 2048 1121 2048 1158 2048 1140 2049 1153 2049 1157 2049 1121 2050 1139 2050 1158 2050 1132 2051 1144 2051 1159 2051 1149 2052 1132 2052 1159 2052 1142 2053 1160 2053 1161 2053 1150 2054 1148 2054 1161 2054 1148 2055 1142 2055 1161 2055 1134 2056 1146 2056 1162 2056 1145 2057 1158 2057 1163 2057 1147 2058 1164 2058 1162 2058 1153 2059 1134 2059 1162 2059 1151 2060 1145 2060 1163 2060 1146 2061 1147 2061 1162 2061 1156 2062 1150 2062 1165 2062 1161 2063 1160 2063 1165 2063 1154 2064 1149 2064 1166 2064 1149 2065 1159 2065 1166 2065 1150 2066 1161 2066 1165 2066 1155 2067 1141 2067 1167 2067 1157 2068 1153 2068 1168 2068 1141 2069 1156 2069 1167 2069 1153 2070 1162 2070 1168 2070 1156 2071 1165 2071 1167 2071 1138 2072 1154 2072 1169 2072 1170 2073 1138 2073 1169 2073 1171 2074 1152 2074 1172 2074 1173 2075 1170 2075 1169 2075 1174 2076 1173 2076 1169 2076 1152 2077 1151 2077 1172 2077 1175 2078 1174 2078 1169 2078 1144 2079 1157 2079 1176 2079 1159 2080 1144 2080 1176 2080 1139 2081 1155 2081 1177 2081 1158 2082 1139 2082 1177 2082 1159 2083 1176 2083 1178 2083 1163 2084 1158 2084 1179 2084 1166 2085 1159 2085 1178 2085 1158 2086 1177 2086 1179 2086 1164 2087 1180 2087 1181 2087 1160 2088 1182 2088 1183 2088 1165 2089 1160 2089 1183 2089 1168 2090 1162 2090 1181 2090 1162 2091 1164 2091 1181 2091 1167 2092 1165 2092 1183 2092 1154 2093 1166 2093 1184 2093 1175 2094 1169 2094 1184 2094 1151 2095 1163 2095 1185 2095 1169 2096 1154 2096 1184 2096 1157 2097 1168 2097 1186 2097 1172 2098 1151 2098 1185 2098 1176 2099 1157 2099 1186 2099 1155 2100 1167 2100 1187 2100 1177 2101 1155 2101 1187 2101 1178 2102 1176 2102 1188 2102 1189 2103 1171 2103 1190 2103 1176 2104 1186 2104 1188 2104 1171 2105 1172 2105 1190 2105 1166 2106 1178 2106 1191 2106 1175 2107 1184 2107 1191 2107 1192 2108 1175 2108 1191 2108 1193 2109 1192 2109 1191 2109 1184 2110 1166 2110 1191 2110 1168 2111 1181 2111 1194 2111 1179 2112 1177 2112 1195 2112 1180 2113 1196 2113 1194 2113 1177 2114 1187 2114 1195 2114 1181 2115 1180 2115 1194 2115 1186 2116 1168 2116 1194 2116 1188 2117 1186 2117 1197 2117 1163 2118 1179 2118 1198 2118 1185 2119 1163 2119 1198 2119 1186 2120 1194 2120 1197 2120 1178 2121 1188 2121 1199 2121 1182 2122 1200 2122 1201 2122 1191 2123 1178 2123 1199 2123 1187 2124 1167 2124 1201 2124 1193 2125 1191 2125 1199 2125 1183 2126 1182 2126 1201 2126 1167 2127 1183 2127 1201 2127 1194 2128 1196 2128 1202 2128 1197 2129 1194 2129 1202 2129 1172 2130 1185 2130 1203 2130 1196 2131 1204 2131 1202 2131 1190 2132 1172 2132 1203 2132 1188 2133 1197 2133 1205 2133 1197 2134 1202 2134 1205 2134 1193 2135 1199 2135 1205 2135 1206 2136 1193 2136 1205 2136 1207 2137 1206 2137 1205 2137 1189 2138 1190 2138 1208 2138 1199 2139 1188 2139 1205 2139 1209 2140 1207 2140 1210 2140 1205 2141 1202 2141 1210 2141 1190 2142 1203 2142 1208 2142 1207 2143 1205 2143 1210 2143 1202 2144 1204 2144 1210 2144 1204 2145 1209 2145 1210 2145 1195 2146 1187 2146 1211 2146 1198 2147 1179 2147 1212 2147 1179 2148 1195 2148 1212 2148 1185 2149 1198 2149 1213 2149 1203 2150 1185 2150 1213 2150 1200 2151 1214 2151 1215 2151 1211 2152 1187 2152 1215 2152 1201 2153 1200 2153 1215 2153 1187 2154 1201 2154 1215 2154 1208 2155 1203 2155 1216 2155 1203 2156 1213 2156 1216 2156 1217 2157 1189 2157 1218 2157 1219 2158 1217 2158 1218 2158 1189 2159 1208 2159 1218 2159 1195 2160 1211 2160 1220 2160 1212 2161 1195 2161 1220 2161 1198 2162 1212 2162 1221 2162 1213 2163 1198 2163 1221 2163 1216 2164 1213 2164 1222 2164 1213 2165 1221 2165 1222 2165 1214 2166 1223 2166 1224 2166 1215 2167 1214 2167 1224 2167 1211 2168 1215 2168 1224 2168 1220 2169 1211 2169 1224 2169 1208 2170 1216 2170 1225 2170 1218 2171 1208 2171 1225 2171 1226 2172 1219 2172 1227 2172 1219 2173 1218 2173 1227 2173 1221 2174 1212 2174 1228 2174 1212 2175 1220 2175 1228 2175 1221 2176 1228 2176 1229 2176 1222 2177 1221 2177 1229 2177 1216 2178 1222 2178 1230 2178 1225 2179 1216 2179 1230 2179 1223 2180 1231 2180 1232 2180 1220 2181 1224 2181 1232 2181 1228 2182 1220 2182 1232 2182 1224 2183 1223 2183 1232 2183 1218 2184 1225 2184 1233 2184 1227 2185 1218 2185 1233 2185 1227 2186 1233 2186 1234 2186 1226 2187 1227 2187 1234 2187 1229 2188 1228 2188 1235 2188 1228 2189 1232 2189 1235 2189 1230 2190 1222 2190 1236 2190 1222 2191 1229 2191 1236 2191 1225 2192 1230 2192 1237 2192 1233 2193 1225 2193 1237 2193 1231 2194 1238 2194 1239 2194 1232 2195 1231 2195 1239 2195 1235 2196 1232 2196 1239 2196 1233 2197 1237 2197 1240 2197 1234 2198 1233 2198 1240 2198 1241 2199 1226 2199 1242 2199 1226 2200 1234 2200 1242 2200 1236 2201 1229 2201 1243 2201 1229 2202 1235 2202 1243 2202 1230 2203 1236 2203 1244 2203 1237 2204 1230 2204 1244 2204 1240 2205 1237 2205 1245 2205 1237 2206 1244 2206 1245 2206 1238 2207 1246 2207 1247 2207 1239 2208 1238 2208 1247 2208 1235 2209 1239 2209 1247 2209 1243 2210 1235 2210 1247 2210 1234 2211 1240 2211 1248 2211 1242 2212 1234 2212 1248 2212 1249 2213 1241 2213 1250 2213 1241 2214 1242 2214 1250 2214 1244 2215 1236 2215 1251 2215 1236 2216 1243 2216 1251 2216 1245 2217 1244 2217 1252 2217 1244 2218 1251 2218 1252 2218 1240 2219 1245 2219 1253 2219 1248 2220 1240 2220 1253 2220 1246 2221 1254 2221 1255 2221 1247 2222 1246 2222 1255 2222 1243 2223 1247 2223 1255 2223 1251 2224 1243 2224 1255 2224 1242 2225 1248 2225 1256 2225 1250 2226 1242 2226 1256 2226 1257 2227 1249 2227 1258 2227 1249 2228 1250 2228 1258 2228 1251 2229 1255 2229 1259 2229 1252 2230 1251 2230 1259 2230 1245 2231 1252 2231 1260 2231 1253 2232 1245 2232 1260 2232 1248 2233 1253 2233 1261 2233 1256 2234 1248 2234 1261 2234 1255 2235 1254 2235 1262 2235 1259 2236 1255 2236 1262 2236 1254 2237 1263 2237 1262 2237 1258 2238 1250 2238 1264 2238 1250 2239 1256 2239 1264 2239 1265 2240 1257 2240 1266 2240 1257 2241 1258 2241 1266 2241 1252 2242 1259 2242 1267 2242 1260 2243 1252 2243 1267 2243 1261 2244 1253 2244 1268 2244 1253 2245 1260 2245 1268 2245 1256 2246 1261 2246 1269 2246 1264 2247 1256 2247 1269 2247 1267 2248 1259 2248 1270 2248 1259 2249 1262 2249 1270 2249 1262 2250 1263 2250 1270 2250 1263 2251 1271 2251 1270 2251 1266 2252 1258 2252 1272 2252 1258 2253 1264 2253 1272 2253 1265 2254 1266 2254 1273 2254 1274 2255 1265 2255 1273 2255 1268 2256 1260 2256 1275 2256 1260 2257 1267 2257 1275 2257 1261 2258 1268 2258 1276 2258 1269 2259 1261 2259 1276 2259 1264 2260 1269 2260 1277 2260 1272 2261 1264 2261 1277 2261 1267 2262 1270 2262 1278 2262 1275 2263 1267 2263 1278 2263 1270 2264 1271 2264 1278 2264 1271 2265 1279 2265 1278 2265 1273 2266 1266 2266 1280 2266 1266 2267 1272 2267 1280 2267 1274 2268 1273 2268 1281 2268 1282 2269 1274 2269 1281 2269 1268 2270 1275 2270 1283 2270 1276 2271 1268 2271 1283 2271 1277 2272 1269 2272 1284 2272 1269 2273 1276 2273 1284 2273 1280 2274 1272 2274 1285 2274 1272 2275 1277 2275 1285 2275 1275 2276 1278 2276 1286 2276 1283 2277 1275 2277 1286 2277 1278 2278 1279 2278 1286 2278 1279 2279 1287 2279 1286 2279 1273 2280 1280 2280 1288 2280 1281 2281 1273 2281 1288 2281 1289 2282 1282 2282 1290 2282 1282 2283 1281 2283 1290 2283 1281 2284 1288 2284 1290 2284 1276 2285 1283 2285 1291 2285 1284 2286 1276 2286 1291 2286 1277 2287 1284 2287 1292 2287 1285 2288 1277 2288 1292 2288 1288 2289 1280 2289 1293 2289 1280 2290 1285 2290 1293 2290 1283 2291 1286 2291 1294 2291 1291 2292 1283 2292 1294 2292 1286 2293 1287 2293 1294 2293 1287 2294 1295 2294 1294 2294 1288 2295 1293 2295 1296 2295 1290 2296 1288 2296 1296 2296 1289 2297 1290 2297 1297 2297 1298 2298 1289 2298 1297 2298 1284 2299 1291 2299 1299 2299 1292 2300 1284 2300 1299 2300 1285 2301 1292 2301 1300 2301 1293 2302 1285 2302 1300 2302 1207 2303 1209 2303 1301 2303 1302 2304 1173 2304 1303 2304 1293 2305 1300 2305 1304 2305 1173 2306 1174 2306 1303 2306 1296 2307 1293 2307 1304 2307 1291 2308 1294 2308 1305 2308 1299 2309 1291 2309 1305 2309 1294 2310 1295 2310 1305 2310 1174 2311 1175 2311 1306 2311 1295 2312 1307 2312 1305 2312 1297 2313 1290 2313 1308 2313 1303 2314 1174 2314 1306 2314 1309 2315 1302 2315 1310 2315 1290 2316 1296 2316 1308 2316 1302 2317 1303 2317 1310 2317 1298 2318 1297 2318 1311 2318 1312 2319 1298 2319 1311 2319 1306 2320 1175 2320 1313 2320 1175 2321 1192 2321 1313 2321 1292 2322 1299 2322 1314 2322 1300 2323 1292 2323 1314 2323 1303 2324 1306 2324 1315 2324 1304 2325 1300 2325 1316 2325 1310 2326 1303 2326 1315 2326 1317 2327 1309 2327 1318 2327 1300 2328 1314 2328 1316 2328 1296 2329 1304 2329 1319 2329 1309 2330 1310 2330 1318 2330 1308 2331 1296 2331 1319 2331 1299 2332 1305 2332 1320 2332 1314 2333 1299 2333 1320 2333 1192 2334 1193 2334 1321 2334 1305 2335 1307 2335 1320 2335 1313 2336 1192 2336 1321 2336 1307 2337 1322 2337 1320 2337 1297 2338 1308 2338 1323 2338 1306 2339 1313 2339 1324 2339 1315 2340 1306 2340 1324 2340 1311 2341 1297 2341 1323 2341 1312 2342 1311 2342 1325 2342 1310 2343 1315 2343 1326 2343 1318 2344 1310 2344 1326 2344 1327 2345 1312 2345 1325 2345 1311 2346 1323 2346 1325 2346 1328 2347 1317 2347 1329 2347 1316 2348 1314 2348 1330 2348 1317 2349 1318 2349 1329 2349 1314 2350 1320 2350 1330 2350 1304 2351 1316 2351 1331 2351 1319 2352 1304 2352 1331 2352 1193 2353 1206 2353 1332 2353 1206 2354 1207 2354 1332 2354 1321 2355 1193 2355 1332 2355 1323 2356 1308 2356 1333 2356 1324 2357 1313 2357 1334 2357 1308 2358 1319 2358 1333 2358 1313 2359 1321 2359 1334 2359 1320 2360 1322 2360 1335 2360 1330 2361 1320 2361 1335 2361 1322 2362 1336 2362 1335 2362 1315 2363 1324 2363 1337 2363 1323 2364 1333 2364 1338 2364 1326 2365 1315 2365 1337 2365 1325 2366 1323 2366 1338 2366 1332 2367 1207 2367 1339 2367 1301 2368 1340 2368 1339 2368 1207 2369 1301 2369 1339 2369 1327 2370 1325 2370 1341 2370 1342 2371 1327 2371 1341 2371 1329 2372 1318 2372 1343 2372 1325 2373 1338 2373 1341 2373 1318 2374 1326 2374 1343 2374 1331 2375 1316 2375 1344 2375 1345 2376 1328 2376 1346 2376 1316 2377 1330 2377 1344 2377 1328 2378 1329 2378 1346 2378 1329 2379 1343 2379 1346 2379 1319 2380 1331 2380 1347 2380 1321 2381 1332 2381 1348 2381 1333 2382 1319 2382 1347 2382 1334 2383 1321 2383 1348 2383 1337 2384 1324 2384 1349 2384 1342 2385 1341 2385 1350 2385 1324 2386 1334 2386 1349 2386 1338 2387 1333 2387 1351 2387 1333 2388 1347 2388 1351 2388 1326 2389 1337 2389 1352 2389 1344 2390 1330 2390 1353 2390 1330 2391 1335 2391 1353 2391 1343 2392 1326 2392 1352 2392 1335 2393 1336 2393 1353 2393 1339 2394 1340 2394 1354 2394 1340 2395 1355 2395 1354 2395 1336 2396 1356 2396 1353 2396 1332 2397 1339 2397 1354 2397 1341 2398 1338 2398 1357 2398 1348 2399 1332 2399 1354 2399 1338 2400 1351 2400 1357 2400 1350 2401 1341 2401 1357 2401 1346 2402 1343 2402 1358 2402 1343 2403 1352 2403 1358 2403 1359 2404 1342 2404 1360 2404 1361 2405 1345 2405 1362 2405 1342 2406 1350 2406 1360 2406 1331 2407 1344 2407 1363 2407 1345 2408 1346 2408 1362 2408 1347 2409 1331 2409 1363 2409 1334 2410 1348 2410 1364 2410 1349 2411 1334 2411 1364 2411 1348 2412 1354 2412 1364 2412 1350 2413 1357 2413 1365 2413 1360 2414 1350 2414 1365 2414 1347 2415 1363 2415 1366 2415 1352 2416 1337 2416 1367 2416 1351 2417 1347 2417 1366 2417 1337 2418 1349 2418 1367 2418 1359 2419 1360 2419 1368 2419 1352 2420 1367 2420 1369 2420 1358 2421 1352 2421 1369 2421 1355 2422 1370 2422 1371 2422 1364 2423 1354 2423 1371 2423 1351 2424 1366 2424 1372 2424 1354 2425 1355 2425 1371 2425 1357 2426 1351 2426 1372 2426 1365 2427 1357 2427 1372 2427 1362 2428 1346 2428 1373 2428 1344 2429 1353 2429 1374 2429 1346 2430 1358 2430 1373 2430 1363 2431 1344 2431 1374 2431 1375 2432 1361 2432 1376 2432 1353 2433 1356 2433 1374 2433 1356 2434 1377 2434 1374 2434 1361 2435 1362 2435 1376 2435 1362 2436 1373 2436 1376 2436 1360 2437 1365 2437 1378 2437 1367 2438 1349 2438 1379 2438 1365 2439 1372 2439 1380 2439 1349 2440 1364 2440 1379 2440 1378 2441 1365 2441 1380 2441 1381 2442 1359 2442 1382 2442 1367 2443 1379 2443 1383 2443 1359 2444 1368 2444 1382 2444 1369 2445 1367 2445 1383 2445 1363 2446 1374 2446 1384 2446 1366 2447 1363 2447 1384 2447 1373 2448 1358 2448 1385 2448 1358 2449 1369 2449 1385 2449 1370 2450 1386 2450 1387 2450 1360 2451 1378 2451 1388 2451 1379 2452 1364 2452 1387 2452 1368 2453 1360 2453 1388 2453 1371 2454 1370 2454 1387 2454 1364 2455 1371 2455 1387 2455 1376 2456 1373 2456 1389 2456 1382 2457 1368 2457 1388 2457 1373 2458 1385 2458 1389 2458 1372 2459 1366 2459 1390 2459 1366 2460 1384 2460 1390 2460 1391 2461 1375 2461 1392 2461 1380 2462 1372 2462 1390 2462 1375 2463 1376 2463 1392 2463 1381 2464 1382 2464 1393 2464 1379 2465 1387 2465 1394 2465 1383 2466 1379 2466 1394 2466 1385 2467 1369 2467 1395 2467 1378 2468 1380 2468 1396 2468 1396 2469 1380 2469 1397 2469 1369 2470 1383 2470 1395 2470 1380 2471 1390 2471 1397 2471 1384 2472 1374 2472 1398 2472 1385 2473 1395 2473 1399 2473 1389 2474 1385 2474 1399 2474 1377 2475 1400 2475 1398 2475 1374 2476 1377 2476 1398 2476 1386 2477 1401 2477 1402 2477 1387 2478 1386 2478 1402 2478 1394 2479 1387 2479 1402 2479 1382 2480 1388 2480 1403 2480 1376 2481 1389 2481 1404 2481 1378 2482 1396 2482 1405 2482 1392 2483 1376 2483 1404 2483 1403 2484 1388 2484 1405 2484 1388 2485 1378 2485 1405 2485 1406 2486 1391 2486 1407 2486 1381 2487 1393 2487 1408 2487 1392 2488 1404 2488 1407 2488 1409 2489 1381 2489 1408 2489 1391 2490 1392 2490 1407 2490 1390 2491 1384 2491 1410 2491 1384 2492 1398 2492 1410 2492 1383 2493 1394 2493 1411 2493 1397 2494 1390 2494 1410 2494 1395 2495 1383 2495 1411 2495 1382 2496 1403 2496 1412 2496 1395 2497 1411 2497 1413 2497 1399 2498 1395 2498 1413 2498 1393 2499 1382 2499 1412 2499 1396 2500 1397 2500 1414 2500 1389 2501 1399 2501 1415 2501 1404 2502 1389 2502 1415 2502 1409 2503 1408 2503 1416 2503 1411 2504 1394 2504 1417 2504 1401 2505 1418 2505 1417 2505 1402 2506 1401 2506 1417 2506 1414 2507 1397 2507 1419 2507 1394 2508 1402 2508 1417 2508 1397 2509 1410 2509 1419 2509 1404 2510 1415 2510 1420 2510 1407 2511 1404 2511 1420 2511 1421 2512 1406 2512 1422 2512 1403 2513 1405 2513 1423 2513 1423 2514 1405 2514 1424 2514 1405 2515 1396 2515 1424 2515 1396 2516 1414 2516 1424 2516 1406 2517 1407 2517 1422 2517 1413 2518 1411 2518 1425 2518 1410 2519 1398 2519 1426 2519 1398 2520 1400 2520 1426 2520 1411 2521 1417 2521 1425 2521 1419 2522 1410 2522 1426 2522 1400 2523 1427 2523 1426 2523 1408 2524 1393 2524 1428 2524 1415 2525 1399 2525 1429 2525 1393 2526 1412 2526 1428 2526 1416 2527 1408 2527 1428 2527 1399 2528 1413 2528 1429 2528 1403 2529 1423 2529 1430 2529 1412 2530 1403 2530 1430 2530 1421 2531 1422 2531 1431 2531 1409 2532 1416 2532 1432 2532 1420 2533 1415 2533 1433 2533 1434 2534 1409 2534 1432 2534 1415 2535 1429 2535 1433 2535 1418 2536 1435 2536 1436 2536 1425 2537 1417 2537 1436 2537 1419 2538 1426 2538 1437 2538 1426 2539 1427 2539 1437 2539 1417 2540 1418 2540 1436 2540 1427 2541 1438 2541 1437 2541 1414 2542 1419 2542 1439 2542 1431 2543 1422 2543 1440 2543 1422 2544 1407 2544 1440 2544 1419 2545 1437 2545 1439 2545 1407 2546 1420 2546 1440 2546 1416 2547 1428 2547 1441 2547 1432 2548 1416 2548 1441 2548 1442 2549 1421 2549 1443 2549 1421 2550 1431 2550 1443 2550 1423 2551 1424 2551 1444 2551 1429 2552 1413 2552 1445 2552 1413 2553 1425 2553 1445 2553 1424 2554 1414 2554 1446 2554 1414 2555 1439 2555 1446 2555 1444 2556 1424 2556 1446 2556 1431 2557 1440 2557 1447 2557 1433 2558 1429 2558 1448 2558 1434 2559 1432 2559 1449 2559 1428 2560 1412 2560 1450 2560 1412 2561 1430 2561 1450 2561 1429 2562 1445 2562 1448 2562 1441 2563 1428 2563 1450 2563 1423 2564 1444 2564 1451 2564 1430 2565 1423 2565 1451 2565 1442 2566 1443 2566 1452 2566 1420 2567 1433 2567 1453 2567 1440 2568 1420 2568 1453 2568 1447 2569 1440 2569 1453 2569 1437 2570 1438 2570 1454 2570 1439 2571 1437 2571 1454 2571 1445 2572 1425 2572 1455 2572 1425 2573 1436 2573 1455 2573 1432 2574 1441 2574 1456 2574 1435 2575 1457 2575 1455 2575 1436 2576 1435 2576 1455 2576 1441 2577 1450 2577 1458 2577 1443 2578 1431 2578 1459 2578 1456 2579 1441 2579 1458 2579 1431 2580 1447 2580 1459 2580 1452 2581 1443 2581 1459 2581 1434 2582 1449 2582 1460 2582 1461 2583 1434 2583 1460 2583 1447 2584 1453 2584 1462 2584 1444 2585 1446 2585 1463 2585 1464 2586 1442 2586 1465 2586 1442 2587 1452 2587 1465 2587 1446 2588 1439 2588 1466 2588 1439 2589 1454 2589 1466 2589 1463 2590 1446 2590 1466 2590 1445 2591 1455 2591 1467 2591 1454 2592 1438 2592 1466 2592 1448 2593 1445 2593 1467 2593 1438 2594 1468 2594 1466 2594 1432 2595 1456 2595 1469 2595 1449 2596 1432 2596 1469 2596 1452 2597 1459 2597 1470 2597 1450 2598 1430 2598 1471 2598 1465 2599 1452 2599 1470 2599 1430 2600 1451 2600 1471 2600 1458 2601 1450 2601 1471 2601 1453 2602 1433 2602 1472 2602 1433 2603 1448 2603 1472 2603 1462 2604 1453 2604 1472 2604 1444 2605 1463 2605 1473 2605 1464 2606 1465 2606 1474 2606 1451 2607 1444 2607 1473 2607 1459 2608 1447 2608 1475 2608 1447 2609 1462 2609 1475 2609 1461 2610 1460 2610 1476 2610 1470 2611 1459 2611 1475 2611 1456 2612 1458 2612 1477 2612 1462 2613 1472 2613 1478 2613 1463 2614 1466 2614 1479 2614 1457 2615 1480 2615 1481 2615 1466 2616 1468 2616 1479 2616 1477 2617 1458 2617 1482 2617 1455 2618 1457 2618 1481 2618 1458 2619 1471 2619 1482 2619 1467 2620 1455 2620 1481 2620 1474 2621 1465 2621 1483 2621 1476 2622 1460 2622 1484 2622 1465 2623 1470 2623 1483 2623 1460 2624 1449 2624 1484 2624 1470 2625 1475 2625 1485 2625 1449 2626 1469 2626 1484 2626 1461 2627 1476 2627 1486 2627 1487 2628 1464 2628 1488 2628 1489 2629 1461 2629 1486 2629 1464 2630 1474 2630 1488 2630 1456 2631 1477 2631 1490 2631 1448 2632 1467 2632 1491 2632 1472 2633 1448 2633 1491 2633 1469 2634 1456 2634 1490 2634 1478 2635 1472 2635 1491 2635 1451 2636 1473 2636 1492 2636 1474 2637 1483 2637 1493 2637 1482 2638 1471 2638 1492 2638 1471 2639 1451 2639 1492 2639 1473 2640 1463 2640 1494 2640 1463 2641 1479 2641 1494 2641 1475 2642 1462 2642 1495 2642 1479 2643 1468 2643 1494 2643 1468 2644 1496 2644 1494 2644 1462 2645 1478 2645 1495 2645 1485 2646 1475 2646 1495 2646 1486 2647 1476 2647 1497 2647 1478 2648 1491 2648 1498 2648 1476 2649 1484 2649 1497 2649 1487 2650 1488 2650 1499 2650 1477 2651 1482 2651 1500 2651 1482 2652 1492 2652 1501 2652 1500 2653 1482 2653 1501 2653 1483 2654 1470 2654 1502 2654 1470 2655 1485 2655 1502 2655 1489 2656 1486 2656 1503 2656 1485 2657 1495 2657 1504 2657 1502 2658 1485 2658 1504 2658 1484 2659 1469 2659 1505 2659 1469 2660 1490 2660 1505 2660 1480 2661 1506 2661 1507 2661 1481 2662 1480 2662 1507 2662 1491 2663 1467 2663 1507 2663 1467 2664 1481 2664 1507 2664 1498 2665 1491 2665 1507 2665 1492 2666 1473 2666 1508 2666 1473 2667 1494 2667 1508 2667 1494 2668 1496 2668 1508 2668 1499 2669 1488 2669 1509 2669 1488 2670 1474 2670 1509 2670 1474 2671 1493 2671 1509 2671 1486 2672 1497 2672 1510 2672 1493 2673 1483 2673 1511 2673 1477 2674 1500 2674 1512 2674 1483 2675 1502 2675 1511 2675 1513 2676 1487 2676 1514 2676 1490 2677 1477 2677 1512 2677 1489 2678 1503 2678 1515 2678 1487 2679 1499 2679 1514 2679 1516 2680 1489 2680 1515 2680 1498 2681 1507 2681 1517 2681 1506 2682 1518 2682 1517 2682 1507 2683 1506 2683 1517 2683 1504 2684 1495 2684 1519 2684 1510 2685 1497 2685 1520 2685 1484 2686 1505 2686 1520 2686 1497 2687 1484 2687 1520 2687 1495 2688 1478 2688 1519 2688 1478 2689 1498 2689 1519 2689 1499 2690 1509 2690 1521 2690 1500 2691 1501 2691 1522 2691 1514 2692 1499 2692 1521 2692 1501 2693 1492 2693 1523 2693 1508 2694 1496 2694 1523 2694 1502 2695 1504 2695 1524 2695 1496 2696 1525 2696 1523 2696 1492 2697 1508 2697 1523 2697 1511 2698 1502 2698 1524 2698 1503 2699 1486 2699 1526 2699 1513 2700 1514 2700 1527 2700 1486 2701 1510 2701 1526 2701 1515 2702 1503 2702 1526 2702 1505 2703 1490 2703 1528 2703 1520 2704 1505 2704 1528 2704 1490 2705 1512 2705 1528 2705 1504 2706 1519 2706 1529 2706 1493 2707 1511 2707 1530 2707 1510 2708 1520 2708 1531 2708 1509 2709 1493 2709 1530 2709 1511 2710 1524 2710 1532 2710 1516 2711 1515 2711 1533 2711 1498 2712 1517 2712 1534 2712 1517 2713 1518 2713 1534 2713 1500 2714 1522 2714 1535 2714 1512 2715 1500 2715 1535 2715 1519 2716 1498 2716 1534 2716 1501 2717 1523 2717 1536 2717 1514 2718 1521 2718 1537 2718 1522 2719 1501 2719 1536 2719 1523 2720 1525 2720 1536 2720 1521 2721 1509 2721 1538 2721 1515 2722 1526 2722 1539 2722 1509 2723 1530 2723 1538 2723 1533 2724 1515 2724 1539 2724 1537 2725 1521 2725 1538 2725 1520 2726 1528 2726 1540 2726 1541 2727 1513 2727 1542 2727 1531 2728 1520 2728 1540 2728 1513 2729 1527 2729 1542 2729 1543 2730 1516 2730 1544 2730 1524 2731 1504 2731 1545 2731 1504 2732 1529 2732 1545 2732 1516 2733 1533 2733 1544 2733 1510 2734 1531 2734 1546 2734 1518 2735 1547 2735 1548 2735 1526 2736 1510 2736 1546 2736 1529 2737 1519 2737 1548 2737 1519 2738 1534 2738 1548 2738 1534 2739 1518 2739 1548 2739 1545 2740 1529 2740 1548 2740 1527 2741 1514 2741 1549 2741 1528 2742 1512 2742 1550 2742 1512 2743 1535 2743 1550 2743 1514 2744 1537 2744 1549 2744 1542 2745 1527 2745 1549 2745 1522 2746 1536 2746 1551 2746 1535 2747 1522 2747 1551 2747 1511 2748 1532 2748 1552 2748 1525 2749 1553 2749 1551 2749 1538 2750 1530 2750 1552 2750 1536 2751 1525 2751 1551 2751 1530 2752 1511 2752 1552 2752 1531 2753 1540 2753 1554 2753 1541 2754 1542 2754 1555 2754 1532 2755 1524 2755 1556 2755 1533 2756 1539 2756 1557 2756 1524 2757 1545 2757 1556 2757 1537 2758 1538 2758 1558 2758 1526 2759 1546 2759 1559 2759 1539 2760 1526 2760 1559 2760 1548 2761 1547 2761 1560 2761 1543 2762 1544 2762 1561 2762 1545 2763 1548 2763 1560 2763 1538 2764 1552 2764 1562 2764 1540 2765 1528 2765 1563 2765 1558 2766 1538 2766 1562 2766 1528 2767 1550 2767 1563 2767 1554 2768 1540 2768 1563 2768 1550 2769 1535 2769 1564 2769 1542 2770 1549 2770 1565 2770 1535 2771 1551 2771 1564 2771 1551 2772 1553 2772 1564 2772 1563 2773 1550 2773 1564 2773 1566 2774 1541 2774 1567 2774 1533 2775 1557 2775 1568 2775 1561 2776 1544 2776 1568 2776 1541 2777 1555 2777 1567 2777 1544 2778 1533 2778 1568 2778 1549 2779 1537 2779 1569 2779 1531 2780 1554 2780 1570 2780 1537 2781 1558 2781 1569 2781 1565 2782 1549 2782 1569 2782 1559 2783 1546 2783 1570 2783 1546 2784 1531 2784 1570 2784 1552 2785 1532 2785 1571 2785 1572 2786 1543 2786 1573 2786 1532 2787 1556 2787 1571 2787 1543 2788 1561 2788 1573 2788 1560 2789 1547 2789 1574 2789 1547 2790 1575 2790 1574 2790 1556 2791 1545 2791 1574 2791 1554 2792 1563 2792 1576 2792 1545 2793 1560 2793 1574 2793 1557 2794 1539 2794 1577 2794 1555 2795 1542 2795 1578 2795 1542 2796 1565 2796 1578 2796 1567 2797 1555 2797 1578 2797 1539 2798 1559 2798 1577 2798 1563 2799 1564 2799 1579 2799 1564 2800 1553 2800 1579 2800 1576 2801 1563 2801 1579 2801 1553 2802 1580 2802 1579 2802 1558 2803 1562 2803 1581 2803 1559 2804 1570 2804 1582 2804 1577 2805 1559 2805 1582 2805 1566 2806 1567 2806 1583 2806 1573 2807 1561 2807 1584 2807 1561 2808 1568 2808 1584 2808 1562 2809 1552 2809 1585 2809 1552 2810 1571 2810 1585 2810 1568 2811 1557 2811 1586 2811 1581 2812 1562 2812 1585 2812 1565 2813 1569 2813 1587 2813 1557 2814 1577 2814 1586 2814 1570 2815 1554 2815 1588 2815 1554 2816 1576 2816 1588 2816 1574 2817 1575 2817 1589 2817 1571 2818 1556 2818 1589 2818 1556 2819 1574 2819 1589 2819 1572 2820 1573 2820 1590 2820 1567 2821 1578 2821 1591 2821 1587 2822 1569 2822 1592 2822 1576 2823 1579 2823 1593 2823 1579 2824 1580 2824 1593 2824 1569 2825 1558 2825 1592 2825 1573 2826 1584 2826 1594 2826 1558 2827 1581 2827 1592 2827 1590 2828 1573 2828 1594 2828 1595 2829 1566 2829 1596 2829 1566 2830 1583 2830 1596 2830 1577 2831 1582 2831 1597 2831 1565 2832 1587 2832 1598 2832 1572 2833 1590 2833 1599 2833 1600 2834 1572 2834 1599 2834 1578 2835 1565 2835 1598 2835 1581 2836 1585 2836 1601 2836 1570 2837 1588 2837 1602 2837 1585 2838 1571 2838 1603 2838 1582 2839 1570 2839 1602 2839 1589 2840 1575 2840 1603 2840 1575 2841 1604 2841 1603 2841 1584 2842 1568 2842 1605 2842 1568 2843 1586 2843 1605 2843 1571 2844 1589 2844 1603 2844 1594 2845 1584 2845 1605 2845 1567 2846 1591 2846 1606 2846 1596 2847 1583 2847 1606 2847 1576 2848 1593 2848 1607 2848 1588 2849 1576 2849 1607 2849 1593 2850 1580 2850 1607 2850 1583 2851 1567 2851 1606 2851 1580 2852 1608 2852 1607 2852 1586 2853 1577 2853 1609 2853 1577 2854 1597 2854 1609 2854 1605 2855 1586 2855 1609 2855 1587 2856 1592 2856 1610 2856 1578 2857 1598 2857 1611 2857 1590 2858 1594 2858 1612 2858 1591 2859 1578 2859 1611 2859 1595 2860 1596 2860 1613 2860 1594 2861 1605 2861 1614 2861 1581 2862 1601 2862 1615 2862 1592 2863 1581 2863 1615 2863 1597 2864 1582 2864 1616 2864 1582 2865 1602 2865 1616 2865 1610 2866 1592 2866 1615 2866 1601 2867 1585 2867 1617 2867 1603 2868 1604 2868 1617 2868 1585 2869 1603 2869 1617 2869 1600 2870 1599 2870 1618 2870 1596 2871 1606 2871 1619 2871 1613 2872 1596 2872 1619 2872 1588 2873 1607 2873 1620 2873 1598 2874 1587 2874 1621 2874 1602 2875 1588 2875 1620 2875 1587 2876 1610 2876 1621 2876 1611 2877 1598 2877 1621 2877 1607 2878 1608 2878 1620 2878 1599 2879 1590 2879 1622 2879 1618 2880 1599 2880 1622 2880 1590 2881 1612 2881 1622 2881 1623 2882 1595 2882 1624 2882 1595 2883 1613 2883 1624 2883 1605 2884 1609 2884 1625 2884 1619 2885 1606 2885 1626 2885 1614 2886 1605 2886 1625 2886 1606 2887 1591 2887 1626 2887 1591 2888 1611 2888 1626 2888 1627 2889 1600 2889 1628 2889 1600 2890 1618 2890 1628 2890 1610 2891 1615 2891 1629 2891 1597 2892 1616 2892 1630 2892 1604 2893 1631 2893 1632 2893 1609 2894 1597 2894 1630 2894 1617 2895 1604 2895 1632 2895 1615 2896 1601 2896 1632 2896 1601 2897 1617 2897 1632 2897 1629 2898 1615 2898 1632 2898 1594 2899 1614 2899 1633 2899 1611 2900 1621 2900 1634 2900 1612 2901 1594 2901 1633 2901 1616 2902 1602 2902 1635 2902 1602 2903 1620 2903 1635 2903 1608 2904 1636 2904 1635 2904 1620 2905 1608 2905 1635 2905 1613 2906 1619 2906 1637 2906 1614 2907 1625 2907 1638 2907 1624 2908 1613 2908 1637 2908 1633 2909 1614 2909 1638 2909 1619 2910 1626 2910 1639 2910 1628 2911 1618 2911 1640 2911 1621 2912 1610 2912 1641 2912 1618 2913 1622 2913 1640 2913 1610 2914 1629 2914 1641 2914 1640 2915 1622 2915 1642 2915 1612 2916 1633 2916 1642 2916 1622 2917 1612 2917 1642 2917 1623 2918 1624 2918 1643 2918 1644 2919 1627 2919 1645 2919 1632 2920 1631 2920 1646 2920 1627 2921 1628 2921 1645 2921 1629 2922 1632 2922 1646 2922 1609 2923 1630 2923 1647 2923 1624 2924 1637 2924 1648 2924 1643 2925 1624 2925 1648 2925 1625 2926 1609 2926 1647 2926 1638 2927 1625 2927 1647 2927 1647 2928 1630 2928 1649 2928 1626 2929 1611 2929 1650 2929 1630 2930 1616 2930 1649 2930 1611 2931 1634 2931 1650 2931 1616 2932 1635 2932 1649 2932 1639 2933 1626 2933 1650 2933 1635 2934 1636 2934 1649 2934 1651 2935 1623 2935 1652 2935 1623 2936 1643 2936 1652 2936 1628 2937 1640 2937 1653 2937 1633 2938 1638 2938 1654 2938 1634 2939 1621 2939 1655 2939 1621 2940 1641 2940 1655 2940 1637 2941 1619 2941 1656 2941 1638 2942 1647 2942 1657 2942 1619 2943 1639 2943 1656 2943 1640 2944 1642 2944 1658 2944 1653 2945 1640 2945 1658 2945 1631 2946 1659 2946 1660 2946 1641 2947 1629 2947 1660 2947 1629 2948 1646 2948 1660 2948 1642 2949 1633 2949 1661 2949 1633 2950 1654 2950 1661 2950 1646 2951 1631 2951 1660 2951 1658 2952 1642 2952 1661 2952 1639 2953 1650 2953 1662 2953 1647 2954 1649 2954 1663 2954 1649 2955 1636 2955 1663 2955 1656 2956 1639 2956 1662 2956 1657 2957 1647 2957 1663 2957 1636 2958 1664 2958 1663 2958 1643 2959 1648 2959 1665 2959 1645 2960 1628 2960 1666 2960 1628 2961 1653 2961 1666 2961 1652 2962 1643 2962 1665 2962 1637 2963 1656 2963 1667 2963 1653 2964 1658 2964 1668 2964 1648 2965 1637 2965 1667 2965 1650 2966 1634 2966 1669 2966 1634 2967 1655 2967 1669 2967 1645 2968 1666 2968 1670 2968 1662 2969 1650 2969 1669 2969 1644 2970 1645 2970 1670 2970 1654 2971 1638 2971 1671 2971 1651 2972 1652 2972 1672 2972 1638 2973 1657 2973 1671 2973 1660 2974 1659 2974 1673 2974 1655 2975 1641 2975 1673 2975 1657 2976 1663 2976 1674 2976 1641 2977 1660 2977 1673 2977 1663 2978 1664 2978 1674 2978 1652 2979 1665 2979 1675 2979 1658 2980 1661 2980 1676 2980 1672 2981 1652 2981 1675 2981 1668 2982 1658 2982 1676 2982 1661 2983 1654 2983 1677 2983 1654 2984 1671 2984 1677 2984 1667 2985 1656 2985 1064 2985 1676 2986 1661 2986 1677 2986 1656 2987 1662 2987 1064 2987 1651 2988 1672 2988 1678 2988 1666 2989 1653 2989 1679 2989 1653 2990 1668 2990 1679 2990 1680 2991 1651 2991 1678 2991 1662 2992 1669 2992 1084 2992 1648 2993 1667 2993 1681 2993 1668 2994 1676 2994 1067 2994 1671 2995 1657 2995 1682 2995 1657 2996 1674 2996 1682 2996 1665 2997 1648 2997 1681 2997 1674 2998 1664 2998 1682 2998 1675 2999 1665 2999 1681 2999 1659 3000 1077 3000 1683 3000 1664 3001 1684 3001 1682 3001 1655 3002 1673 3002 1683 3002 1084 3003 1669 3003 1683 3003 1666 3004 1679 3004 1088 3004 1669 3005 1655 3005 1683 3005 1670 3006 1666 3006 1088 3006 1673 3007 1659 3007 1683 3007 1667 3008 1064 3008 1063 3008 1671 3009 1682 3009 1685 3009 1681 3010 1667 3010 1063 3010 1677 3011 1671 3011 1685 3011 1682 3012 1684 3012 1685 3012 1676 3013 1677 3013 1686 3013 1678 3014 1672 3014 1074 3014 1672 3015 1675 3015 1074 3015 1067 3016 1676 3016 1686 3016 1677 3017 1685 3017 1686 3017 1687 3018 1644 3018 1073 3018 1644 3019 1670 3019 1073 3019 1071 3020 1687 3020 1073 3020 1675 3021 1681 3021 1075 3021 1074 3022 1675 3022 1075 3022 1064 3023 1662 3023 1082 3023 1668 3024 1067 3024 1066 3024 1679 3025 1668 3025 1066 3025 1662 3026 1084 3026 1082 3026 1067 3027 1686 3027 1069 3027 1680 3028 1678 3028 1092 3028 1088 3029 1679 3029 1080 3029 1679 3030 1066 3030 1080 3030 1683 3031 1077 3031 1083 3031 1084 3032 1683 3032 1083 3032 1684 3033 1095 3033 1688 3033 1685 3034 1684 3034 1688 3034 1686 3035 1685 3035 1688 3035 1678 3036 1074 3036 1093 3036 1069 3037 1686 3037 1688 3037 1092 3038 1678 3038 1093 3038 1073 3039 1670 3039 1087 3039 1681 3040 1063 3040 1085 3040 1670 3041 1088 3041 1087 3041 1075 3042 1681 3042 1085 3042 1102 3043 1680 3043 1096 3043 1069 3044 1688 3044 1090 3044 1688 3045 1095 3045 1090 3045 1680 3046 1092 3046 1096 3046 1064 3047 1082 3047 1065 3047 594 3048 1689 3048 1690 3048 594 3049 570 3049 1689 3049 595 3050 1690 3050 1691 3050 595 3051 594 3051 1690 3051 622 3052 1691 3052 1692 3052 622 3053 595 3053 1691 3053 623 3054 1692 3054 1693 3054 623 3055 622 3055 1692 3055 654 3056 1693 3056 1694 3056 654 3057 623 3057 1693 3057 682 3058 1694 3058 1695 3058 682 3059 654 3059 1694 3059 719 3060 1695 3060 1696 3060 719 3061 682 3061 1695 3061 760 3062 1696 3062 1697 3062 760 3063 719 3063 1696 3063 805 3064 760 3064 1697 3064 805 3065 1697 3065 1698 3065 850 3066 1698 3066 1699 3066 850 3067 805 3067 1698 3067 896 3068 1699 3068 1700 3068 896 3069 850 3069 1699 3069 932 3070 1700 3070 1701 3070 932 3071 896 3071 1700 3071 964 3072 1701 3072 1702 3072 964 3073 932 3073 1701 3073 990 3074 1702 3074 1703 3074 990 3075 964 3075 1702 3075 991 3076 1703 3076 1704 3076 991 3077 990 3077 1703 3077 1005 3078 1704 3078 1705 3078 1005 3079 991 3079 1704 3079 1034 3080 1705 3080 1706 3080 1034 3081 1005 3081 1705 3081 1035 3082 1706 3082 1707 3082 1035 3083 1034 3083 1706 3083 1058 3084 1707 3084 1708 3084 1058 3085 1035 3085 1707 3085 228 3086 1708 3086 1709 3086 228 3087 1709 3087 1710 3087 228 3088 1058 3088 1708 3088 248 3089 1710 3089 1711 3089 248 3090 228 3090 1710 3090 275 3091 1711 3091 1712 3091 275 3092 248 3092 1711 3092 310 3093 1712 3093 1713 3093 310 3094 275 3094 1712 3094 338 3095 1713 3095 1714 3095 338 3096 310 3096 1713 3096 364 3097 1714 3097 1715 3097 364 3098 338 3098 1714 3098 386 3099 1715 3099 1716 3099 386 3100 364 3100 1715 3100 404 3101 1716 3101 1717 3101 404 3102 386 3102 1716 3102 418 3103 1717 3103 1718 3103 418 3104 404 3104 1717 3104 419 3105 1718 3105 1719 3105 419 3106 418 3106 1718 3106 449 3107 1719 3107 1720 3107 449 3108 419 3108 1719 3108 450 3109 1720 3109 1721 3109 450 3110 449 3110 1720 3110 471 3111 1721 3111 1722 3111 471 3112 450 3112 1721 3112 495 3113 471 3113 1722 3113 495 3114 1722 3114 1723 3114 519 3115 495 3115 1723 3115 519 3116 1723 3116 1724 3116 549 3117 519 3117 1724 3117 549 3118 1724 3118 1725 3118 582 3119 549 3119 1725 3119 582 3120 1725 3120 1726 3120 633 3121 582 3121 1726 3121 633 3122 1726 3122 1727 3122 672 3123 633 3123 1727 3123 672 3124 1727 3124 1728 3124 708 3125 672 3125 1728 3125 708 3126 1728 3126 1729 3126 742 3127 708 3127 1729 3127 742 3128 1729 3128 1730 3128 771 3129 742 3129 1730 3129 771 3130 1730 3130 1731 3130 792 3131 771 3131 1731 3131 792 3132 1731 3132 1732 3132 793 3133 792 3133 1732 3133 793 3134 1732 3134 1733 3134 817 3135 1733 3135 1734 3135 817 3136 793 3136 1733 3136 859 3137 817 3137 1734 3137 859 3138 1734 3138 1735 3138 871 3139 1735 3139 1736 3139 871 3140 859 3140 1735 3140 900 3141 1736 3141 1737 3141 900 3142 871 3142 1736 3142 935 3143 1737 3143 1738 3143 935 3144 900 3144 1737 3144 976 3145 1738 3145 1739 3145 976 3146 935 3146 1738 3146 1014 3147 1739 3147 1740 3147 1014 3148 976 3148 1739 3148 1044 3149 1740 3149 1741 3149 1044 3150 1014 3150 1740 3150 241 3151 1741 3151 1742 3151 241 3152 1044 3152 1741 3152 242 3153 1742 3153 1743 3153 242 3154 241 3154 1742 3154 264 3155 1743 3155 1744 3155 264 3156 242 3156 1743 3156 284 3157 1744 3157 1745 3157 284 3158 264 3158 1744 3158 285 3159 1745 3159 1746 3159 285 3160 284 3160 1745 3160 297 3161 1746 3161 1747 3161 297 3162 285 3162 1746 3162 313 3163 1747 3163 1748 3163 313 3164 297 3164 1747 3164 326 3165 313 3165 1748 3165 326 3166 1748 3166 1749 3166 350 3167 326 3167 1749 3167 350 3168 1749 3168 1750 3168 368 3169 350 3169 1750 3169 368 3170 1750 3170 1751 3170 394 3171 368 3171 1751 3171 394 3172 1751 3172 1752 3172 421 3173 394 3173 1752 3173 455 3174 421 3174 1752 3174 455 3175 1752 3175 1753 3175 481 3176 455 3176 1753 3176 481 3177 1753 3177 1754 3177 503 3178 481 3178 1754 3178 503 3179 1754 3179 1755 3179 525 3180 503 3180 1755 3180 525 3181 1755 3181 1756 3181 544 3182 525 3182 1756 3182 544 3183 1756 3183 1757 3183 557 3184 544 3184 1757 3184 557 3185 1757 3185 1758 3185 558 3186 557 3186 1758 3186 558 3187 1758 3187 1759 3187 577 3188 558 3188 1759 3188 577 3189 1759 3189 1760 3189 600 3190 577 3190 1760 3190 600 3191 1760 3191 1761 3191 632 3192 600 3192 1761 3192 632 3193 1761 3193 1762 3193 666 3194 632 3194 1762 3194 666 3195 1762 3195 1763 3195 703 3196 666 3196 1763 3196 703 3197 1763 3197 1764 3197 744 3198 703 3198 1764 3198 744 3199 1764 3199 1765 3199 790 3200 744 3200 1765 3200 790 3201 1765 3201 1766 3201 836 3202 1766 3202 1767 3202 836 3203 790 3203 1766 3203 879 3204 1767 3204 1768 3204 879 3205 836 3205 1767 3205 916 3206 1768 3206 1769 3206 916 3207 879 3207 1768 3207 569 3208 1769 3208 1770 3208 569 3209 916 3209 1769 3209 570 3210 1770 3210 1689 3210 570 3211 569 3211 1770 3211 1226 3212 1771 3212 1772 3212 1226 3213 1241 3213 1771 3213 1219 3214 1772 3214 1773 3214 1219 3215 1226 3215 1772 3215 1217 3216 1773 3216 1774 3216 1217 3217 1219 3217 1773 3217 1189 3218 1774 3218 1775 3218 1189 3219 1217 3219 1774 3219 1171 3220 1775 3220 1776 3220 1171 3221 1189 3221 1775 3221 1152 3222 1776 3222 1777 3222 1152 3223 1171 3223 1776 3223 1127 3224 1777 3224 1778 3224 1127 3225 1152 3225 1777 3225 1125 3226 1778 3226 1779 3226 1125 3227 1127 3227 1778 3227 1102 3228 1779 3228 1780 3228 1102 3229 1125 3229 1779 3229 1680 3230 1780 3230 1781 3230 1680 3231 1102 3231 1780 3231 1651 3232 1781 3232 1782 3232 1651 3233 1680 3233 1781 3233 1623 3234 1782 3234 1783 3234 1623 3235 1651 3235 1782 3235 1595 3236 1783 3236 1784 3236 1595 3237 1623 3237 1783 3237 1566 3238 1784 3238 1785 3238 1566 3239 1595 3239 1784 3239 1541 3240 1785 3240 1786 3240 1541 3241 1566 3241 1785 3241 1513 3242 1786 3242 1787 3242 1513 3243 1541 3243 1786 3243 1487 3244 1787 3244 1788 3244 1487 3245 1513 3245 1787 3245 1464 3246 1788 3246 1789 3246 1464 3247 1487 3247 1788 3247 1442 3248 1789 3248 1790 3248 1442 3249 1464 3249 1789 3249 1421 3250 1442 3250 1790 3250 1421 3251 1790 3251 1791 3251 1406 3252 1421 3252 1791 3252 1406 3253 1791 3253 1792 3253 1391 3254 1406 3254 1792 3254 1391 3255 1792 3255 1793 3255 1375 3256 1391 3256 1793 3256 1375 3257 1793 3257 1794 3257 1361 3258 1375 3258 1794 3258 1361 3259 1794 3259 1795 3259 1345 3260 1795 3260 1796 3260 1345 3261 1361 3261 1795 3261 1328 3262 1796 3262 1797 3262 1328 3263 1345 3263 1796 3263 1317 3264 1797 3264 1798 3264 1317 3265 1328 3265 1797 3265 1309 3266 1798 3266 1799 3266 1309 3267 1317 3267 1798 3267 1302 3268 1799 3268 1800 3268 1302 3269 1309 3269 1799 3269 1173 3270 1800 3270 1801 3270 1173 3271 1302 3271 1800 3271 1170 3272 1801 3272 1802 3272 1170 3273 1173 3273 1801 3273 1138 3274 1802 3274 1803 3274 1138 3275 1170 3275 1802 3275 1137 3276 1803 3276 1804 3276 1137 3277 1138 3277 1803 3277 1100 3278 1804 3278 1805 3278 1100 3279 1137 3279 1804 3279 1070 3280 1805 3280 1806 3280 1070 3281 1100 3281 1805 3281 1071 3282 1806 3282 1807 3282 1071 3283 1070 3283 1806 3283 1687 3284 1807 3284 1808 3284 1687 3285 1071 3285 1807 3285 1644 3286 1808 3286 1809 3286 1644 3287 1687 3287 1808 3287 1627 3288 1809 3288 1810 3288 1627 3289 1644 3289 1809 3289 1600 3290 1810 3290 1811 3290 1600 3291 1627 3291 1810 3291 1572 3292 1811 3292 1812 3292 1572 3293 1600 3293 1811 3293 1543 3294 1812 3294 1813 3294 1543 3295 1572 3295 1812 3295 1516 3296 1813 3296 1814 3296 1516 3297 1543 3297 1813 3297 1489 3298 1814 3298 1815 3298 1489 3299 1516 3299 1814 3299 1461 3300 1489 3300 1815 3300 1461 3301 1815 3301 1816 3301 1434 3302 1461 3302 1816 3302 1434 3303 1816 3303 1817 3303 1409 3304 1434 3304 1817 3304 1409 3305 1817 3305 1818 3305 1381 3306 1409 3306 1818 3306 1381 3307 1818 3307 1819 3307 1359 3308 1381 3308 1819 3308 1359 3309 1819 3309 1820 3309 1342 3310 1359 3310 1820 3310 1342 3311 1820 3311 1821 3311 1327 3312 1342 3312 1821 3312 1327 3313 1821 3313 1822 3313 1312 3314 1327 3314 1822 3314 1312 3315 1822 3315 1823 3315 1298 3316 1312 3316 1823 3316 1298 3317 1823 3317 1824 3317 1289 3318 1298 3318 1824 3318 1289 3319 1824 3319 1825 3319 1282 3320 1289 3320 1825 3320 1282 3321 1825 3321 1826 3321 1274 3322 1282 3322 1826 3322 1274 3323 1826 3323 1827 3323 1265 3324 1274 3324 1827 3324 1265 3325 1827 3325 1828 3325 1257 3326 1828 3326 1829 3326 1257 3327 1265 3327 1828 3327 1249 3328 1829 3328 1830 3328 1249 3329 1257 3329 1829 3329 1241 3330 1830 3330 1771 3330 1241 3331 1249 3331 1830 3331 1772 3332 1831 3332 1832 3332 1772 3333 1771 3333 1831 3333 1773 3334 1832 3334 1833 3334 1773 3335 1772 3335 1832 3335 1774 3336 1833 3336 1834 3336 1774 3337 1773 3337 1833 3337 1775 3338 1834 3338 1835 3338 1775 3339 1774 3339 1834 3339 1776 3340 1835 3340 1836 3340 1776 3341 1775 3341 1835 3341 1777 3342 1836 3342 1837 3342 1777 3343 1776 3343 1836 3343 1778 3344 1837 3344 1838 3344 1778 3345 1777 3345 1837 3345 1779 3346 1838 3346 1839 3346 1779 3347 1778 3347 1838 3347 1780 3348 1839 3348 1840 3348 1780 3349 1779 3349 1839 3349 1781 3350 1780 3350 1840 3350 1782 3351 1840 3351 1841 3351 1782 3352 1781 3352 1840 3352 1783 3353 1841 3353 1842 3353 1783 3354 1782 3354 1841 3354 1784 3355 1842 3355 1843 3355 1784 3356 1783 3356 1842 3356 1785 3357 1843 3357 1844 3357 1785 3358 1784 3358 1843 3358 1786 3359 1844 3359 1845 3359 1786 3360 1785 3360 1844 3360 1787 3361 1845 3361 1846 3361 1787 3362 1786 3362 1845 3362 1788 3363 1846 3363 1847 3363 1788 3364 1787 3364 1846 3364 1789 3365 1847 3365 1848 3365 1789 3366 1788 3366 1847 3366 1790 3367 1848 3367 1849 3367 1790 3368 1789 3368 1848 3368 1791 3369 1790 3369 1849 3369 1792 3370 1791 3370 1849 3370 1792 3371 1849 3371 1850 3371 1793 3372 1850 3372 1851 3372 1793 3373 1792 3373 1850 3373 1794 3374 1793 3374 1851 3374 1794 3375 1851 3375 1852 3375 1795 3376 1794 3376 1852 3376 1795 3377 1852 3377 1853 3377 1796 3378 1795 3378 1853 3378 1796 3379 1853 3379 1854 3379 1797 3380 1796 3380 1854 3380 1797 3381 1854 3381 1855 3381 1798 3382 1797 3382 1855 3382 1798 3383 1855 3383 1856 3383 1799 3384 1856 3384 1857 3384 1799 3385 1798 3385 1856 3385 1800 3386 1857 3386 1858 3386 1800 3387 1799 3387 1857 3387 1801 3388 1800 3388 1858 3388 1802 3389 1858 3389 1859 3389 1802 3390 1801 3390 1858 3390 1803 3391 1859 3391 1860 3391 1803 3392 1802 3392 1859 3392 1804 3393 1860 3393 1861 3393 1804 3394 1803 3394 1860 3394 1805 3395 1861 3395 1862 3395 1805 3396 1804 3396 1861 3396 1806 3397 1862 3397 1863 3397 1806 3398 1805 3398 1862 3398 1807 3399 1863 3399 1864 3399 1807 3400 1806 3400 1863 3400 1808 3401 1864 3401 1865 3401 1808 3402 1807 3402 1864 3402 1809 3403 1865 3403 1866 3403 1809 3404 1808 3404 1865 3404 1810 3405 1866 3405 1867 3405 1810 3406 1809 3406 1866 3406 1811 3407 1810 3407 1867 3407 1812 3408 1867 3408 1868 3408 1812 3409 1811 3409 1867 3409 1813 3410 1868 3410 1869 3410 1813 3411 1812 3411 1868 3411 1814 3412 1869 3412 1870 3412 1814 3413 1813 3413 1869 3413 1815 3414 1870 3414 1871 3414 1815 3415 1814 3415 1870 3415 1816 3416 1871 3416 1872 3416 1816 3417 1815 3417 1871 3417 1817 3418 1872 3418 1873 3418 1817 3419 1816 3419 1872 3419 1818 3420 1873 3420 1874 3420 1818 3421 1817 3421 1873 3421 1819 3422 1818 3422 1874 3422 1819 3423 1874 3423 1875 3423 1820 3424 1819 3424 1875 3424 1820 3425 1875 3425 1876 3425 1821 3426 1820 3426 1876 3426 1822 3427 1821 3427 1876 3427 1822 3428 1876 3428 1877 3428 1823 3429 1822 3429 1877 3429 1823 3430 1877 3430 1878 3430 1824 3431 1823 3431 1878 3431 1824 3432 1878 3432 1879 3432 1825 3433 1824 3433 1879 3433 1825 3434 1879 3434 1880 3434 1826 3435 1825 3435 1880 3435 1826 3436 1880 3436 1881 3436 1827 3437 1826 3437 1881 3437 1827 3438 1881 3438 1882 3438 1828 3439 1827 3439 1882 3439 1828 3440 1882 3440 1883 3440 1829 3441 1828 3441 1883 3441 1829 3442 1883 3442 1884 3442 1830 3443 1829 3443 1884 3443 1830 3444 1884 3444 1831 3444 1771 3445 1830 3445 1831 3445 1885 3446 439 3446 465 3446 1885 3447 465 3447 490 3447 1885 3448 490 3448 512 3448 1885 3449 512 3449 531 3449 1051 3450 237 3450 1886 3450 1885 3451 531 3451 540 3451 1885 3452 540 3452 561 3452 784 3453 1887 3453 747 3453 580 3454 1885 3454 561 3454 1038 3455 1051 3455 1886 3455 1038 3456 1886 3456 1887 3456 828 3457 1887 3457 784 3457 1007 3458 1038 3458 1887 3458 870 3459 1887 3459 828 3459 986 3460 1007 3460 1887 3460 1888 3461 819 3461 1889 3461 1888 3462 567 3462 604 3462 1888 3463 604 3463 647 3463 907 3464 1887 3464 870 3464 1888 3465 647 3465 685 3465 1888 3466 685 3466 720 3466 1888 3467 720 3467 751 3467 970 3468 986 3468 1887 3468 1888 3469 751 3469 766 3469 1888 3470 766 3470 797 3470 1888 3471 797 3471 819 3471 942 3472 970 3472 1887 3472 942 3473 1887 3473 907 3473 537 3474 567 3474 1888 3474 510 3475 537 3475 1888 3475 1890 3476 1885 3476 580 3476 1890 3477 580 3477 627 3477 1890 3478 627 3478 658 3478 1890 3479 658 3479 694 3479 1890 3480 694 3480 732 3480 773 3481 1890 3481 732 3481 487 3482 510 3482 1888 3482 813 3483 1890 3483 773 3483 467 3484 487 3484 1888 3484 854 3485 1890 3485 813 3485 436 3486 467 3486 1888 3486 1886 3487 436 3487 1888 3487 890 3488 1890 3488 854 3488 423 3489 436 3489 1886 3489 928 3490 1890 3490 890 3490 401 3491 423 3491 1886 3491 957 3492 1890 3492 928 3492 391 3493 401 3493 1886 3493 974 3494 1890 3494 957 3494 371 3495 391 3495 1886 3495 589 3496 1890 3496 974 3496 348 3497 371 3497 1886 3497 322 3498 348 3498 1886 3498 1889 3499 819 3499 862 3499 1889 3500 862 3500 892 3500 1889 3501 892 3501 923 3501 1889 3502 923 3502 962 3502 1889 3503 962 3503 1000 3503 588 3504 1887 3504 1890 3504 1889 3505 1000 3505 1026 3505 1889 3506 1026 3506 1054 3506 588 3507 1890 3507 589 3507 1889 3508 1054 3508 233 3508 645 3509 1887 3509 588 3509 1889 3510 233 3510 250 3510 1889 3511 250 3511 271 3511 1889 3512 271 3512 281 3512 1889 3513 281 3513 300 3513 1889 3514 300 3514 329 3514 293 3515 322 3515 1886 3515 675 3516 1887 3516 645 3516 266 3517 293 3517 1886 3517 709 3518 1887 3518 675 3518 236 3519 266 3519 1886 3519 747 3520 1887 3520 709 3520 1885 3521 1889 3521 329 3521 1885 3522 329 3522 343 3522 1885 3523 343 3523 363 3523 1885 3524 363 3524 384 3524 237 3525 236 3525 1886 3525 1885 3526 384 3526 411 3526 1885 3527 411 3527 439 3527 1860 3528 1862 3528 1861 3528 1860 3529 1863 3529 1862 3529 1860 3530 1864 3530 1863 3530 1843 3531 1837 3531 1831 3531 1843 3532 1840 3532 1837 3532 1843 3533 1842 3533 1840 3533 1877 3534 1879 3534 1878 3534 1843 3535 1831 3535 1877 3535 1881 3536 1880 3536 1879 3536 1875 3537 1877 3537 1876 3537 1857 3538 1859 3538 1858 3538 1846 3539 1870 3539 1865 3539 1846 3540 1844 3540 1843 3540 1846 3541 1845 3541 1844 3541 1846 3542 1843 3542 1877 3542 1846 3543 1865 3543 1864 3543 1846 3544 1877 3544 1870 3544 1855 3545 1857 3545 1856 3545 1872 3546 1874 3546 1873 3546 1872 3547 1875 3547 1874 3547 1848 3548 1847 3548 1846 3548 1872 3549 1877 3549 1875 3549 1854 3550 1864 3550 1860 3550 1854 3551 1860 3551 1859 3551 1831 3552 1882 3552 1881 3552 1854 3553 1846 3553 1864 3553 1831 3554 1883 3554 1882 3554 1854 3555 1859 3555 1857 3555 1831 3556 1884 3556 1883 3556 1854 3557 1857 3557 1855 3557 1831 3558 1879 3558 1877 3558 1831 3559 1881 3559 1879 3559 1849 3560 1848 3560 1846 3560 1853 3561 1849 3561 1846 3561 1853 3562 1846 3562 1854 3562 1850 3563 1849 3563 1853 3563 1870 3564 1872 3564 1871 3564 1851 3565 1853 3565 1852 3565 1851 3566 1850 3566 1853 3566 1870 3567 1877 3567 1872 3567 1833 3568 1832 3568 1831 3568 1868 3569 1870 3569 1869 3569 1835 3570 1834 3570 1833 3570 1835 3571 1833 3571 1831 3571 1836 3572 1835 3572 1831 3572 1866 3573 1868 3573 1867 3573 1866 3574 1870 3574 1868 3574 1837 3575 1836 3575 1831 3575 1865 3576 1870 3576 1866 3576 1840 3577 1838 3577 1837 3577 1840 3578 1839 3578 1838 3578 1842 3579 1841 3579 1840 3579 1714 3580 1713 3580 1547 3580 1725 3581 1370 3581 1726 3581 1725 3582 1386 3582 1370 3582 1715 3583 1714 3583 1547 3583 1715 3584 1547 3584 1518 3584 1724 3585 1386 3585 1725 3585 1724 3586 1401 3586 1386 3586 1716 3587 1518 3587 1506 3587 1716 3588 1715 3588 1518 3588 1723 3589 1401 3589 1724 3589 1723 3590 1418 3590 1401 3590 1717 3591 1716 3591 1506 3591 1717 3592 1506 3592 1480 3592 1722 3593 1418 3593 1723 3593 1718 3594 1717 3594 1480 3594 1721 3595 1418 3595 1722 3595 1721 3596 1435 3596 1418 3596 1719 3597 1718 3597 1480 3597 1719 3598 1480 3598 1457 3598 1720 3599 1435 3599 1721 3599 1720 3600 1719 3600 1457 3600 1720 3601 1457 3601 1435 3601 1377 3602 1761 3602 1760 3602 1356 3603 1762 3603 1761 3603 1356 3604 1761 3604 1377 3604 1400 3605 1759 3605 1758 3605 1400 3606 1760 3606 1759 3606 1400 3607 1377 3607 1760 3607 1336 3608 1763 3608 1762 3608 1336 3609 1764 3609 1763 3609 1336 3610 1762 3610 1356 3610 1427 3611 1400 3611 1758 3611 1427 3612 1758 3612 1757 3612 1322 3613 1764 3613 1336 3613 1322 3614 1765 3614 1764 3614 1438 3615 1427 3615 1757 3615 1438 3616 1757 3616 1756 3616 1307 3617 1765 3617 1322 3617 1307 3618 1766 3618 1765 3618 1468 3619 1438 3619 1756 3619 1468 3620 1755 3620 1754 3620 1468 3621 1756 3621 1755 3621 1295 3622 1766 3622 1307 3622 1295 3623 1767 3623 1766 3623 1295 3624 1768 3624 1767 3624 1496 3625 1468 3625 1754 3625 1496 3626 1754 3626 1753 3626 1287 3627 1768 3627 1295 3627 1287 3628 1769 3628 1768 3628 1525 3629 1496 3629 1753 3629 1525 3630 1753 3630 1752 3630 1279 3631 1769 3631 1287 3631 1279 3632 1770 3632 1769 3632 1553 3633 1525 3633 1752 3633 1553 3634 1752 3634 1751 3634 1271 3635 1690 3635 1689 3635 1271 3636 1770 3636 1279 3636 1271 3637 1689 3637 1770 3637 1580 3638 1553 3638 1751 3638 1580 3639 1750 3639 1749 3639 1580 3640 1751 3640 1750 3640 1263 3641 1691 3641 1690 3641 1263 3642 1690 3642 1271 3642 1608 3643 1580 3643 1749 3643 1608 3644 1749 3644 1748 3644 1254 3645 1692 3645 1691 3645 1254 3646 1691 3646 1263 3646 1636 3647 1608 3647 1748 3647 1636 3648 1748 3648 1747 3648 1246 3649 1693 3649 1692 3649 1246 3650 1694 3650 1693 3650 1246 3651 1692 3651 1254 3651 1664 3652 1636 3652 1747 3652 1664 3653 1746 3653 1745 3653 1664 3654 1747 3654 1746 3654 1238 3655 1695 3655 1694 3655 1238 3656 1694 3656 1246 3656 1684 3657 1664 3657 1745 3657 1684 3658 1745 3658 1744 3658 1231 3659 1696 3659 1695 3659 1231 3660 1695 3660 1238 3660 1095 3661 1684 3661 1744 3661 1095 3662 1744 3662 1743 3662 1223 3663 1697 3663 1696 3663 1223 3664 1696 3664 1231 3664 1698 3665 1697 3665 1223 3665 1097 3666 1743 3666 1742 3666 1097 3667 1095 3667 1743 3667 1741 3668 1097 3668 1742 3668 1214 3669 1698 3669 1223 3669 1699 3670 1698 3670 1214 3670 1113 3671 1097 3671 1741 3671 1200 3672 1699 3672 1214 3672 1740 3673 1113 3673 1741 3673 1129 3674 1113 3674 1740 3674 1700 3675 1699 3675 1200 3675 1182 3676 1700 3676 1200 3676 1739 3677 1129 3677 1740 3677 1147 3678 1129 3678 1739 3678 1701 3679 1700 3679 1182 3679 1738 3680 1147 3680 1739 3680 1702 3681 1182 3681 1160 3681 1702 3682 1701 3682 1182 3682 1737 3683 1147 3683 1738 3683 1737 3684 1164 3684 1147 3684 1703 3685 1702 3685 1160 3685 1703 3686 1160 3686 1142 3686 1736 3687 1164 3687 1737 3687 1736 3688 1180 3688 1164 3688 1704 3689 1142 3689 1118 3689 1704 3690 1703 3690 1142 3690 1735 3691 1180 3691 1736 3691 1735 3692 1196 3692 1180 3692 1705 3693 1704 3693 1118 3693 1734 3694 1196 3694 1735 3694 1706 3695 1118 3695 1078 3695 1706 3696 1705 3696 1118 3696 1733 3697 1196 3697 1734 3697 1733 3698 1204 3698 1196 3698 1707 3699 1078 3699 1077 3699 1707 3700 1706 3700 1078 3700 1732 3701 1204 3701 1733 3701 1732 3702 1209 3702 1204 3702 1708 3703 1077 3703 1659 3703 1708 3704 1707 3704 1077 3704 1731 3705 1301 3705 1209 3705 1731 3706 1209 3706 1732 3706 1709 3707 1659 3707 1631 3707 1709 3708 1708 3708 1659 3708 1730 3709 1301 3709 1731 3709 1710 3710 1709 3710 1631 3710 1729 3711 1340 3711 1301 3711 1729 3712 1301 3712 1730 3712 1711 3713 1631 3713 1604 3713 1711 3714 1710 3714 1631 3714 1728 3715 1355 3715 1340 3715 1728 3716 1340 3716 1729 3716 1712 3717 1604 3717 1575 3717 1712 3718 1711 3718 1604 3718 1727 3719 1370 3719 1355 3719 1727 3720 1355 3720 1728 3720 1713 3721 1575 3721 1547 3721 1713 3722 1712 3722 1575 3722 1726 3723 1370 3723 1727 3723 195 3724 1887 3724 1886 3724 195 3725 1891 3725 1887 3725 1892 3726 195 3726 1886 3726 1890 3727 1887 3727 187 3727 1887 3728 1891 3728 187 3728 1890 3729 187 3729 1893 3729 176 3730 1885 3730 1890 3730 176 3731 1894 3731 1885 3731 1893 3732 176 3732 1890 3732 141 3733 1889 3733 1885 3733 141 3734 1895 3734 1889 3734 1894 3735 141 3735 1885 3735 1888 3736 1889 3736 0 3736 1889 3737 1895 3737 0 3737 1888 3738 0 3738 1896 3738 1886 3739 1888 3739 203 3739 1888 3740 1896 3740 203 3740 1886 3741 203 3741 1892 3741 160 3742 122 3742 1895 3742 131 3743 160 3743 1895 3743 132 3744 131 3744 1895 3744 1895 3745 122 3745 121 3745 1895 3746 121 3746 119 3746 1895 3747 119 3747 1 3747 1 3748 0 3748 1895 3748 132 3749 1895 3749 141 3749 167 3750 166 3750 1894 3750 1894 3751 166 3751 164 3751 1894 3752 164 3752 158 3752 1894 3753 158 3753 157 3753 1894 3754 157 3754 156 3754 1894 3755 156 3755 142 3755 142 3756 141 3756 1894 3756 167 3757 1894 3757 176 3757 1893 3758 181 3758 177 3758 181 3759 1893 3759 182 3759 182 3760 1893 3760 183 3760 183 3761 1893 3761 184 3761 184 3762 1893 3762 185 3762 185 3763 1893 3763 186 3763 177 3764 176 3764 1893 3764 186 3765 1893 3765 187 3765 189 3766 188 3766 1891 3766 190 3767 189 3767 1891 3767 190 3768 1891 3768 191 3768 191 3769 1891 3769 192 3769 192 3770 1891 3770 193 3770 188 3771 187 3771 1891 3771 194 3772 1891 3772 195 3772 193 3773 1891 3773 194 3773 197 3774 196 3774 1892 3774 198 3775 197 3775 1892 3775 199 3776 198 3776 1892 3776 200 3777 199 3777 1892 3777 200 3778 1892 3778 201 3778 201 3779 1892 3779 202 3779 196 3780 195 3780 1892 3780 202 3781 1892 3781 203 3781 172 3782 171 3782 1896 3782 146 3783 172 3783 1896 3783 147 3784 146 3784 1896 3784 149 3785 147 3785 1896 3785 98 3786 149 3786 1896 3786 204 3787 203 3787 1896 3787 171 3788 204 3788 1896 3788 98 3789 1896 3789 0 3789

+
+
+
+ + + + 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 0.1909247 -0.4621123 0.8660254 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.3150257 0.7624853 -1.012556e-16 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -0.06491438 0.1571182 -2.086479e-17 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -1.050086 2.541618 -3.375186e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.572774 1.386337 -1.841011e-16 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -0.3292751 0.7969743 -0.8623167 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 0.9913266 -0.1314211 7.055574e-16 0.9913266 -0.1314211 7.055574e-16 0.9913266 -0.1314211 7.055574e-16 0.3818493 -0.9242246 1.22734e-16 0.3818493 -0.9242246 1.22734e-16 0.3818493 -0.9242246 1.22734e-16 -0.6094773 -0.7928035 -5.828233e-16 -0.6094773 -0.7928035 -5.828233e-16 -0.6094773 -0.7928035 -5.828233e-16 -0.9913266 0.1314211 -7.055574e-16 -0.9913266 0.1314211 -7.055574e-16 -0.9913266 0.1314211 -7.055574e-16 -0.3818493 0.9242246 -1.22734e-16 -0.3818493 0.9242246 -1.22734e-16 -0.3818493 0.9242246 -1.22734e-16 0.6094773 0.7928035 5.828233e-16 0.6094773 0.7928035 5.828233e-16 0.6094773 0.7928035 5.828233e-16 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 + + + + + + + + + + 6.506193 10.94658 88.35566 6.664945 11.15309 88.35566 6.495502 11.11908 88.28349 6.443297 11.26873 88.21132 6.337462 11.13106 88.21132 6.402404 10.86709 88.35566 6.495663 11.43429 88.21132 6.488245 11.60778 88.21132 6.374658 11.51602 88.13916 6.247832 11.46714 88.06699 6.357542 11.38691 88.13916 6.244123 11.55389 88.06699 6.157477 11.55458 88.01887 6.210969 11.63413 88.06699 6.140646 11.58942 88.01887 6.115528 11.54773 87.99482 6.381849 10.57578 88.5 6.499218 10.63352 88.5 6.469471 10.76161 88.42783 6.595903 11.31152 88.28349 6.743495 11.40143 88.35566 6.116233 11.61945 88.01887 6.152369 11.6982 88.06699 6.346584 11.64319 88.13916 6.421938 11.76827 88.21132 6.624429 11.5267 88.28349 6.732368 11.66167 88.35566 6.276708 11.7531 88.13916 6.304739 11.8964 88.21132 6.632907 11.9024 88.35566 6.57764 11.73866 88.28349 6.173456 11.83247 88.13916 6.075392 11.73836 88.06699 6.150783 11.97672 88.21132 6.461179 11.92183 88.28349 6.457108 12.0946 88.35566 5.989321 11.74977 88.06699 6.049283 11.87175 88.13916 5.978641 11.99954 88.21132 6.289093 12.05412 88.28349 6.226175 12.21508 88.35566 5.919166 11.86618 88.13916 5.809075 11.96211 88.21132 5.904538 11.73106 88.06699 6.082138 12.11958 88.28349 5.967962 12.24932 88.35566 5.798798 11.81645 88.13916 5.831269 11.68447 88.06699 5.662538 11.86894 88.21132 5.865276 12.11031 88.28349 5.713613 12.19317 88.35566 5.556703 11.73127 88.21132 5.702699 11.72855 88.13916 5.778352 11.61564 88.06699 5.752168 11.53286 88.06699 5.755877 11.44611 88.06699 5.833353 11.50257 88.01887 5.664664 12.02742 88.28349 5.493807 12.05342 88.35566 5.504337 11.56571 88.21132 5.642458 11.61309 88.13916 5.837252 11.46407 88.01887 5.504498 11.88092 88.28349 5.335055 11.84691 88.35566 5.849924 11.42751 88.01887 5.884472 11.45227 87.99482 5.789031 11.36587 88.06699 5.894515 11.43293 87.99482 5.511755 11.39222 88.21132 5.625342 11.48398 88.13916 5.847631 11.3018 88.06699 5.870686 11.39485 88.01887 5.907764 11.41563 87.99482 5.404097 11.68848 88.28349 5.256505 11.59857 88.35566 5.923815 11.4009 87.99482 5.653416 11.35681 88.13916 5.578062 11.23173 88.21132 5.924608 11.26164 88.06699 5.942181 11.38918 87.99482 5.375571 11.4733 88.28349 5.267632 11.33833 88.35566 5.962304 11.38082 87.99482 5.723292 11.2469 88.13916 5.695261 11.1036 88.21132 6.010679 11.25023 88.06699 5.983572 11.37608 87.99482 5.367093 11.0976 88.35566 5.42236 11.26134 88.28349 6.00534 11.37511 87.99482 5.826544 11.16753 88.13916 5.849217 11.02328 88.21132 5.538821 11.07817 88.28349 5.542892 10.9054 88.35566 5.950717 11.12825 88.13916 6.021359 11.00046 88.21132 6.05389 11.25588 88.06699 6.026945 11.37794 87.99482 6 11.5 87.92265 5.773825 10.78492 88.35566 5.710907 10.94588 88.28349 5.917862 10.88042 88.28349 6.032038 10.75068 88.35566 6.257947 10.53384 88.5 6.188613 10.64557 88.42783 6.161669 10.76763 88.35566 6.067067 11.39452 87.99482 6.084366 11.40776 87.99482 6.038003 11.45038 87.95873 6.042183 11.45388 87.95873 6.046042 11.45773 87.95873 6.0991 11.42382 87.99482 6.04955 11.46191 87.95873 6.110824 11.44218 87.99482 6.052682 11.46637 87.95873 6.055412 11.47109 87.95873 6.119181 11.4623 87.99482 6.057721 11.47603 87.95873 6.123916 11.48357 87.99482 6.172855 11.16721 88.13916 6.134135 11.28903 88.06699 6.168731 11.31553 88.06699 6.297301 11.27145 88.13916 6.05079 11.56607 87.97076 6.608045 10.7061 88.5 6.632742 10.80823 88.46392 6.706468 10.79226 88.5 6.792804 10.89052 88.5 6.07427 11.69465 88.04293 6.02397 11.55772 87.95873 6.039342 11.70459 88.04293 5.999452 11.63889 88.00284 6.923534 11.11648 88.5 6.965692 11.24031 88.5 5.952269 11.61553 87.99482 5.936358 11.65404 88.01887 5.925752 11.67971 88.03491 5.918209 11.62074 88.00685 5.878877 11.59311 88.01086 5.827729 11.61716 88.04293 5.810002 11.58546 88.04293 5.97603 11.44228 87.95873 6.991327 11.36858 88.5 7 11.4991 88.5 5.981152 11.44041 87.95873 5.986417 11.43899 87.95873 5.991786 11.43804 87.95873 5.997217 11.43756 87.95873 6.00267 11.43756 87.95873 6.008102 11.43803 87.95873 6.187403 10.90376 88.28349 5.868579 10.50867 88.5 5.999097 10.5 88.5 6.040048 10.56336 88.46392 6.129631 10.50844 88.5 6.991562 11.62963 88.5 6.966159 11.75795 88.5 6.924225 11.88185 88.5 6.03125 11.49997 87.94069 6.124886 11.50534 87.99482 6.070449 11.51881 87.96475 6.122061 11.52694 87.99482 6.057764 11.52387 87.95873 6.668928 10.98575 88.40979 6.865574 10.99922 88.5 5.933769 11.56635 87.97678 5.942279 11.52397 87.95873 6.866476 11.99922 88.5 6.793903 12.10805 88.5 6.707745 12.20647 88.5 5.884558 11.54794 87.99482 5.917389 11.51095 87.97076 5.96875 11.50003 87.94069 5.862316 11.51825 88.00284 5.961491 11.48409 87.94671 5.616483 10.57647 88.5 5.740309 10.53431 88.5 5.889113 10.66357 88.40979 6.609477 12.2928 88.5 6.500782 12.36557 88.5 6.008693 11.51298 87.93167 6.000028 11.53125 87.94069 5.976134 11.55776 87.95873 5.973993 11.539 87.94971 6.383517 12.42353 88.5 6.259691 12.46569 88.5 6.131421 12.49133 88.5 6.000903 12.5 88.5 5.870369 12.49156 88.5 5.742053 12.46616 88.5 5.618151 12.42422 88.5 5.500782 12.36648 88.5 5.391955 12.2939 88.5 5.293532 12.20774 88.5 5.207196 12.10948 88.5 5.134426 12.00078 88.5 5.076466 11.88352 88.5 5.034308 11.75969 88.5 5.008673 11.63142 88.5 5 11.5009 88.5 5.008438 11.37037 88.5 5.033841 11.24205 88.5 5.075775 11.11815 88.5 5.133524 11.00078 88.5 5.206097 10.89195 88.5 5.292255 10.79353 88.5 5.390523 10.7072 88.5 5.499218 10.63443 88.5 6.221648 11.38436 88.06699 6.165819 11.51679 88.01887 3.353933 11.05287 89.88826 3.291812 11.24851 89.8311 3.318178 11.04683 89.8311 8.105318 10.01244 89.9714 8.043712 9.928871 89.9714 8.089374 9.893769 89.93583 8.152356 9.979202 89.93583 3.357698 10.76597 89.76726 3.337677 10.84228 89.76726 3.330263 10.84045 89.7 3.387016 10.64279 89.7 7.994293 9.966863 89.99276 7.930942 9.887804 89.99276 7.880667 9.92978 90 3.433214 11.26164 89.9714 3.422579 11.45412 89.9714 3.364993 11.4531 89.93583 8.000919 10.0862 90 3.375866 11.25632 89.93583 8.347558 10.19978 89.88826 8.309186 10.13279 89.88826 8.340388 10.11432 89.8311 3.364924 10.9921 89.88826 3.329317 10.98523 89.8311 8.379279 10.18221 89.8311 3.359543 10.84768 89.8311 3.307202 10.98097 89.76726 8.4443 10.30713 89.8311 8.398982 10.1713 89.76726 8.464541 10.29726 89.76726 3.401414 11.0609 89.93583 3.327918 11.25186 89.88826 8.26775 10.15733 89.93583 8.203565 10.0544 89.93583 8.155408 10.08599 89.9714 8.471105 10.3637 89.8311 8.491568 10.35429 89.76726 3.394273 10.64517 89.76726 3.379399 10.772 89.8311 8.054409 10.04841 89.99276 3.495282 11.26741 89.99276 3.56477 11.23139 90 3.551052 11.42821 90 3.484904 11.45523 89.99276 8.55333 10.49947 89.76726 8.498506 10.3511 89.7 8.577377 10.54103 89.7 3.412207 11.00121 89.93583 8.305434 10.22311 89.93583 3.394746 10.85638 89.88826 8.411712 10.32304 89.88826 3.425331 10.55574 89.76726 3.458382 10.44991 89.7 8.103288 10.12018 89.99276 8.108194 10.25179 90 3.458204 11.07049 89.9714 8.21819 10.18667 89.9714 3.415673 10.65219 89.8311 8.438159 10.37885 89.88826 3.414338 10.78171 89.88826 8.53236 10.50769 89.8311 3.468761 11.01211 89.9714 8.25505 10.25102 89.9714 3.441494 10.86793 89.93583 8.368437 10.34416 89.93583 8.164552 10.21843 89.99276 3.465441 10.45283 89.76726 3.446477 10.56349 89.8311 8.62556 10.70817 89.76726 8.641834 10.73632 89.7 3.519667 11.08088 89.99276 3.594281 11.0363 90 8.394409 10.39897 89.93583 3.450128 10.66349 89.88826 8.498598 10.52092 89.88826 3.460735 10.7946 89.93583 8.200521 10.28122 89.99276 8.201797 10.42548 90 3.52997 11.02391 89.99276 8.316676 10.36942 89.9714 3.497408 10.88174 89.9714 3.509662 10.35162 89.76726 8.603996 10.71468 89.8311 3.543962 10.26292 89.7 8.342081 10.42303 89.9714 3.486257 10.46143 89.8311 8.453763 10.53849 89.93583 3.480521 10.57598 89.88826 8.260656 10.39676 89.99276 3.495883 10.6785 89.93583 8.680761 10.92201 89.76726 8.691517 10.93588 89.7 3.516228 10.81001 89.9714 8.569279 10.72515 89.88826 3.550783 10.26635 89.76726 8.285447 10.44907 89.99276 3.557924 10.89669 89.99276 3.639394 10.84423 90 8.28112 10.60614 90 3.530114 10.36105 89.8311 8.400138 10.5595 89.9714 8.658745 10.92676 89.8311 3.519771 10.47528 89.88826 8.523176 10.73905 89.93583 3.52573 10.59256 89.93583 8.3421 10.58224 89.99276 3.576289 10.8267 89.99276 8.345649 10.79259 90 8.718577 11.1396 89.76726 3.550608 10.69645 89.9714 8.726148 11.13859 89.7 8.623298 10.9344 89.88826 3.610143 10.15496 89.76726 3.643277 10.08283 89.7 8.468034 10.75568 89.9714 3.570898 10.27648 89.8311 8.69625 11.14256 89.8311 3.563044 10.37624 89.88826 3.564276 10.49366 89.93583 8.576225 10.94455 89.93583 8.408354 10.77368 89.99276 3.579803 10.61239 89.9714 8.394966 10.98363 90 8.737909 11.34376 89.76726 8.745533 11.34333 89.7 8.749564 11.54894 89.7 3.649822 10.08677 89.76726 3.609838 10.71588 89.99276 3.699816 10.6564 90 8.660303 11.14732 89.88826 3.629771 10.166 89.8311 8.519924 10.95669 89.9714 3.603283 10.29279 89.88826 8.715423 11.34505 89.8311 3.606772 10.3964 89.93583 8.612567 11.15365 89.93583 3.617506 10.51566 89.9714 3.638326 10.63385 89.99276 8.741929 11.5488 89.76726 8.738219 11.75428 89.7 8.458989 10.96983 89.99276 3.669124 10.09838 89.8311 3.726123 9.967016 89.76726 3.755772 9.910679 89.7 8.67922 11.34711 89.88826 3.661371 10.18379 89.88826 8.555471 11.16122 89.9714 3.64629 10.31446 89.93583 8.719409 11.5484 89.8311 3.762005 9.915093 89.76726 8.631144 11.34986 89.93583 3.659074 10.42052 89.9714 8.730614 11.75357 89.76726 3.675118 10.53946 89.99276 3.775156 10.47405 90 8.493677 11.16941 89.99276 8.42875 11.17802 90 3.7002 10.11706 89.88826 8.683154 11.54776 89.88826 3.744798 9.979607 89.8311 8.573643 11.35314 89.9714 3.703335 10.20741 89.93583 8.708188 11.75149 89.8311 3.697728 10.34037 89.9714 3.780385 9.92811 89.8311 8.635007 11.5469 89.93583 8.70403 11.95692 89.76726 8.71156 11.95819 89.7 3.71568 10.44663 89.99276 3.856851 9.789016 89.76726 8.511409 11.35669 89.99276 8.446783 11.3745 90 3.880817 9.747412 89.7 8.672082 11.74814 89.88826 3.741467 10.14188 89.93583 3.774865 9.999877 89.88826 8.692798 12.01903 89.76726 8.669737 12.15955 89.7 3.7534 10.36841 89.99276 3.864925 10.29835 90 8.577421 11.54588 89.9714 8.681822 11.95317 89.8311 3.753527 10.23566 89.9714 3.809977 9.949066 89.88826 8.624134 11.74368 89.93583 3.874452 9.803068 89.8311 3.790826 10.17156 89.9714 8.670683 12.01477 89.8311 3.814793 10.02679 89.93583 8.662323 12.15772 89.76726 8.515096 11.54477 89.99276 8.448948 11.57179 90 3.807849 10.26623 89.99276 8.646067 11.94713 89.88826 4.001477 9.622113 89.76726 4.017714 9.593946 89.7 8.642302 12.23403 89.76726 8.612984 12.35721 89.7 3.849275 9.976896 89.93583 3.902791 9.825692 89.88826 8.566786 11.73836 89.9714 3.844246 10.20368 89.99276 3.968541 10.13045 90 8.635076 12.0079 89.88826 3.862549 10.05899 89.9714 8.640457 12.15232 89.8311 4.017891 9.637535 89.8311 8.598586 11.9391 89.93583 3.896277 10.01018 89.9714 8.605727 12.35483 89.76726 8.620601 12.228 89.8311 3.940423 9.855736 89.93583 3.914235 10.09384 89.99276 8.504718 11.73259 89.99276 8.43523 11.76861 90 4.159065 9.467388 89.76726 4.165697 9.451139 89.7 8.587793 11.99879 89.93583 4.044317 9.662366 89.88826 8.605254 12.14362 89.88826 3.947148 10.04621 89.99276 4.085332 9.971424 90 8.574669 12.44426 89.76726 8.541618 12.55009 89.7 3.985433 9.89167 89.9714 8.541796 11.92951 89.9714 4.174185 9.484081 89.8311 8.584327 12.34781 89.8311 4.07941 9.695341 89.93583 4.034148 9.930561 89.99276 8.585662 12.21829 89.88826 4.21454 9.822314 90 4.328592 9.325845 89.76726 8.531239 11.98789 89.9714 8.558506 12.13207 89.93583 4.323937 9.31979 89.7 4.198527 9.510958 89.88826 4.121382 9.73478 89.9714 8.534559 12.54717 89.76726 8.553523 12.43651 89.8311 4.342319 9.343701 89.8311 8.480333 11.91912 89.99276 8.405719 11.9637 90 4.230852 9.546649 89.93583 8.549872 12.33651 89.88826 4.16681 9.777465 89.99276 4.355327 9.684084 90 8.539265 12.2054 89.93583 4.49574 9.20702 89.76726 8.47003 11.97609 89.99276 4.491551 9.200634 89.7 8.502592 12.11826 89.9714 4.36442 9.372449 89.88826 8.490338 12.64838 89.76726 8.456038 12.73708 89.7 4.269515 9.589338 89.9714 8.513743 12.53857 89.8311 8.519479 12.42402 89.88826 4.508095 9.225852 89.8311 8.504117 12.3215 89.93583 4.393769 9.410626 89.93583 8.483772 12.18999 89.9714 4.671301 9.101018 89.76726 4.667601 9.094337 89.7 4.851102 9.001494 89.7 8.449217 12.73365 89.76726 4.311361 9.63554 89.99276 8.442076 12.10331 89.99276 8.360606 12.15577 90 4.527985 9.256171 89.88826 8.469886 12.63895 89.8311 4.428871 9.456288 89.9714 4.682214 9.120721 89.8311 8.480229 12.52472 89.88826 8.47427 12.40744 89.93583 8.423711 12.1733 89.99276 4.554399 9.296435 89.93583 8.449392 12.30355 89.9714 4.854293 9.008432 89.76726 5.041028 8.922623 89.7 8.389857 12.84504 89.76726 8.356723 12.91717 89.7 4.466863 9.505707 89.99276 4.506781 9.557631 90 8.429102 12.72352 89.8311 4.699783 9.152442 89.88826 8.436956 12.62376 89.88826 4.585991 9.344592 89.9714 8.435724 12.50634 89.93583 8.420197 12.38761 89.9714 4.863702 9.028895 89.8311 4.723114 9.194566 89.93583 8.350178 12.91323 89.76726 5.043691 8.929781 89.76726 8.390162 12.28412 89.99276 8.300184 12.3436 90 4.620184 9.396712 89.99276 4.667918 9.443776 90 8.370229 12.834 89.8311 8.396717 12.70721 89.88826 4.878852 9.061841 89.88826 8.393228 12.6036 89.93583 5.103094 8.908453 89.76726 5.236317 8.858166 89.7 4.751019 9.24495 89.9714 8.382494 12.48434 89.9714 8.361674 12.36615 89.99276 5.051545 8.95089 89.8311 8.330876 12.90162 89.8311 4.89897 9.105591 89.93583 8.273877 13.03298 89.76726 8.244228 13.08932 89.7 5.11046 8.929738 89.8311 8.338629 12.81621 89.88826 5.238438 8.865502 89.76726 8.35371 12.68554 89.93583 4.781221 9.299479 89.99276 4.837695 9.343255 90 8.237995 13.08491 89.76726 5.06419 8.984875 89.88826 8.340926 12.57948 89.9714 8.324882 12.46054 89.99276 8.224844 12.52595 90 5.314535 8.844686 89.76726 5.435877 8.808483 89.7 4.923032 9.157919 89.9714 8.2998 12.88294 89.88826 8.255202 13.02039 89.8311 5.12232 8.964005 89.88826 5.244693 8.887139 89.8311 8.296665 12.79259 89.93583 5.080983 9.030006 89.93583 8.302272 12.65963 89.9714 8.219615 13.07189 89.8311 5.437444 8.815957 89.76726 5.320165 8.866494 89.8311 8.28432 12.55337 89.99276 8.143149 13.21098 89.76726 8.119183 13.25259 89.7 4.949074 9.214553 89.99276 5.01501 9.256722 90 8.258533 12.85812 89.93583 5.138069 9.009511 89.93583 5.254763 8.921974 89.88826 8.225135 13.00012 89.88826 8.2466 12.63159 89.99276 8.135075 12.70165 90 5.530422 8.798139 89.76726 8.246473 12.76434 89.9714 5.638592 8.773852 89.7 5.101067 9.083986 89.9714 8.190023 13.05093 89.88826 5.442064 8.838001 89.8311 8.125548 13.19693 89.8311 5.329229 8.901604 89.88826 8.209174 12.82844 89.9714 5.156905 9.063938 89.9714 8.185207 12.97321 89.93583 5.268135 8.968234 89.93583 8.192151 12.73377 89.99276 7.998523 13.37789 89.76726 5.639596 8.781423 89.76726 7.982286 13.40605 89.7 8.150725 13.0231 89.93583 5.534279 8.82033 89.8311 5.122804 9.142408 89.99276 5.198713 9.184738 90 8.097209 13.17431 89.88826 5.449503 8.873492 89.88826 8.155754 12.79632 89.99276 4.95283 14.03456 89.76726 5.142786 14.11298 89.7 4.949914 14.04162 89.7 8.031459 12.86955 90 5.341265 8.94823 89.93583 8.137451 12.94101 89.9714 5.177292 9.122845 89.99276 5.28413 9.023564 89.9714 7.982109 13.36246 89.8311 8.103723 12.98982 89.9714 5.749354 8.769115 89.76726 5.843328 8.754467 89.7 8.059577 13.14426 89.93583 5.642556 8.80375 89.8311 5.540488 8.856056 89.88826 8.085765 12.90616 89.99276 5.459381 8.920622 89.93583 7.840935 13.53261 89.76726 7.834303 13.54886 89.7 5.355661 9.003997 89.9714 7.955683 13.33763 89.88826 4.766351 13.94922 89.76726 5.843763 8.762091 89.76726 8.052852 12.95379 89.99276 7.914668 13.02858 90 4.762915 13.95604 89.7 5.30144 9.083447 89.99276 5.387612 9.127769 90 4.776483 13.9291 89.8311 4.961431 14.01374 89.8311 8.014567 13.10833 89.9714 5.751413 8.791544 89.8311 4.58677 13.85018 89.76726 5.647321 8.839697 89.88826 7.825815 13.51592 89.8311 4.582835 13.85672 89.7 4.410679 13.74423 89.7 4.792795 13.89672 89.88826 5.548733 8.903498 89.93583 4.975277 13.98023 89.88826 7.92059 13.30466 89.93583 5.371242 9.064353 89.99276 7.965852 13.06944 89.99276 7.78546 13.17769 90 4.598377 13.83088 89.8311 5.471196 8.976992 89.9714 7.671408 13.67415 89.76726 7.676063 13.68021 89.7 4.814457 13.85371 89.93583 4.993665 13.93572 89.93583 5.969912 8.757802 89.76726 5.015657 13.88249 89.9714 7.801473 13.48904 89.88826 4.415093 13.738 89.76726 6.04894 8.750436 89.7 5.845046 8.784577 89.8311 7.878618 13.26522 89.9714 4.617064 13.7998 89.88826 7.657681 13.6563 89.8311 4.840366 13.80227 89.9714 5.754727 8.827654 89.88826 5.65365 8.887433 89.93583 5.03946 13.82488 89.99276 7.769148 13.45335 89.93583 4.42811 13.71961 89.8311 5.558595 8.960243 89.9714 7.83319 13.22253 89.99276 7.50426 13.79298 89.76726 7.508449 13.79937 89.7 7.332399 13.90566 89.7 4.641879 13.75853 89.93583 6.048804 8.758071 89.76726 5.483983 9.038001 89.99276 5.580484 9.086184 90 7.63558 13.62755 89.88826 4.252279 13.6133 89.76726 4.247412 13.61918 89.7 5.970159 8.780324 89.8311 4.868407 13.7466 89.99276 7.730485 13.41066 89.9714 5.064469 13.76435 90 4.885298 13.68173 90 4.449066 13.69002 89.88826 5.847112 8.82078 89.88826 7.491905 13.77415 89.8311 4.204108 13.57252 89.76726 4.093946 13.48229 89.7 5.759128 8.875606 89.93583 7.606231 13.58937 89.93583 4.67156 13.70917 89.9714 5.661219 8.944529 89.9714 5.569269 9.021657 89.99276 7.328699 13.89898 89.76726 4.266633 13.59594 89.8311 7.688639 13.36446 89.99276 7.644673 13.31592 90 6.048403 8.780591 89.8311 7.472015 13.74383 89.88826 4.476896 13.65072 89.93583 6.190665 8.764273 89.76726 4.218857 13.5555 89.8311 6.254278 8.761781 89.7 7.571129 13.54371 89.9714 5.970557 8.816583 89.88826 5.849855 8.868856 89.93583 7.317786 13.87928 89.8311 4.099239 13.47678 89.76726 4.703683 13.65575 89.99276 4.713357 13.58496 90 7.445601 13.70357 89.93583 4.289742 13.568 89.88826 6.253572 8.769386 89.76726 5.764392 8.93296 89.9714 7.145707 13.99157 89.76726 7.148898 13.99851 89.7 4.043163 13.42129 89.76726 5.669411 9.006323 89.99276 5.776075 9.060255 90 3.951139 13.3343 89.7 7.533137 13.49429 89.99276 7.493219 13.44237 90 4.510182 13.60372 89.9714 6.047758 8.816846 89.88826 7.300217 13.84756 89.88826 4.242604 13.52809 89.88826 6.189099 8.786741 89.8311 7.414009 13.65541 89.9714 4.11485 13.46055 89.8311 7.136298 13.9711 89.8311 5.971085 8.864734 89.93583 4.320431 13.53089 89.93583 7.276886 13.80543 89.93583 5.853137 8.926357 89.9714 3.956829 13.32921 89.76726 6.956309 14.07022 89.76726 6.958972 14.07738 89.7 6.25149 8.791812 89.8311 4.059234 13.40551 89.8311 5.770089 8.995034 89.99276 7.379816 13.60329 89.99276 7.332082 13.55622 90 4.546208 13.55285 89.99276 6.410181 8.788486 89.76726 6.458195 8.78844 89.7 7.121148 13.93816 89.88826 4.54976 13.47467 90 4.274139 13.4917 89.93583 6.046901 8.864993 89.93583 6.896906 14.09155 89.76726 6.763683 14.14183 89.7 4.139983 13.43441 89.88826 6.186578 8.822915 89.88826 7.248981 13.75505 89.9714 3.894909 13.2576 89.76726 5.856688 8.988591 89.99276 5.973119 9.050147 90 6.948455 14.04911 89.8311 3.81979 13.17606 89.7 4.357137 13.48651 89.9714 5.971717 8.922325 89.9714 7.10103 13.89441 89.93583 3.973609 13.31419 89.8311 6.248137 8.827918 89.88826 6.88954 14.07026 89.8311 4.085109 13.3801 89.88826 6.406812 8.810756 89.8311 6.045876 8.922579 89.9714 6.761562 14.1345 89.76726 4.311856 13.44817 89.9714 7.218779 13.70052 89.99276 7.162305 13.65674 90 6.18323 8.870953 89.93583 4.173359 13.3997 89.93583 6.93581 14.01513 89.88826 3.825845 13.17141 89.76726 5.972401 8.984657 89.99276 6.685465 14.15531 89.76726 6.564123 14.19152 89.7 3.912198 13.24316 89.8311 6.627037 8.830285 89.76726 6.659549 8.830263 89.7 4.396863 13.43847 89.99276 7.076968 13.84208 89.9714 4.395568 13.35157 90 4.000626 13.29 89.88826 6.243684 8.875866 89.93583 6.401388 8.846609 89.88826 6.87768 14.036 89.88826 4.11947 13.34637 89.93583 6.755307 14.11286 89.8311 6.044767 8.984904 89.99276 6.170338 9.055929 90 4.352677 13.40106 89.99276 6.179225 8.928408 89.9714 6.919017 13.96999 89.93583 4.213279 13.35818 89.9714 6.621887 8.852211 89.8311 3.760308 13.08251 89.76726 6.562556 14.18404 89.76726 3.700634 13.00845 89.7 6.679835 14.13351 89.8311 6.238359 8.933214 89.9714 3.843701 13.15768 89.8311 6.394186 8.894222 89.93583 7.050926 13.78545 89.99276 3.940033 13.21992 89.88826 6.98499 13.74328 90 6.174891 8.990592 89.99276 4.036502 13.25788 89.93583 6.861931 13.99049 89.93583 6.745237 14.07803 89.88826 6.839826 8.889398 89.76726 4.160567 13.30602 89.9714 6.857214 8.887016 89.7 6.469578 14.20186 89.76726 6.361408 14.22615 89.7 6.613596 8.887512 89.88826 3.70702 13.00426 89.76726 6.898933 13.91601 89.9714 4.256484 13.31325 89.99276 6.232595 8.995282 89.99276 6.366452 9.07756 90 4.251781 13.21646 90 3.778702 13.06951 89.8311 6.385571 8.951169 89.9714 6.557936 14.162 89.8311 6.670771 14.0984 89.88826 3.872449 13.13558 89.88826 6.832929 8.910838 89.8311 3.976997 13.18906 89.93583 6.843095 13.93606 89.9714 6.602586 8.93439 89.93583 4.205047 13.26234 89.99276 6.731865 14.03177 89.93583 6.376248 9.012803 89.99276 4.079413 13.21946 89.9714 6.360404 14.21858 89.76726 7.047169 8.965441 89.76726 7.050086 8.958382 89.7 3.640231 12.89716 89.76726 6.465721 14.17967 89.8311 3.594337 12.8324 89.7 6.821824 8.945357 89.88826 3.725852 12.99191 89.8311 6.877196 13.85759 89.99276 6.801287 13.81526 90 6.589417 8.990459 89.9714 3.808317 13.04859 89.88826 6.550497 14.12651 89.88826 6.658735 14.05177 89.93583 3.910626 13.10623 89.93583 7.038569 8.986257 89.8311 6.822708 13.87716 89.99276 6.807077 8.991198 89.93583 4.021208 13.15215 89.9714 6.575164 9.051143 89.99276 6.560189 9.114903 90 6.71587 13.97644 89.9714 3.601018 12.8287 89.76726 7.233649 9.050783 89.76726 7.237085 9.043962 89.7 7.417165 9.143277 89.7 6.250646 14.23088 89.76726 6.156672 14.24553 89.7 4.125855 13.17788 89.99276 4.119333 13.07022 90 6.357444 14.19625 89.8311 7.024723 9.019771 89.88826 3.659612 12.88568 89.8311 6.459512 14.14394 89.88826 3.756171 12.97201 89.88826 6.78944 9.046025 89.9714 6.540619 14.07938 89.93583 7.223517 9.070898 89.8311 3.847644 13.0208 89.93583 6.644339 13.996 89.9714 3.956288 13.07113 89.9714 7.006335 9.064276 89.93583 4.069058 13.1122 89.99276 6.156237 14.23791 89.76726 7.41323 9.149822 89.76726 6.69856 13.91655 89.99276 3.620721 12.81779 89.8311 6.612388 13.87223 90 7.589321 9.255772 89.7 6.77035 9.105365 89.99276 6.750293 9.167713 90 3.535459 12.70274 89.76726 6.248587 14.20846 89.8311 7.207205 9.103283 89.88826 3.501494 12.6489 89.7 6.352679 14.1603 89.88826 3.690814 12.86721 89.88826 6.984343 9.117506 89.9714 6.451267 14.0965 89.93583 3.796435 12.9456 89.93583 7.401623 9.169124 89.8311 6.628758 13.93565 89.99276 3.508432 12.64571 89.76726 6.528804 14.02301 89.9714 3.894682 12.98756 89.9714 4.005707 13.03314 89.99276 7.185543 9.14629 89.93583 6.030088 14.2422 89.76726 5.95106 14.24956 89.7 7.584907 9.262005 89.76726 3.999081 12.9138 90 6.154954 14.21542 89.8311 3.652442 12.80022 89.88826 6.96054 9.175118 89.99276 6.935531 9.23565 90 6.245273 14.17235 89.88826 3.5557 12.69287 89.8311 7.382936 9.2002 89.88826 7.159634 9.197728 89.9714 3.73225 12.84267 89.93583 6.34635 14.11257 89.93583 3.844592 12.91401 89.9714 6.441405 14.03976 89.9714 7.57189 9.280385 89.8311 7.358121 9.241467 89.93583 5.951196 14.24193 89.76726 3.528895 12.6363 89.8311 3.945591 12.95159 89.99276 6.516017 13.962 89.99276 6.419516 13.91382 90 7.747721 9.386703 89.76726 3.44667 12.50053 89.76726 7.752588 9.380817 89.7 3.422623 12.45897 89.7 7.131593 9.2534 89.99276 7.114702 9.318271 90 6.029841 14.21968 89.8311 6.152888 14.17922 89.88826 3.694566 12.77689 89.93583 7.550934 9.309977 89.88826 6.240872 14.12439 89.93583 3.588288 12.67696 89.88826 3.896712 12.87982 89.99276 7.795892 9.427483 89.76726 7.906054 9.517714 89.7 6.338781 14.05547 89.9714 7.32844 9.290826 89.9714 3.891806 12.74821 90 3.78181 12.81333 89.9714 6.430731 13.97834 89.99276 7.733367 9.404059 89.8311 5.951597 14.21941 89.8311 3.561841 12.62115 89.88826 5.809335 14.23573 89.76726 5.745722 14.23822 89.7 7.523104 9.349275 89.93583 3.46764 12.49231 89.8311 6.029443 14.18342 89.88826 3.74495 12.74898 89.9714 7.781143 9.444505 89.8311 6.150145 14.13114 89.93583 3.631563 12.65584 89.93583 7.900761 9.523219 89.76726 3.835448 12.78157 89.99276 7.296317 9.344246 89.99276 7.286643 9.415042 90 5.746428 14.23061 89.76726 3.37444 12.29183 89.76726 6.235608 14.06704 89.9714 7.710258 9.432003 89.88826 3.358166 12.26368 89.7 6.330589 13.99368 89.99276 7.956837 9.578713 89.76726 8.048861 9.665697 89.7 6.223925 13.93975 90 3.605591 12.60103 89.93583 5.952242 14.18315 89.88826 7.489818 9.396277 89.9714 3.501402 12.47908 89.88826 5.810901 14.21326 89.8311 3.799479 12.71878 89.99276 3.798203 12.57452 90 7.757396 9.471909 89.88826 3.683324 12.63058 89.9714 6.028915 14.13527 89.93583 7.88515 9.539454 89.8311 3.396004 12.28532 89.8311 6.146863 14.07364 89.9714 7.679569 9.469111 89.93583 5.74851 14.20819 89.8311 3.657919 12.57697 89.9714 8.043171 9.670791 89.76726 3.546237 12.46151 89.93583 6.229911 14.00497 89.99276 3.739344 12.60324 89.99276 7.940766 9.594492 89.8311 5.589819 14.21151 89.76726 5.541805 14.21156 89.7 7.453792 9.447148 89.99276 7.45024 9.525335 90 3.319239 12.07799 89.76726 5.953099 14.13501 89.93583 3.308483 12.06412 89.7 7.725861 9.508301 89.93583 3.430721 12.27485 89.88826 7.860017 9.565593 89.88826 5.813422 14.17708 89.88826 3.714553 12.55093 89.99276 3.71888 12.39386 90 6.143312 14.01141 89.99276 8.105091 9.742403 89.76726 8.18021 9.823937 89.7 6.026881 13.94985 90 3.599862 12.4405 89.9714 7.642863 9.513494 89.9714 6.028283 14.07767 89.9714 3.341255 12.07324 89.8311 5.751863 14.17208 89.88826 3.476824 12.26095 89.93583 8.026391 9.685814 89.8311 7.914891 9.619897 89.88826 5.593188 14.18924 89.8311 3.6579 12.41776 89.99276 7.688144 9.551828 89.9714 5.954124 14.07742 89.9714 3.281423 11.8604 89.76726 7.826641 9.600304 89.93583 3.273852 11.86141 89.7 5.81677 14.12905 89.93583 3.376702 12.0656 89.88826 8.174155 9.828592 89.76726 6.027599 14.01534 89.99276 3.531966 12.24432 89.9714 8.087802 9.756838 89.8311 5.372963 14.16972 89.76726 5.340451 14.16974 89.7 3.30375 11.85744 89.8311 7.603137 9.56153 89.99276 7.604432 9.648434 90 7.999374 9.710001 89.88826 5.756316 14.12413 89.93583 3.423775 12.05545 89.93583 7.88053 9.653634 89.93583 3.591646 12.22632 89.99276 3.654351 12.20741 90 5.598612 14.15339 89.88826 3.605034 12.01637 90 5.955233 14.0151 89.99276 3.262091 11.65624 89.76726 5.829662 13.94407 90 7.647323 9.598937 89.99276 3.254467 11.65667 89.7 3.250436 11.45106 89.7 5.820775 14.07159 89.9714 7.786721 9.64182 89.9714 3.339697 11.85268 89.88826 8.239692 9.917492 89.76726 5.378113 14.14779 89.8311 8.299366 9.991551 89.7 3.480076 12.04331 89.9714 5.761641 14.06679 89.9714 8.156299 9.842319 89.8311 8.059967 9.780078 89.88826 3.284577 11.65495 89.8311 5.605814 14.10578 89.93583 3.387433 11.84635 89.93583 7.963498 9.742121 89.93583 5.825109 14.00941 89.99276 7.839433 9.693984 89.9714 5.160174 14.1106 89.76726 3.258071 11.4512 89.76726 3.541011 12.03017 89.99276 3.57125 11.82198 90 5.386404 14.11249 89.88826 8.29298 9.99574 89.76726 7.743516 9.686753 89.99276 7.748219 9.783541 90 3.32078 11.65289 89.88826 8.221298 9.930489 89.8311 5.767405 14.00472 89.99276 5.633548 13.92244 90 3.444529 11.83878 89.9714 5.614429 14.04883 89.9714 3.280591 11.4516 89.8311 8.127551 9.86442 89.88826 5.167071 14.08916 89.8311 8.023003 9.810941 89.93583 3.368856 11.65014 89.93583 7.794953 9.737656 89.99276 5.397414 14.06561 89.93583 3.269386 11.24643 89.76726 3.261781 11.24572 89.7 7.920587 9.780538 89.9714 5.623752 13.9872 89.99276 3.506323 11.83059 89.99276 8.359769 10.10284 89.76726 8.405663 10.1676 89.7 5.178176 14.05464 89.88826 3.316846 11.45224 89.88826 8.274148 10.00809 89.8311 5.410583 14.00954 89.9714 3.426357 11.64686 89.9714 8.191683 9.951414 89.88826 5.192923 14.0088 89.93583 5.424836 13.94886 89.99276 5.439811 13.8851 90 5.21056 13.95397 89.9714 7.978792 9.847853 89.9714 3.29597 11.04308 89.76726 5.22965 13.89463 89.99276 3.28844 11.04181 89.7 5.249707 13.83229 90 3.488591 11.64331 89.99276 3.553217 11.6255 90 7.874145 9.822116 89.99276 8.243829 10.02799 89.88826 7.324679 10.79041 87.92334 7.363128 10.84831 87.9454 7.331851 10.78656 87.9454 4.56234 11.93753 87.92334 4.539076 11.85213 87.92334 4.531166 11.85404 87.9454 7.457938 11.0563 87.96494 7.474453 11.05128 87.9809 7.452354 10.98422 87.9809 4.483514 11.65074 87.96494 4.458779 11.50139 87.9809 4.466337 11.65245 87.9809 4.489258 11.70028 87.96494 7.407428 10.91554 87.96494 7.436088 10.99 87.96494 4.438269 11.50141 87.99239 7.278252 10.7151 87.9 7.280607 10.71365 87.92334 7.248748 10.66398 87.92334 7.189205 10.58578 87.9 4.58649 12.00199 87.9 4.583887 12.00291 87.92334 7.374911 10.84268 87.96494 4.502205 11.69856 87.9454 4.505592 11.79866 87.96494 4.518399 11.7961 87.9454 7.498312 11.13886 87.9809 7.518251 11.13405 87.99239 7.494074 11.0453 87.99239 4.472146 11.70255 87.9809 7.549843 11.19026 87.99808 7.568974 11.18644 88 7.536488 11.12965 87.99808 4.407564 11.34461 88 4.400001 11.50144 88 4.41951 11.50143 87.99808 4.445651 11.34833 87.99239 4.42698 11.3465 87.99808 7.530685 11.03416 88 7.42337 10.90892 87.9809 4.554556 11.9399 87.9454 7.28754 10.70939 87.9454 4.518469 11.8571 87.96494 4.646706 12.14699 87.9 4.612148 12.07634 87.92334 7.343363 10.7804 87.96494 7.471682 10.97735 87.99239 4.445927 11.65448 87.99239 7.191396 10.5841 87.92334 4.576219 12.00563 87.9454 4.488665 11.80204 87.9809 7.512021 11.03984 87.99808 4.451814 11.70524 87.99239 7.255509 10.65946 87.9454 7.390484 10.83523 87.9809 4.644213 12.14818 87.92334 7.16079 10.54561 87.92334 7.087129 10.46649 87.9 4.542062 11.9437 87.96494 7.442312 10.90105 87.99239 4.501688 11.86114 87.9809 7.29867 10.70256 87.96494 4.407847 11.65826 88 4.42726 11.65633 87.99808 4.604634 12.07946 87.9454 7.48936 10.97108 87.99808 7.477654 10.88637 88 7.35858 10.77225 87.9809 4.721748 12.2849 87.9 4.675321 12.20959 87.92334 7.197846 10.57914 87.9454 4.563912 12.01 87.96494 4.431026 11.81356 88 4.433217 11.70771 87.99808 7.266361 10.65219 87.96494 4.468552 11.80606 87.99239 7.408989 10.82639 87.99239 4.636872 12.15169 87.9454 7.459637 10.89385 87.99808 7.089132 10.46458 87.92334 4.525547 11.94872 87.9809 4.481749 11.86595 87.99239 7.167075 10.54044 87.9454 4.592572 12.08446 87.96494 7.31338 10.69353 87.9809 4.719393 12.28635 87.92334 7.376659 10.76256 87.99239 4.450157 11.80974 87.99808 7.2082 10.57118 87.96494 4.668149 12.21344 87.9454 7.425913 10.81829 87.99808 7.410393 10.74449 88 7.280705 10.64259 87.9809 4.547646 12.01578 87.9809 4.810795 12.41422 87.9 4.751252 12.33602 87.92334 7.095028 10.45898 87.9454 7.177163 10.53215 87.96494 4.625089 12.15732 87.96494 4.505926 11.9547 87.99239 7.330858 10.6828 87.99239 4.469315 11.96584 88 4.463512 11.87035 87.99808 7.393196 10.7537 87.99808 4.57663 12.09108 87.9809 6.973142 10.35851 87.9 6.974935 10.35641 87.92334 6.848493 10.26304 87.9 4.71246 12.29061 87.9454 7.221886 10.56066 87.9809 4.656637 12.2196 87.96494 7.297749 10.63118 87.99239 4.528318 12.02265 87.99239 7.104494 10.44998 87.96494 4.808604 12.4159 87.92334 7.190497 10.52118 87.9809 4.487979 11.96016 87.99808 7.346844 10.67298 87.99808 7.329548 10.60989 88 4.744491 12.34054 87.9454 6.980213 10.35022 87.9454 4.609516 12.16477 87.9809 4.912871 12.53351 87.9 4.83921 12.45439 87.92334 7.313337 10.62074 87.99808 4.557688 12.09895 87.99239 7.238146 10.54816 87.99239 6.850056 10.26077 87.92334 4.70133 12.29744 87.96494 4.522346 12.11363 88 4.51064 12.02892 87.99808 7.117004 10.43808 87.9809 4.64142 12.22775 87.9809 7.20634 10.50816 87.99239 6.988686 10.34028 87.96494 4.802154 12.42086 87.9454 7.253019 10.53673 87.99808 4.733639 12.34781 87.96494 7.2359 10.48385 88 6.854658 10.25406 87.9454 4.591011 12.17361 87.99239 4.540363 12.10615 87.99808 7.22083 10.49624 87.99808 7.131869 10.42395 87.99239 5.026858 12.64149 87.9 4.910868 12.53542 87.92334 6.715864 10.1787 87.92334 6.714548 10.18113 87.9 6.572774 10.11366 87.9 4.832925 12.45956 87.9454 6.573828 10.11111 87.92335 6.576935 10.10359 87.9454 6.999885 10.32714 87.9809 4.68662 12.30647 87.9809 4.623341 12.23744 87.99239 6.862046 10.24329 87.96494 4.7918 12.42882 87.96494 7.145465 10.41103 87.99808 7.130349 10.36761 88 4.589607 12.25551 88 4.574087 12.18171 87.99808 6.581924 10.09152 87.96494 6.71974 10.17155 87.9454 4.719295 12.35741 87.9809 7.013191 10.31153 87.99239 4.904972 12.54102 87.9454 6.871811 10.22905 87.9809 6.725961 10.16006 87.96494 6.588515 10.07556 87.9809 4.822837 12.46785 87.96494 7.013912 10.26227 88 7.025362 10.29726 87.99808 4.669142 12.3172 87.99239 6.883412 10.21214 87.99239 4.606804 12.2463 87.99808 6.734184 10.14488 87.9809 5.025065 12.64359 87.92334 6.596345 10.05661 87.99239 6.887711 10.16885 88 6.894024 10.19667 87.99808 4.778114 12.43934 87.9809 6.743955 10.12685 87.99239 4.702251 12.36882 87.99239 6.603509 10.03927 87.99808 6.752891 10.11036 87.99808 6.752961 10.08825 88 4.895506 12.55002 87.96494 4.809503 12.47882 87.9809 4.653156 12.32702 87.99808 4.670452 12.39011 88 5.019787 12.64978 87.9454 4.686663 12.37926 87.99808 4.761854 12.45184 87.99239 5.151507 12.73696 87.9 5.149944 12.73923 87.92334 5.285452 12.81887 87.9 4.882996 12.56192 87.9809 4.79366 12.49184 87.99239 5.011314 12.65972 87.96494 4.7641 12.51615 88 4.746981 12.46327 87.99808 5.145342 12.74594 87.9454 4.77917 12.50376 87.99808 4.868131 12.57605 87.99239 5.284136 12.8213 87.92334 5.000115 12.67286 87.9809 5.137954 12.75671 87.96494 4.869651 12.63239 88 4.854535 12.58897 87.99808 5.28026 12.82845 87.9454 4.986809 12.68847 87.99239 5.427226 12.88634 87.9 5.426171 12.88889 87.92334 5.128189 12.77095 87.9809 5.274039 12.83994 87.96494 4.986088 12.73773 88 4.974638 12.70274 87.99808 5.423064 12.89641 87.9454 5.116588 12.78786 87.99239 5.575275 12.93861 87.9 5.565069 12.93845 87.92334 5.265816 12.85512 87.9809 5.418077 12.90848 87.96494 5.112289 12.83115 88 5.105976 12.80333 87.99808 5.562714 12.94624 87.9454 5.727978 12.97513 87.9 5.708156 12.97415 87.92334 5.256045 12.87315 87.99239 5.411486 12.92443 87.9809 5.558935 12.95874 87.96494 5.247039 12.91175 88 5.247109 12.88964 87.99808 5.706576 12.98213 87.9454 5.883661 12.99548 87.9 5.854053 12.99566 87.92334 5.403654 12.94339 87.99239 5.553939 12.97526 87.9809 5.70404 12.99494 87.96494 5.396491 12.96073 87.99808 5.389041 12.97876 88 5.853263 13.00376 87.9454 6.001356 13.00276 87.92334 6.040619 12.99945 87.9 5.548002 12.99489 87.99239 5.700687 13.01188 87.9809 5.851995 13.01676 87.96494 5.542573 13.01285 87.99808 5.536927 13.03152 88 6.001364 13.0109 87.9454 6.197132 12.98699 87.9 6.148646 12.99539 87.92334 5.696704 13.032 87.99239 5.850318 13.03394 87.9809 6.197495 12.98973 87.92334 6.001376 13.02396 87.96494 5.693061 13.0504 87.99808 5.689272 13.06954 88 6.149451 13.00349 87.9454 6.610959 10.02124 88 6.424725 10.06139 87.9 6.434931 10.06155 87.92334 6.351484 12.95824 87.9 6.294505 12.97362 87.92334 5.848327 13.05435 87.99239 6.437286 10.05376 87.9454 6.198564 12.99779 87.9454 6.272022 10.02487 87.9 6.291844 10.02585 87.92334 6.001391 13.04122 87.9809 6.441065 10.04126 87.96494 6.352132 12.96092 87.92334 6.150743 13.01649 87.96494 6.293424 10.01787 87.9454 5.846505 13.07302 87.99808 6.116339 10.00452 87.9 6.145947 10.00434 87.92334 5.84461 13.09244 88 6.296099 12.9816 87.9454 6.446061 10.02474 87.9809 6.20028 13.01074 87.96494 6.29596 10.00506 87.96494 6.437527 12.93766 87.92334 6.501986 12.91351 87.9 6.146737 9.996243 87.9454 6.00141 13.06173 87.99239 5.959381 10.00055 87.9 5.998644 9.997238 87.92334 6.354038 12.96883 87.9454 6.152451 13.03366 87.9809 6.451998 10.00511 87.99239 6.502911 12.91611 87.92334 6.299313 9.988122 87.9809 6.298659 12.99441 87.96494 6.148005 9.983245 87.96494 6.202549 13.02785 87.9809 6.457427 9.987151 87.99808 6.463073 9.968477 88 6.001427 13.08049 87.99808 5.998636 9.989101 87.9454 6.001444 13.1 88 6.439896 12.94544 87.9454 5.802868 10.01301 87.9 5.851354 10.00461 87.92334 6.357099 12.98153 87.96494 6.303296 9.968002 87.99239 6.646988 12.85329 87.9 6.576336 12.88785 87.92334 6.154479 13.05407 87.99239 6.149682 9.966064 87.9809 6.505634 12.92378 87.9454 5.802505 10.01027 87.92334 6.302042 13.01134 87.9809 5.998624 9.976041 87.96494 6.205244 13.04819 87.99239 6.310728 9.930462 88 6.306939 9.9496 87.99808 5.850549 9.99651 87.9454 6.64818 12.85579 87.92334 5.648516 10.04176 87.9 5.705495 10.02638 87.92334 6.443698 12.95794 87.96494 6.361144 12.99831 87.9809 6.151673 9.945651 87.99239 6.156335 13.07274 87.99808 5.801436 10.00221 87.9454 6.158265 13.09215 88 6.579456 12.89537 87.9454 5.998609 9.958779 87.9809 6.784902 12.77825 87.9 6.709594 12.82468 87.92334 6.510005 12.93609 87.96494 5.647868 10.03908 87.92334 6.20771 13.06678 87.99808 5.849257 9.983514 87.96494 6.313561 13.06897 88 6.153495 9.92698 87.99808 6.15539 9.907564 88 6.306061 13.03145 87.99239 6.65169 12.86313 87.9454 5.703901 10.0184 87.9454 6.448724 12.97445 87.9809 5.79972 9.989258 87.96494 5.562473 10.06234 87.92334 5.498014 10.08649 87.9 6.36595 13.01825 87.99239 6.584465 12.90743 87.96494 5.99859 9.938269 87.99239 6.786348 12.78061 87.92334 5.645962 10.03117 87.9454 6.309738 13.04984 87.99808 5.847549 9.966337 87.9809 6.713436 12.83185 87.9454 5.497089 10.08389 87.92334 6.515782 12.95235 87.9809 5.701341 10.00559 87.96494 6.836018 12.74875 87.92334 5.797451 9.972146 87.9809 6.914216 12.68921 87.9 6.657323 12.87491 87.96494 5.998556 9.900001 88 5.998573 9.91951 87.99808 5.560104 10.05456 87.9454 6.454696 12.99407 87.99239 6.370345 13.03649 87.99808 5.642901 10.01847 87.96494 6.465837 13.03068 88 6.591085 12.92337 87.9809 5.353012 10.14671 87.9 5.423664 10.11215 87.92334 6.790605 12.78754 87.9454 5.845521 9.945927 87.99239 6.719602 12.84336 87.96494 5.494366 10.07622 87.9454 6.522645 12.97168 87.99239 5.697958 9.988665 87.9809 5.794756 9.951814 87.99239 6.9159 12.6914 87.92334 6.460157 13.01202 87.99808 5.35182 10.14421 87.92334 6.840544 12.75551 87.9454 5.556302 10.04206 87.96494 6.664768 12.89048 87.9809 5.638856 10.00169 87.9809 6.954391 12.66079 87.92334 7.033514 12.58713 87.9 5.843665 9.92726 87.99808 5.841735 9.907847 88 6.598951 12.94231 87.99239 5.420544 10.10463 87.9454 6.797439 12.79867 87.96494 5.215098 10.22175 87.9 5.290406 10.17532 87.92334 6.528923 12.98936 87.99808 6.613628 12.97765 88 6.727753 12.85858 87.9809 5.489995 10.06391 87.96494 5.79229 9.933217 87.99808 5.686439 9.931026 88 6.920859 12.69785 87.9454 5.693939 9.968552 87.99239 6.84781 12.76636 87.96494 5.34831 10.13687 87.9454 5.551276 10.02555 87.9809 6.673615 12.90899 87.99239 6.606146 12.95964 87.99808 5.63405 9.981749 87.99239 7.035417 12.58913 87.92334 5.415535 10.09257 87.96494 6.959558 12.66708 87.9454 5.213652 10.21939 87.92334 6.806472 12.81338 87.9809 5.690262 9.950157 87.99808 6.737438 12.87666 87.99239 5.286564 10.16815 87.9454 6.928819 12.7082 87.96494 5.484218 10.04765 87.9809 6.681706 12.92591 87.99808 6.755508 12.91039 88 5.085784 10.31079 87.9 5.163982 10.25125 87.92334 6.857413 12.78071 87.9809 5.342677 10.12509 87.96494 7.041023 12.59503 87.9454 5.545304 10.00593 87.99239 6.967853 12.67716 87.96494 5.629655 9.963512 87.99808 5.534163 9.969315 88 6.817204 12.83086 87.99239 5.408915 10.07663 87.9809 6.746296 12.8932 87.99808 5.209395 10.21246 87.9454 7.141488 12.47314 87.9 7.14359 12.47493 87.92334 7.236956 12.34849 87.9 6.93934 12.72189 87.9809 5.280398 10.15664 87.96494 6.868823 12.79775 87.99239 5.477355 10.02832 87.99239 7.050022 12.60449 87.96494 5.0841 10.3086 87.92334 5.539843 9.987979 87.99808 6.978816 12.6905 87.9809 6.82702 12.84684 87.99808 5.159456 10.24449 87.9454 6.890113 12.82955 88 7.149782 12.48021 87.9454 5.335232 10.10952 87.9809 5.045609 10.33921 87.92334 4.966486 10.41287 87.9 6.87926 12.81334 87.99808 6.95184 12.73815 87.99239 5.401049 10.05769 87.99239 7.239234 12.35006 87.92334 7.318871 12.21455 87.9 5.202561 10.20133 87.96494 7.061916 12.617 87.9809 5.471077 10.01064 87.99808 5.386372 10.02235 88 6.991841 12.70634 87.99239 5.272247 10.14142 87.9809 7.159721 12.48869 87.96494 5.079141 10.30215 87.9454 5.15219 10.23364 87.96494 6.963273 12.75302 87.99808 7.016145 12.7359 88 5.326385 10.09101 87.99239 7.245944 12.35466 87.9454 7.003755 12.72083 87.99808 5.393854 10.04036 87.99808 7.076047 12.63187 87.99239 4.964583 10.41087 87.92334 7.321301 12.21586 87.92334 5.040442 10.33292 87.9454 5.193528 10.18662 87.9809 7.172857 12.49988 87.9809 7.256714 12.36205 87.96494 5.262562 10.12334 87.99239 5.071181 10.2918 87.96494 7.088973 12.64547 87.99808 7.132392 12.63035 88 5.318294 10.07409 87.99808 5.244492 10.08961 88 7.328454 12.21974 87.9454 5.142587 10.21929 87.9809 7.188465 12.51319 87.99239 7.388891 12.07383 87.92334 7.386337 12.07277 87.9 4.958977 10.40497 87.9454 5.032147 10.32284 87.96494 7.270948 12.37181 87.9809 5.182796 10.16914 87.99239 7.339937 12.22596 87.96494 5.253704 10.1068 87.99808 4.85641 10.52507 87.92334 4.858512 10.52686 87.9 7.202741 12.52536 87.99808 7.237732 12.51391 88 7.39641 12.07694 87.9454 5.06066 10.27811 87.9809 7.287862 12.38341 87.99239 5.131177 10.20225 87.99239 7.438448 11.93493 87.92334 7.438614 11.92472 87.9 4.949978 10.39551 87.96494 7.355115 12.23418 87.9809 5.021184 10.3095 87.9809 5.109887 10.17045 88 5.17298 10.15316 87.99808 7.408481 12.08192 87.96494 7.303332 12.39402 87.99808 4.850218 10.51979 87.9454 7.331153 12.38771 88 7.446236 11.93729 87.9454 5.12074 10.18666 87.99808 7.474152 11.79184 87.92334 5.04816 10.26185 87.99239 7.475129 11.77202 87.9 4.760766 10.64994 87.92334 4.763044 10.65151 87.9 4.681129 10.78545 87.9 7.373149 12.24395 87.99239 7.424435 12.08851 87.9809 4.938084 10.383 87.9809 7.458737 11.94107 87.96494 5.008159 10.29366 87.99239 7.389643 12.25289 87.99808 4.840279 10.51131 87.96494 7.411754 12.25296 88 7.482133 11.79342 87.9454 4.983855 10.2641 88 5.036727 10.24698 87.99808 7.495482 11.61634 87.9 7.495659 11.64595 87.92334 4.754056 10.64534 87.9454 7.443391 12.09635 87.99239 4.996245 10.27917 87.99808 4.923953 10.36813 87.99239 7.47526 11.94606 87.9809 7.494945 11.79596 87.96494 4.678699 10.78414 87.92334 7.460729 12.10351 87.99808 4.827143 10.50012 87.9809 7.478759 12.11096 88 7.503757 11.64674 87.9454 7.49945 11.45938 87.9 7.502762 11.49864 87.92334 4.743286 10.63795 87.96494 4.911027 10.35453 87.99808 4.867608 10.36965 88 4.671546 10.78026 87.9454 7.494893 11.952 87.99239 7.511878 11.79931 87.9809 4.811535 10.48681 87.99239 7.516755 11.64801 87.96494 4.613663 10.92723 87.9 4.611109 10.92617 87.92334 7.512849 11.95743 87.99808 4.729052 10.62819 87.9809 7.531523 11.96307 88 7.510899 11.49864 87.9454 7.48699 11.30287 87.9 7.495393 11.35135 87.92334 4.660063 10.77404 87.96494 4.797259 10.47464 87.99808 4.762268 10.48609 88 7.531998 11.8033 87.99239 7.533936 11.64968 87.9809 4.60359 10.92306 87.9454 4.712138 10.61659 87.99239 7.489729 11.30251 87.92334 4.561386 11.07528 87.9 4.561552 11.06507 87.92334 7.523959 11.49862 87.96494 7.5504 11.80694 87.99808 7.569538 11.81073 88 4.644885 10.76582 87.9809 4.591519 10.91808 87.96494 7.50349 11.35055 87.9454 7.458238 11.14852 87.9 7.473623 11.2055 87.92334 4.668847 10.61229 88 4.696668 10.60598 87.99808 7.554349 11.65167 87.99239 4.553764 11.06271 87.9454 4.524871 11.22798 87.9 4.525848 11.20816 87.92334 7.497795 11.30144 87.9454 7.541221 11.49861 87.9809 4.626851 10.75605 87.99239 4.575565 10.91149 87.9809 7.460924 11.14787 87.92334 7.516486 11.34926 87.96494 4.541263 11.05893 87.96494 4.588246 10.74704 88 4.610357 10.74711 87.99808 7.57302 11.6535 87.99808 7.592436 11.65539 88 4.517867 11.20658 87.9454 7.481601 11.2039 87.9454 4.504518 11.38366 87.9 4.504341 11.35405 87.92334 7.510742 11.29972 87.96494 7.41351 10.99801 87.9 7.43766 11.06247 87.92334 4.556609 10.90365 87.99239 7.561731 11.49859 87.99239 4.52474 11.05394 87.9809 4.505055 11.20404 87.96494 7.468834 11.14596 87.9454 4.521241 10.88904 88 4.539271 10.89649 87.99808 7.533663 11.34755 87.9809 4.496243 11.35326 87.9454 7.416113 10.99709 87.92334 4.50055 11.54062 87.9 4.497238 11.50136 87.92334 7.494408 11.20134 87.96494 7.527854 11.29745 87.9809 4.505107 11.048 87.99239 7.58049 11.49857 87.99808 4.488122 11.20069 87.9809 7.599999 11.49856 88 7.445444 11.0601 87.9454 4.483245 11.35199 87.96494 7.481531 11.1429 87.96494 4.468477 11.03693 88 4.487151 11.04257 87.99808 7.353294 10.85301 87.9 7.387852 10.92366 87.92334 4.489101 11.50136 87.9454 4.504607 11.64865 87.92334 7.554073 11.34552 87.99239 4.51301 11.69713 87.9 7.423781 10.99437 87.9454 4.468002 11.1967 87.99239 7.511335 11.19796 87.9809 4.466064 11.35032 87.9809 7.548186 11.29476 87.99239 4.510271 11.69749 87.92334 7.355787 10.85182 87.92334 4.476041 11.50138 87.96494 4.4496 11.19306 87.99808 4.430462 11.18927 88 4.49651 11.64945 87.9454 7.57274 11.34367 87.99808 4.541762 11.85148 87.9 4.526377 11.7945 87.92334 7.592153 11.34174 88 7.395366 10.92054 87.9454 7.566783 11.29229 87.99808 7.531448 11.19394 87.99239 4.949914 14.04162 88 4.762915 13.95604 88 4.582835 13.85672 88 4.410679 13.74423 88 4.247412 13.61918 88 4.093946 13.48229 88 3.951139 13.3343 88 3.81979 13.17606 88 3.700634 13.00845 88 3.594337 12.8324 88 3.501494 12.6489 88 3.422623 12.45897 88 3.358166 12.26368 88 3.308483 12.06412 88 3.273852 11.86141 88 3.254467 11.65667 88 3.250436 11.45106 88 3.261781 11.24572 88 3.28844 11.04181 88 3.330263 10.84045 88 3.387016 10.64279 88 3.458382 10.44991 88 3.543962 10.26292 88 3.643277 10.08283 88 3.755772 9.910679 88 3.880817 9.747412 88 4.017714 9.593946 88 4.165697 9.451139 88 4.323937 9.31979 88 4.491551 9.200634 88 4.667601 9.094337 88 4.851102 9.001494 88 5.041028 8.922623 88 5.236317 8.858166 88 5.435877 8.808483 88 5.638592 8.773852 88 5.843328 8.754467 88 6.04894 8.750436 88 6.254278 8.761781 88 6.458195 8.78844 88 6.659549 8.830263 88 6.857214 8.887016 88 7.050086 8.958382 88 7.237085 9.043962 88 7.417165 9.143277 88 7.589321 9.255772 88 7.752588 9.380817 88 7.906054 9.517714 88 8.048861 9.665697 88 8.18021 9.823937 88 8.299366 9.991551 88 8.405663 10.1676 88 8.498506 10.3511 88 8.577377 10.54103 88 8.641834 10.73632 88 8.691517 10.93588 88 8.726148 11.13859 88 8.745533 11.34333 88 8.749564 11.54894 88 8.738219 11.75428 88 8.71156 11.95819 88 8.669737 12.15955 88 8.612984 12.35721 88 8.541618 12.55009 88 8.456038 12.73708 88 8.356723 12.91717 88 8.244228 13.08932 88 8.119183 13.25259 88 7.982286 13.40605 88 7.834303 13.54886 88 7.676063 13.68021 88 7.508449 13.79937 88 7.332399 13.90566 88 7.148898 13.99851 88 6.958972 14.07738 88 6.763683 14.14183 88 6.564123 14.19152 88 6.361408 14.22615 88 6.156672 14.24553 88 5.95106 14.24956 88 5.745722 14.23822 88 5.541805 14.21156 88 5.340451 14.16974 88 5.142786 14.11298 88 5.427226 12.88634 78.2805 5.289911 12.82128 78.2805 5.159883 12.74266 78.2805 5.038476 12.65129 78.2805 4.926935 12.54811 78.2805 4.826405 12.43417 78.2805 4.737918 12.31065 78.2805 4.662381 12.17881 78.2805 4.600571 12.04 78.2805 4.55312 11.89565 78.2805 4.520516 11.74724 78.2805 4.503094 11.5963 78.2805 4.501032 11.44436 78.2805 4.514352 11.293 78.2805 4.542916 11.14376 78.2805 4.586432 10.99818 78.2805 4.644453 10.85774 78.2805 4.716384 10.7239 78.2805 4.801486 10.59802 78.2805 4.898887 10.4814 78.2805 5.007587 10.37523 78.2805 5.12647 10.2806 78.2805 5.254317 10.19848 78.2805 5.389815 10.12972 78.2805 5.531575 10.07502 78.2805 5.678142 10.03494 78.2805 5.828011 10.00989 78.2805 5.979645 10.00014 78.2805 6.131488 10.00577 78.2805 6.281982 10.02674 78.2805 6.429582 10.06283 78.2805 6.572774 10.11366 78.2805 6.710089 10.17872 78.2805 6.840117 10.25734 78.2805 6.961524 10.34871 78.2805 7.073065 10.45189 78.2805 7.173595 10.56583 78.2805 7.262082 10.68935 78.2805 7.337619 10.82119 78.2805 7.399429 10.96 78.2805 7.44688 11.10435 78.2805 7.479484 11.25276 78.2805 7.496906 11.4037 78.2805 7.498968 11.55564 78.2805 7.485648 11.707 78.2805 7.457084 11.85624 78.2805 7.413568 12.00182 78.2805 7.355547 12.14226 78.2805 7.283616 12.2761 78.2805 7.198514 12.40198 78.2805 7.101113 12.5186 78.2805 6.992413 12.62477 78.2805 6.87353 12.7194 78.2805 6.745683 12.80152 78.2805 6.610185 12.87028 78.2805 6.468425 12.92498 78.2805 6.321858 12.96506 78.2805 6.171989 12.99011 78.2805 6.020355 12.99986 78.2805 5.868512 12.99423 78.2805 5.718018 12.97326 78.2805 5.570418 12.93717 78.2805 5.534335 12.62709 78 5.406636 12.56541 78 5.286962 12.48932 78 5.17693 12.39985 78 5.078028 12.29822 78 4.991595 12.18578 78 4.918799 12.06408 78 4.860624 11.93474 78 4.817857 11.79953 78 4.791077 11.66027 78 4.780645 11.51884 78 4.786703 11.37715 78 4.809169 11.23713 78 4.847739 11.10066 78 4.901891 10.96959 78 4.970893 10.84569 78 5.053812 10.73064 78 5.149527 10.626 78 5.256742 10.53318 78 5.374009 10.45343 78 5.499742 10.38783 78 5.63224 10.33727 78 5.769711 10.30244 78 5.910296 10.2838 78 6.052094 10.28161 78 6.193188 10.2959 78 6.331669 10.32647 78 6.465665 10.37291 78 6.593364 10.43459 78 6.713038 10.51068 78 6.82307 10.60015 78 6.921972 10.70178 78 7.008405 10.81422 78 7.081201 10.93592 78 7.139376 11.06526 78 7.182143 11.20047 78 7.208923 11.33973 78 7.219355 11.48116 78 7.213297 11.62285 78 7.190831 11.76287 78 7.152261 11.89934 78 7.098109 12.03041 78 7.029107 12.15431 78 6.946188 12.26936 78 6.850473 12.374 78 6.743258 12.46682 78 6.625991 12.54657 78 6.500258 12.61217 78 6.36776 12.66273 78 6.230289 12.69756 78 6.089704 12.7162 78 5.947906 12.71839 78 5.806812 12.7041 78 5.668331 12.67353 78 5.084549 12.20376 90 7.067203 11.94092 90 6.915451 10.79624 90 4.932797 11.05908 90 5.848248 10.35531 90 6.151752 12.64469 90 5.084549 12.20376 88.5 4.932797 11.05908 88.5 6.151752 12.64469 88.5 7.067203 11.94092 88.5 6.915451 10.79624 88.5 5.848248 10.35531 88.5 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 2 1 4 2 5 2 2 2 5 3 0 3 2 3 6 4 7 4 8 4 9 5 10 5 8 5 11 6 9 6 8 6 10 7 6 7 8 7 12 8 13 8 14 8 15 9 12 9 14 9 16 10 17 10 18 10 5 11 16 11 18 11 0 12 5 12 18 12 2 13 1 13 19 13 6 14 3 14 19 14 1 15 20 15 19 15 3 16 2 16 19 16 14 17 13 17 21 17 13 18 22 18 21 18 8 19 7 19 23 19 13 20 11 20 23 20 7 21 24 21 23 21 11 22 8 22 23 22 6 23 19 23 25 23 19 24 20 24 25 24 20 25 26 25 25 25 7 26 6 26 25 26 23 27 24 27 27 27 24 28 28 28 27 28 13 29 23 29 27 29 22 30 13 30 27 30 26 31 29 31 30 31 25 32 26 32 30 32 7 33 25 33 30 33 24 34 7 34 30 34 27 35 28 35 31 35 32 36 22 36 31 36 22 37 27 37 31 37 28 38 33 38 31 38 28 39 24 39 34 39 24 40 30 40 34 40 29 41 35 41 34 41 30 42 29 42 34 42 36 43 32 43 37 43 32 44 31 44 37 44 31 45 33 45 37 45 33 46 38 46 37 46 28 47 34 47 39 47 34 48 35 48 39 48 35 49 40 49 39 49 33 50 28 50 39 50 37 51 38 51 41 51 36 52 37 52 41 52 38 53 42 53 41 53 43 54 36 54 41 54 39 55 40 55 44 55 33 56 39 56 44 56 38 57 33 57 44 57 40 58 45 58 44 58 41 59 42 59 46 59 43 60 41 60 46 60 47 61 43 61 46 61 42 62 48 62 46 62 38 63 44 63 49 63 44 64 45 64 49 64 42 65 38 65 49 65 45 66 50 66 49 66 48 67 51 67 52 67 47 68 46 68 52 68 46 69 48 69 52 69 53 70 47 70 52 70 54 71 55 71 56 71 42 72 49 72 57 72 49 73 50 73 57 73 48 74 42 74 57 74 50 75 58 75 57 75 51 76 59 76 60 76 54 77 53 77 60 77 53 78 52 78 60 78 52 79 51 79 60 79 56 80 55 80 61 80 51 81 48 81 62 81 58 82 63 82 62 82 48 83 57 83 62 83 57 84 58 84 62 84 61 85 55 85 64 85 65 86 61 86 64 86 55 87 66 87 64 87 65 88 64 88 67 88 59 89 68 89 69 89 54 90 60 90 69 90 60 91 59 91 69 91 55 92 54 92 69 92 66 93 70 93 71 93 64 94 66 94 71 94 67 95 64 95 71 95 72 96 67 96 71 96 59 97 51 97 73 97 62 98 63 98 73 98 63 99 74 99 73 99 51 100 62 100 73 100 71 101 70 101 75 101 72 102 71 102 75 102 69 103 68 103 76 103 55 104 69 104 76 104 68 105 77 105 76 105 66 106 55 106 76 106 70 107 78 107 79 107 75 108 70 108 79 108 59 109 73 109 80 109 74 110 81 110 80 110 68 111 59 111 80 111 73 112 74 112 80 112 79 113 78 113 82 113 66 114 76 114 83 114 76 115 77 115 83 115 77 116 84 116 83 116 70 117 66 117 83 117 78 118 85 118 86 118 82 119 78 119 86 119 81 120 87 120 88 120 77 121 68 121 88 121 68 122 80 122 88 122 80 123 81 123 88 123 86 124 85 124 89 124 83 125 84 125 90 125 70 126 83 126 90 126 78 127 70 127 90 127 84 128 91 128 90 128 77 129 88 129 92 129 87 130 93 130 92 130 84 131 77 131 92 131 88 132 87 132 92 132 78 133 90 133 94 133 90 134 91 134 94 134 85 135 78 135 94 135 91 136 95 136 94 136 89 137 85 137 96 137 97 138 89 138 96 138 96 139 97 139 98 139 85 140 94 140 96 140 94 141 95 141 96 141 93 142 99 142 100 142 92 143 93 143 100 143 84 144 92 144 100 144 91 145 84 145 100 145 91 146 100 146 101 146 95 147 91 147 101 147 100 148 99 148 101 148 99 149 102 149 101 149 103 150 16 150 104 150 16 151 105 151 104 151 105 152 102 152 104 152 106 153 107 153 108 153 98 154 106 154 108 154 108 155 107 155 109 155 98 156 108 156 109 156 98 157 109 157 110 157 109 158 107 158 110 158 107 159 111 159 110 159 110 160 111 160 112 160 98 161 110 161 112 161 111 162 113 162 114 162 112 163 111 163 114 163 98 164 112 164 114 164 114 165 113 165 115 165 98 166 114 166 115 166 113 167 116 167 117 167 115 168 113 168 117 168 116 169 118 169 117 169 98 170 16 170 119 170 120 171 98 171 119 171 121 172 120 172 119 172 122 173 121 173 119 173 16 174 5 174 119 174 5 175 4 175 119 175 4 176 122 176 119 176 14 177 21 177 123 177 17 178 124 178 125 178 124 179 126 179 125 179 126 180 127 180 125 180 18 181 17 181 125 181 21 182 22 182 128 182 123 183 21 183 128 183 129 184 123 184 128 184 22 185 32 185 128 185 32 186 36 186 130 186 128 187 32 187 130 187 129 188 128 188 130 188 130 189 36 189 131 189 129 190 130 190 131 190 132 191 133 191 1 191 134 192 131 192 135 192 36 193 43 193 136 193 135 194 131 194 136 194 131 195 36 195 136 195 43 196 47 196 137 196 134 197 135 197 137 197 135 198 136 198 137 198 136 199 43 199 137 199 137 200 47 200 138 200 47 201 53 201 139 201 138 202 47 202 139 202 53 203 54 203 140 203 139 204 53 204 140 204 79 205 82 205 141 205 142 206 143 206 20 206 72 207 75 207 141 207 75 208 79 208 141 208 1 209 133 209 20 209 133 210 142 210 20 210 141 211 82 211 144 211 98 212 141 212 144 212 98 213 144 213 145 213 144 214 82 214 145 214 82 215 86 215 145 215 98 216 145 216 146 216 145 217 86 217 146 217 86 218 89 218 147 218 98 219 146 219 147 219 146 220 86 220 147 220 147 221 89 221 148 221 98 222 147 222 148 222 148 223 89 223 149 223 89 224 97 224 149 224 97 225 98 225 149 225 98 226 148 226 149 226 105 227 16 227 150 227 96 228 95 228 150 228 95 229 101 229 150 229 101 230 102 230 150 230 102 231 105 231 150 231 98 232 96 232 150 232 16 233 98 233 150 233 151 234 152 234 153 234 152 235 154 235 153 235 154 236 103 236 153 236 143 237 155 237 26 237 155 238 156 238 26 238 103 239 104 239 153 239 156 240 157 240 26 240 115 241 117 241 158 241 117 242 118 242 158 242 20 243 143 243 26 243 98 244 115 244 158 244 118 245 159 245 158 245 158 246 159 246 160 246 159 247 161 247 160 247 161 248 15 248 160 248 158 249 160 249 162 249 160 250 15 250 162 250 14 251 123 251 162 251 15 252 14 252 162 252 18 253 125 253 163 253 0 254 18 254 163 254 1 255 0 255 163 255 132 256 1 256 163 256 127 257 164 257 163 257 164 258 132 258 163 258 125 259 127 259 163 259 137 260 138 260 165 260 165 261 138 261 166 261 157 262 167 262 29 262 167 263 168 263 29 263 168 264 169 264 29 264 139 265 140 265 170 265 166 266 138 266 170 266 26 267 157 267 29 267 138 268 139 268 170 268 166 269 170 269 171 269 171 270 56 270 172 270 166 271 171 271 172 271 56 272 61 272 172 272 56 273 171 273 173 273 54 274 56 274 173 274 170 275 140 275 173 275 171 276 170 276 173 276 140 277 54 277 173 277 98 278 172 278 174 278 72 279 141 279 174 279 172 280 61 280 174 280 61 281 65 281 174 281 65 282 67 282 174 282 141 283 98 283 174 283 67 284 72 284 174 284 175 285 176 285 177 285 176 286 151 286 177 286 153 287 104 287 177 287 178 288 179 288 35 288 104 289 102 289 177 289 99 290 175 290 177 290 102 291 99 291 177 291 151 292 153 292 177 292 172 293 98 293 180 293 169 294 178 294 35 294 162 295 123 295 180 295 29 296 169 296 35 296 158 297 162 297 180 297 98 298 158 298 180 298 123 299 129 299 180 299 180 300 129 300 181 300 129 301 131 301 181 301 172 302 180 302 181 302 181 303 131 303 182 303 131 304 134 304 182 304 137 305 165 305 183 305 166 306 172 306 183 306 172 307 181 307 183 307 134 308 137 308 183 308 181 309 182 309 183 309 182 310 134 310 183 310 165 311 166 311 183 311 179 312 184 312 40 312 184 313 185 313 40 313 185 314 186 314 40 314 35 315 179 315 40 315 40 316 186 316 45 316 186 317 187 317 45 317 187 318 188 318 45 318 188 319 189 319 45 319 190 320 191 320 50 320 189 321 190 321 50 321 45 322 189 322 50 322 191 323 192 323 58 323 192 324 193 324 58 324 193 325 194 325 58 325 50 326 191 326 58 326 58 327 194 327 63 327 194 328 195 328 63 328 195 329 196 329 63 329 196 330 197 330 63 330 63 331 197 331 74 331 198 332 199 332 74 332 197 333 198 333 74 333 199 334 200 334 81 334 200 335 201 335 81 335 201 336 202 336 81 336 74 337 199 337 81 337 202 338 203 338 87 338 203 339 204 339 87 339 204 340 205 340 87 340 81 341 202 341 87 341 206 342 207 342 93 342 87 343 205 343 93 343 205 344 206 344 93 344 207 345 175 345 99 345 93 346 207 346 99 346 106 347 121 347 107 347 121 348 106 348 120 348 120 349 98 349 106 349 107 350 121 350 111 350 121 351 208 351 111 351 111 352 208 352 113 352 208 353 9 353 116 353 113 354 208 354 116 354 116 355 9 355 118 355 4 356 3 356 122 356 208 357 121 357 122 357 118 358 9 358 209 358 159 359 118 359 209 359 9 360 11 360 209 360 159 361 209 361 161 361 122 362 3 362 10 362 9 363 208 363 10 363 3 364 6 364 10 364 208 365 122 365 10 365 209 366 11 366 12 366 11 367 13 367 12 367 15 368 161 368 12 368 161 369 209 369 12 369 210 370 211 370 212 370 213 371 214 371 215 371 213 372 215 372 216 372 217 373 218 373 219 373 217 374 219 374 220 374 221 375 222 375 214 375 221 376 223 376 222 376 224 377 225 377 226 377 221 378 227 378 223 378 224 379 226 379 228 379 229 380 230 380 231 380 232 381 212 381 233 381 229 382 231 382 234 382 232 383 210 383 212 383 235 384 233 384 236 384 237 385 234 385 238 385 237 386 238 386 239 386 235 387 236 387 218 387 240 388 228 388 241 388 240 389 241 389 210 389 242 390 230 390 229 390 242 391 243 391 230 391 244 392 216 392 243 392 240 393 210 393 232 393 244 394 213 394 216 394 245 395 239 395 246 395 247 396 217 396 220 396 245 397 237 397 239 397 248 398 218 398 217 398 248 399 235 399 218 399 249 400 221 400 214 400 249 401 214 401 213 401 250 402 251 402 252 402 249 403 227 403 221 403 250 404 252 404 253 404 250 405 225 405 224 405 254 406 245 406 246 406 250 407 253 407 225 407 254 408 255 408 256 408 254 409 246 409 255 409 257 410 240 410 232 410 258 411 242 411 229 411 259 412 233 412 235 412 259 413 232 413 233 413 260 414 234 414 237 414 261 415 220 415 262 415 260 416 229 416 234 416 263 417 264 417 227 417 263 418 249 418 213 418 261 419 247 419 220 419 263 420 213 420 244 420 263 421 227 421 249 421 265 422 228 422 240 422 265 423 224 423 228 423 266 424 244 424 243 424 266 425 243 425 242 425 267 426 248 426 217 426 267 427 217 427 247 427 268 428 237 428 245 428 268 429 260 429 237 429 269 430 259 430 235 430 269 431 235 431 248 431 270 432 245 432 254 432 271 433 265 433 240 433 270 434 268 434 245 434 272 435 242 435 258 435 271 436 240 436 257 436 272 437 266 437 242 437 273 438 257 438 232 438 273 439 232 439 259 439 274 440 258 440 229 440 274 441 229 441 260 441 275 442 264 442 263 442 276 443 261 443 262 443 275 444 263 444 244 444 277 445 247 445 261 445 275 446 244 446 266 446 278 447 256 447 279 447 278 448 254 448 256 448 277 449 267 449 247 449 278 450 270 450 254 450 280 451 224 451 265 451 280 452 281 452 251 452 280 453 251 453 250 453 282 454 260 454 268 454 280 455 250 455 224 455 283 456 248 456 267 456 283 457 269 457 248 457 282 458 274 458 260 458 284 459 268 459 270 459 285 460 259 460 269 460 285 461 273 461 259 461 284 462 282 462 268 462 286 463 266 463 272 463 286 464 287 464 264 464 286 465 275 465 266 465 285 466 269 466 283 466 286 467 264 467 275 467 288 468 265 468 271 468 288 469 281 469 280 469 289 470 272 470 258 470 288 471 280 471 265 471 289 472 258 472 274 472 290 473 257 473 273 473 290 474 271 474 257 474 291 475 276 475 262 475 292 476 270 476 278 476 292 477 284 477 270 477 291 478 262 478 293 478 294 479 289 479 274 479 294 480 274 480 282 480 295 481 276 481 291 481 295 482 277 482 261 482 296 483 294 483 282 483 295 484 261 484 276 484 297 485 267 485 277 485 296 486 282 486 284 486 297 487 283 487 267 487 298 488 286 488 272 488 298 489 272 489 289 489 299 490 285 490 283 490 298 491 287 491 286 491 299 492 283 492 297 492 300 493 279 493 301 493 302 494 290 494 273 494 300 495 278 495 279 495 302 496 273 496 285 496 300 497 292 497 278 497 303 498 284 498 292 498 303 499 296 499 284 499 304 500 291 500 293 500 305 501 289 501 294 501 306 502 307 502 281 502 305 503 287 503 298 503 305 504 308 504 287 504 306 505 281 505 288 505 305 506 298 506 289 506 306 507 288 507 271 507 306 508 271 508 290 508 309 509 295 509 291 509 310 510 305 510 294 510 310 511 294 511 296 511 311 512 303 512 292 512 311 513 292 513 300 513 312 514 297 514 277 514 312 515 277 515 295 515 312 516 295 516 309 516 313 517 296 517 303 517 314 518 297 518 312 518 314 519 299 519 297 519 315 520 308 520 305 520 316 521 290 521 302 521 315 522 305 522 310 522 316 523 306 523 290 523 315 524 317 524 308 524 316 525 307 525 306 525 318 526 300 526 301 526 319 527 285 527 299 527 319 528 302 528 285 528 318 529 301 529 320 529 319 530 316 530 302 530 321 531 303 531 311 531 322 532 304 532 293 532 322 533 293 533 323 533 321 534 313 534 303 534 324 535 296 535 313 535 324 536 310 536 296 536 325 537 304 537 322 537 325 538 309 538 291 538 325 539 291 539 304 539 326 540 311 540 300 540 326 541 300 541 318 541 327 542 312 542 309 542 328 543 314 543 312 543 329 544 324 544 313 544 329 545 313 545 321 545 328 546 312 546 327 546 330 547 310 547 324 547 331 548 319 548 299 548 330 549 315 549 310 549 331 550 299 550 314 550 330 551 317 551 315 551 330 552 332 552 317 552 333 553 334 553 335 553 333 554 320 554 334 554 333 555 318 555 320 555 336 556 322 556 323 556 337 557 338 557 307 557 337 558 307 558 316 558 339 559 321 559 311 559 337 560 316 560 319 560 340 561 325 561 322 561 339 562 311 562 326 562 341 563 324 563 329 563 340 564 322 564 336 564 341 565 330 565 324 565 342 566 325 566 340 566 342 567 309 567 325 567 342 568 327 568 309 568 343 569 326 569 318 569 343 570 318 570 333 570 344 571 328 571 327 571 344 572 327 572 342 572 345 573 329 573 321 573 346 574 331 574 314 574 345 575 321 575 339 575 346 576 314 576 328 576 346 577 328 577 344 577 347 578 338 578 337 578 348 579 335 579 349 579 347 580 319 580 331 580 348 581 333 581 335 581 347 582 337 582 319 582 348 583 343 583 333 583 350 584 332 584 330 584 350 585 330 585 341 585 351 586 340 586 336 586 352 587 351 587 336 587 352 588 323 588 353 588 354 589 339 589 326 589 354 590 326 590 343 590 352 591 336 591 323 591 355 592 340 592 351 592 356 593 341 593 329 593 356 594 329 594 345 594 355 595 342 595 340 595 357 596 344 596 342 596 357 597 342 597 355 597 358 598 343 598 348 598 358 599 354 599 343 599 359 600 352 600 353 600 360 601 345 601 339 601 360 602 339 602 354 602 361 603 346 603 344 603 362 604 358 604 348 604 363 605 347 605 331 605 363 606 364 606 338 606 362 607 348 607 349 607 363 608 346 608 361 608 365 609 341 609 356 609 363 610 338 610 347 610 365 611 366 611 332 611 363 612 331 612 346 612 365 613 332 613 350 613 365 614 350 614 341 614 367 615 355 615 351 615 368 616 354 616 358 616 369 617 367 617 351 617 370 618 345 618 360 618 370 619 356 619 345 619 369 620 351 620 352 620 371 621 357 621 355 621 371 622 355 622 367 622 372 623 358 623 362 623 373 624 344 624 357 624 372 625 368 625 358 625 373 626 357 626 371 626 373 627 361 627 344 627 374 628 369 628 352 628 375 629 360 629 354 629 374 630 352 630 359 630 375 631 354 631 368 631 376 632 349 632 377 632 378 633 363 633 361 633 376 634 362 634 349 634 378 635 364 635 363 635 379 636 359 636 353 636 380 637 381 637 366 637 379 638 353 638 382 638 380 639 366 639 365 639 380 640 365 640 356 640 380 641 356 641 370 641 383 642 368 642 372 642 384 643 371 643 367 643 385 644 367 644 369 644 386 645 377 645 387 645 386 646 376 646 377 646 388 647 389 647 364 647 390 648 360 648 375 648 388 649 364 649 378 649 388 650 361 650 373 650 388 651 378 651 361 651 390 652 370 652 360 652 391 653 372 653 362 653 392 654 373 654 371 654 392 655 371 655 384 655 392 656 388 656 373 656 391 657 376 657 386 657 391 658 362 658 376 658 393 659 385 659 369 659 393 660 369 660 374 660 394 661 368 661 383 661 395 662 374 662 359 662 394 663 375 663 368 663 395 664 359 664 379 664 396 665 392 665 384 665 397 666 391 666 386 666 398 667 367 667 385 667 398 668 385 668 393 668 399 669 386 669 387 669 398 670 384 670 367 670 400 671 370 671 390 671 398 672 396 672 384 672 400 673 401 673 381 673 402 674 389 674 388 674 400 675 381 675 380 675 402 676 388 676 392 676 400 677 380 677 370 677 402 678 392 678 396 678 403 679 372 679 391 679 403 680 383 680 372 680 404 681 379 681 382 681 403 682 391 682 397 682 404 683 382 683 405 683 404 684 395 684 379 684 406 685 387 685 407 685 406 686 399 686 387 686 408 687 398 687 393 687 409 688 374 688 395 688 410 689 390 689 375 689 410 690 375 690 394 690 409 691 393 691 374 691 411 692 412 692 389 692 413 693 403 693 397 693 411 694 389 694 402 694 411 695 402 695 396 695 414 696 396 696 398 696 415 697 397 697 386 697 415 698 386 698 399 698 414 699 411 699 396 699 416 700 409 700 395 700 417 701 383 701 403 701 417 702 394 702 383 702 417 703 403 703 413 703 416 704 395 704 404 704 418 705 398 705 408 705 419 706 406 706 407 706 418 707 414 707 398 707 420 708 399 708 406 708 421 709 408 709 393 709 421 710 393 710 409 710 420 711 415 711 399 711 421 712 418 712 408 712 422 713 411 713 414 713 422 714 412 714 411 714 423 715 401 715 400 715 423 716 424 716 401 716 423 717 400 717 390 717 425 718 405 718 426 718 423 719 390 719 410 719 427 720 417 720 413 720 425 721 404 721 405 721 428 722 409 722 416 722 429 723 397 723 415 723 429 724 413 724 397 724 428 725 421 725 409 725 430 726 422 726 414 726 429 727 415 727 420 727 430 728 431 728 412 728 430 729 412 729 422 729 430 730 414 730 418 730 432 731 407 731 433 731 432 732 419 732 407 732 434 733 418 733 421 733 435 734 410 734 394 734 436 735 404 735 425 735 435 736 394 736 417 736 435 737 417 737 427 737 437 738 406 738 419 738 436 739 416 739 404 739 437 740 419 740 432 740 438 741 421 741 428 741 437 742 420 742 406 742 438 743 434 743 421 743 439 744 431 744 430 744 440 745 429 745 420 745 439 746 430 746 418 746 439 747 418 747 434 747 439 748 441 748 431 748 442 749 425 749 426 749 443 750 435 750 427 750 444 751 427 751 413 751 442 752 426 752 445 752 444 753 413 753 429 753 444 754 429 754 440 754 446 755 416 755 436 755 446 756 428 756 416 756 447 757 434 757 438 757 448 758 432 758 433 758 447 759 439 759 434 759 449 760 437 760 432 760 450 761 425 761 442 761 449 762 432 762 448 762 451 763 424 763 423 763 451 764 452 764 424 764 451 765 410 765 435 765 451 766 423 766 410 766 450 767 436 767 425 767 451 768 435 768 443 768 453 769 438 769 428 769 453 770 428 770 446 770 454 771 420 771 437 771 454 772 440 772 420 772 454 773 437 773 449 773 455 774 439 774 447 774 455 775 441 775 439 775 455 776 456 776 441 776 457 777 444 777 440 777 457 778 440 778 454 778 458 779 442 779 445 779 459 780 452 780 451 780 459 781 451 781 443 781 458 782 445 782 460 782 461 783 427 783 444 783 461 784 443 784 427 784 462 785 446 785 436 785 463 786 433 786 464 786 462 787 436 787 450 787 463 788 448 788 433 788 465 789 438 789 453 789 465 790 447 790 438 790 466 791 449 791 448 791 467 792 449 792 466 792 468 793 442 793 458 793 468 794 450 794 442 794 467 795 454 795 449 795 469 796 454 796 467 796 470 797 453 797 446 797 469 798 457 798 454 798 470 799 446 799 462 799 471 800 461 800 444 800 471 801 444 801 457 801 472 802 458 802 460 802 472 803 473 803 474 803 472 804 460 804 473 804 475 805 463 805 464 805 476 806 455 806 447 806 477 807 452 807 459 807 476 808 456 808 455 808 477 809 459 809 443 809 476 810 447 810 465 810 477 811 478 811 452 811 477 812 443 812 461 812 479 813 462 813 450 813 480 814 466 814 448 814 479 815 450 815 468 815 481 816 465 816 453 816 480 817 448 817 463 817 481 818 453 818 470 818 482 819 468 819 458 819 483 820 467 820 466 820 484 821 469 821 467 821 482 822 458 822 472 822 484 823 467 823 483 823 485 824 461 824 471 824 485 825 477 825 461 825 486 826 462 826 479 826 485 827 478 827 477 827 486 828 470 828 462 828 487 829 457 829 469 829 487 830 471 830 457 830 487 831 469 831 484 831 488 832 474 832 489 832 488 833 472 833 474 833 488 834 482 834 472 834 490 835 464 835 491 835 492 836 493 836 456 836 490 837 475 837 464 837 492 838 465 838 481 838 492 839 456 839 476 839 492 840 476 840 465 840 494 841 463 841 475 841 495 842 468 842 482 842 494 843 480 843 463 843 495 844 479 844 468 844 496 845 466 845 480 845 496 846 483 846 466 846 497 847 481 847 470 847 497 848 470 848 486 848 498 849 483 849 496 849 498 850 484 850 483 850 499 851 484 851 498 851 500 852 495 852 482 852 499 853 487 853 484 853 500 854 482 854 488 854 501 855 486 855 479 855 501 856 479 856 495 856 502 857 490 857 491 857 503 858 488 858 489 858 504 859 471 859 487 859 504 860 485 860 471 860 504 861 478 861 485 861 504 862 505 862 478 862 504 863 487 863 499 863 506 864 507 864 493 864 508 865 475 865 490 865 506 866 481 866 497 866 506 867 493 867 492 867 506 868 492 868 481 868 508 869 494 869 475 869 508 870 490 870 502 870 509 871 480 871 494 871 510 872 495 872 500 872 509 873 496 873 480 873 511 874 498 874 496 874 512 875 489 875 513 875 512 876 503 876 489 876 511 877 496 877 509 877 514 878 486 878 501 878 514 879 497 879 486 879 515 880 499 880 498 880 516 881 505 881 504 881 516 882 504 882 499 882 516 883 499 883 515 883 517 884 488 884 503 884 517 885 500 885 488 885 518 886 508 886 502 886 519 887 501 887 495 887 520 888 491 888 521 888 519 889 495 889 510 889 520 890 502 890 491 890 522 891 517 891 503 891 523 892 508 892 518 892 523 893 494 893 508 893 522 894 503 894 512 894 523 895 509 895 494 895 524 896 512 896 513 896 525 897 511 897 509 897 526 898 497 898 514 898 526 899 527 899 507 899 526 900 507 900 506 900 526 901 506 901 497 901 528 902 520 902 521 902 529 903 510 903 500 903 530 904 498 904 511 904 530 905 515 905 498 905 529 906 500 906 517 906 531 907 532 907 505 907 531 908 505 908 516 908 531 909 516 909 515 909 533 910 513 910 534 910 533 911 524 911 513 911 535 912 501 912 519 912 536 913 523 913 518 913 535 914 514 914 501 914 537 915 518 915 502 915 538 916 517 916 522 916 537 917 502 917 520 917 538 918 529 918 517 918 539 919 522 919 512 919 540 920 523 920 536 920 539 921 512 921 524 921 540 922 509 922 523 922 540 923 525 923 509 923 541 924 519 924 510 924 542 925 530 925 511 925 541 926 510 926 529 926 542 927 511 927 525 927 541 928 529 928 538 928 543 929 537 929 520 929 544 930 533 930 534 930 543 931 520 931 528 931 545 932 524 932 533 932 545 933 539 933 524 933 546 934 532 934 531 934 546 935 515 935 530 935 546 936 531 936 515 936 547 937 521 937 548 937 549 938 550 938 527 938 547 939 528 939 521 939 549 940 514 940 535 940 551 941 540 941 536 941 549 942 526 942 514 942 549 943 527 943 526 943 552 944 541 944 538 944 553 945 522 945 539 945 553 946 538 946 522 946 554 947 518 947 537 947 554 948 536 948 518 948 555 949 546 949 530 949 555 950 530 950 542 950 555 951 532 951 546 951 555 952 556 952 532 952 557 953 544 953 534 953 558 954 525 954 540 954 557 955 534 955 559 955 558 956 542 956 525 956 558 957 540 957 551 957 560 958 519 958 541 958 561 959 554 959 537 959 560 960 535 960 519 960 562 961 533 961 544 961 561 962 537 962 543 962 562 963 545 963 533 963 563 964 543 964 528 964 562 965 544 965 557 965 564 966 539 966 545 966 563 967 528 967 547 967 564 968 545 968 562 968 565 969 558 969 551 969 564 970 553 970 539 970 566 971 541 971 552 971 567 972 536 972 554 972 566 973 560 973 541 973 567 974 551 974 536 974 568 975 538 975 553 975 569 976 556 976 555 976 568 977 552 977 538 977 569 978 542 978 558 978 568 979 553 979 564 979 569 980 555 980 542 980 569 981 558 981 565 981 570 982 547 982 548 982 571 983 557 983 559 983 570 984 548 984 572 984 570 985 563 985 547 985 573 986 554 986 561 986 574 987 562 987 557 987 574 988 557 988 571 988 575 989 550 989 549 989 575 990 576 990 550 990 573 991 567 991 554 991 575 992 549 992 535 992 575 993 535 993 560 993 577 994 543 994 563 994 577 995 561 995 543 995 578 996 564 996 562 996 578 997 562 997 574 997 579 998 556 998 569 998 580 999 581 999 582 999 579 1000 569 1000 565 1000 579 1001 583 1001 556 1001 584 1002 568 1002 564 1002 585 1003 551 1003 567 1003 584 1004 564 1004 578 1004 585 1005 565 1005 551 1005 586 1006 576 1006 575 1006 586 1007 560 1007 566 1007 586 1008 575 1008 560 1008 587 1009 566 1009 552 1009 587 1010 552 1010 568 1010 588 1011 577 1011 563 1011 588 1012 563 1012 570 1012 589 1013 567 1013 573 1013 589 1014 585 1014 567 1014 590 1015 559 1015 591 1015 590 1016 571 1016 559 1016 592 1017 561 1017 577 1017 592 1018 573 1018 561 1018 593 1019 574 1019 571 1019 594 1020 578 1020 574 1020 594 1021 574 1021 593 1021 595 1022 579 1022 565 1022 595 1023 583 1023 579 1023 596 1024 578 1024 594 1024 595 1025 565 1025 585 1025 596 1026 584 1026 578 1026 597 1027 572 1027 598 1027 597 1028 588 1028 570 1028 597 1029 570 1029 572 1029 599 1030 568 1030 584 1030 599 1031 587 1031 568 1031 600 1032 592 1032 577 1032 601 1033 580 1033 582 1033 600 1034 577 1034 588 1034 602 1035 590 1035 591 1035 603 1036 604 1036 583 1036 601 1037 582 1037 605 1037 603 1038 585 1038 589 1038 603 1039 583 1039 595 1039 606 1040 607 1040 576 1040 603 1041 595 1041 585 1041 608 1042 609 1042 580 1042 606 1043 566 1043 587 1043 606 1044 576 1044 586 1044 606 1045 586 1045 566 1045 610 1046 573 1046 592 1046 610 1047 589 1047 573 1047 608 1048 580 1048 601 1048 611 1049 571 1049 590 1049 612 1050 601 1050 605 1050 611 1051 593 1051 571 1051 613 1052 594 1052 593 1052 614 1053 588 1053 597 1053 612 1054 615 1054 616 1054 612 1055 605 1055 615 1055 614 1056 600 1056 588 1056 617 1057 609 1057 608 1057 618 1058 596 1058 594 1058 617 1059 619 1059 609 1059 620 1060 610 1060 592 1060 620 1061 592 1061 600 1061 618 1062 594 1062 613 1062 621 1063 587 1063 599 1063 622 1064 623 1064 604 1064 621 1065 606 1065 587 1065 622 1066 604 1066 603 1066 624 1067 601 1067 612 1067 622 1068 603 1068 589 1068 624 1069 608 1069 601 1069 621 1070 607 1070 606 1070 622 1071 589 1071 610 1071 625 1072 584 1072 596 1072 626 1073 598 1073 627 1073 625 1074 599 1074 584 1074 626 1075 597 1075 598 1075 625 1076 596 1076 618 1076 628 1077 629 1077 619 1077 630 1078 602 1078 591 1078 628 1079 631 1079 629 1079 628 1080 619 1080 617 1080 632 1081 600 1081 614 1081 633 1082 612 1082 616 1082 632 1083 620 1083 600 1083 630 1084 591 1084 634 1084 633 1085 624 1085 612 1085 635 1086 611 1086 590 1086 636 1087 610 1087 620 1087 637 1088 617 1088 608 1088 635 1089 590 1089 602 1089 636 1090 622 1090 610 1090 637 1091 608 1091 624 1091 638 1092 597 1092 626 1092 639 1093 631 1093 628 1093 640 1094 613 1094 593 1094 640 1095 593 1095 611 1095 638 1096 614 1096 597 1096 641 1097 618 1097 613 1097 639 1098 642 1098 631 1098 643 1099 620 1099 632 1099 644 1100 637 1100 624 1100 643 1101 636 1101 620 1101 645 1102 618 1102 641 1102 646 1103 622 1103 636 1103 644 1104 624 1104 633 1104 645 1105 625 1105 618 1105 646 1106 623 1106 622 1106 647 1107 648 1107 649 1107 650 1108 628 1108 617 1108 647 1109 627 1109 648 1109 651 1110 630 1110 634 1110 650 1111 639 1111 628 1111 650 1112 617 1112 637 1112 647 1113 626 1113 627 1113 652 1114 621 1114 599 1114 652 1115 653 1115 607 1115 654 1116 614 1116 638 1116 652 1117 607 1117 621 1117 655 1118 616 1118 656 1118 652 1119 625 1119 645 1119 652 1120 599 1120 625 1120 655 1121 633 1121 616 1121 654 1122 632 1122 614 1122 657 1123 602 1123 630 1123 658 1124 642 1124 639 1124 657 1125 635 1125 602 1125 659 1126 636 1126 643 1126 658 1127 660 1127 642 1127 659 1128 646 1128 636 1128 658 1129 661 1129 660 1129 662 1130 637 1130 644 1130 663 1131 635 1131 657 1131 663 1132 611 1132 635 1132 664 1133 626 1133 647 1133 662 1134 650 1134 637 1134 663 1135 640 1135 611 1135 664 1136 638 1136 626 1136 665 1137 656 1137 666 1137 667 1138 641 1138 613 1138 668 1139 632 1139 654 1139 667 1140 613 1140 640 1140 665 1141 655 1141 656 1141 669 1142 639 1142 650 1142 667 1143 640 1143 663 1143 669 1144 658 1144 639 1144 670 1145 645 1145 641 1145 668 1146 643 1146 632 1146 671 1147 653 1147 652 1147 672 1148 664 1148 647 1148 671 1149 652 1149 645 1149 673 1150 644 1150 633 1150 671 1151 645 1151 670 1151 672 1152 647 1152 649 1152 673 1153 633 1153 655 1153 674 1154 623 1154 646 1154 674 1155 646 1155 659 1155 674 1156 675 1156 623 1156 676 1157 657 1157 630 1157 677 1158 638 1158 664 1158 678 1159 650 1159 662 1159 677 1160 654 1160 638 1160 678 1161 669 1161 650 1161 676 1162 630 1162 651 1162 679 1163 651 1163 634 1163 680 1164 673 1164 655 1164 679 1165 634 1165 681 1165 682 1166 659 1166 643 1166 683 1167 663 1167 657 1167 682 1168 643 1168 668 1168 682 1169 674 1169 659 1169 680 1170 655 1170 665 1170 684 1171 663 1171 683 1171 685 1172 664 1172 672 1172 686 1173 665 1173 666 1173 687 1174 658 1174 669 1174 687 1175 661 1175 658 1175 684 1176 667 1176 663 1176 685 1177 677 1177 664 1177 687 1178 688 1178 661 1178 689 1179 654 1179 677 1179 689 1180 668 1180 654 1180 690 1181 644 1181 673 1181 690 1182 662 1182 644 1182 691 1183 679 1183 681 1183 692 1184 641 1184 667 1184 693 1185 649 1185 694 1185 692 1186 670 1186 641 1186 695 1187 686 1187 666 1187 696 1188 697 1188 653 1188 693 1189 672 1189 649 1189 695 1190 666 1190 698 1190 696 1191 671 1191 670 1191 696 1192 653 1192 671 1192 699 1193 675 1193 674 1193 699 1194 674 1194 682 1194 699 1195 700 1195 675 1195 701 1196 687 1196 669 1196 702 1197 657 1197 676 1197 703 1198 689 1198 677 1198 701 1199 669 1199 678 1199 703 1200 677 1200 685 1200 702 1201 683 1201 657 1201 704 1202 673 1202 680 1202 704 1203 690 1203 673 1203 705 1204 676 1204 651 1204 706 1205 668 1205 689 1205 705 1206 651 1206 679 1206 706 1207 682 1207 668 1207 707 1208 680 1208 665 1208 708 1209 685 1209 672 1209 707 1210 665 1210 686 1210 709 1211 684 1211 683 1211 708 1212 672 1212 693 1212 710 1213 662 1213 690 1213 710 1214 678 1214 662 1214 711 1215 689 1215 703 1215 710 1216 690 1216 704 1216 712 1217 667 1217 684 1217 711 1218 706 1218 689 1218 712 1219 692 1219 667 1219 713 1220 695 1220 698 1220 714 1221 694 1221 715 1221 714 1222 693 1222 694 1222 716 1223 679 1223 691 1223 716 1224 705 1224 679 1224 717 1225 707 1225 686 1225 718 1226 697 1226 696 1226 717 1227 686 1227 695 1227 718 1228 670 1228 692 1228 719 1229 682 1229 706 1229 718 1230 696 1230 670 1230 719 1231 699 1231 682 1231 719 1232 700 1232 699 1232 719 1233 720 1233 700 1233 721 1234 687 1234 701 1234 722 1235 681 1235 723 1235 724 1236 703 1236 685 1236 721 1237 688 1237 687 1237 722 1238 691 1238 681 1238 721 1239 725 1239 688 1239 722 1240 716 1240 691 1240 724 1241 685 1241 708 1241 726 1242 710 1242 704 1242 727 1243 683 1243 702 1243 728 1244 715 1244 729 1244 727 1245 709 1245 683 1245 728 1246 714 1246 715 1246 730 1247 704 1247 680 1247 730 1248 680 1248 707 1248 731 1249 676 1249 705 1249 731 1250 702 1250 676 1250 732 1251 706 1251 711 1251 732 1252 719 1252 706 1252 733 1253 713 1253 698 1253 734 1254 718 1254 692 1254 734 1255 735 1255 697 1255 736 1256 708 1256 693 1256 733 1257 698 1257 737 1257 734 1258 697 1258 718 1258 738 1259 678 1259 710 1259 734 1260 692 1260 712 1260 738 1261 721 1261 701 1261 736 1262 693 1262 714 1262 739 1263 684 1263 709 1263 740 1264 711 1264 703 1264 738 1265 701 1265 678 1265 739 1266 712 1266 684 1266 741 1267 713 1267 733 1267 740 1268 703 1268 724 1268 741 1269 717 1269 695 1269 742 1270 731 1270 705 1270 741 1271 695 1271 713 1271 743 1272 714 1272 728 1272 744 1273 707 1273 717 1273 742 1274 705 1274 716 1274 745 1275 716 1275 722 1275 743 1276 736 1276 714 1276 744 1277 730 1277 707 1277 745 1278 742 1278 716 1278 746 1279 739 1279 709 1279 747 1280 728 1280 729 1280 748 1281 710 1281 726 1281 747 1282 743 1282 728 1282 748 1283 738 1283 710 1283 746 1284 709 1284 727 1284 749 1285 750 1285 720 1285 751 1286 727 1286 702 1286 752 1287 704 1287 730 1287 749 1288 719 1288 732 1288 749 1289 720 1289 719 1289 752 1290 726 1290 704 1290 751 1291 731 1291 742 1291 753 1292 724 1292 708 1292 754 1293 733 1293 737 1293 751 1294 702 1294 731 1294 755 1295 734 1295 712 1295 753 1296 708 1296 736 1296 755 1297 712 1297 739 1297 753 1298 736 1298 743 1298 755 1299 735 1299 734 1299 756 1300 729 1300 757 1300 758 1301 741 1301 733 1301 759 1302 745 1302 722 1302 756 1303 747 1303 729 1303 759 1304 723 1304 760 1304 761 1305 721 1305 738 1305 759 1306 722 1306 723 1306 762 1307 732 1307 711 1307 761 1308 725 1308 721 1308 762 1309 711 1309 740 1309 761 1310 763 1310 725 1310 764 1311 717 1311 741 1311 765 1312 751 1312 742 1312 764 1313 744 1313 717 1313 764 1314 741 1314 758 1314 766 1315 742 1315 745 1315 767 1316 753 1316 743 1316 768 1317 752 1317 730 1317 769 1318 767 1318 743 1318 768 1319 730 1319 744 1319 768 1320 744 1320 764 1320 770 1321 771 1321 735 1321 770 1322 735 1322 755 1322 770 1323 755 1323 739 1323 769 1324 743 1324 747 1324 772 1325 738 1325 748 1325 770 1326 739 1326 746 1326 772 1327 763 1327 761 1327 773 1328 727 1328 751 1328 774 1329 753 1329 767 1329 772 1330 761 1330 738 1330 773 1331 746 1331 727 1331 774 1332 740 1332 724 1332 775 1333 726 1333 752 1333 774 1334 724 1334 753 1334 776 1335 745 1335 759 1335 775 1336 748 1336 726 1336 777 1337 754 1337 737 1337 778 1338 756 1338 757 1338 777 1339 737 1339 779 1339 776 1340 766 1340 745 1340 780 1341 769 1341 747 1341 781 1342 773 1342 751 1342 782 1343 754 1343 777 1343 781 1344 751 1344 765 1344 782 1345 733 1345 754 1345 780 1346 747 1346 756 1346 783 1347 765 1347 742 1347 782 1348 758 1348 733 1348 783 1349 742 1349 766 1349 784 1350 732 1350 762 1350 785 1351 764 1351 758 1351 784 1352 786 1352 750 1352 784 1353 750 1353 749 1353 784 1354 749 1354 732 1354 787 1355 770 1355 746 1355 788 1356 768 1356 764 1356 788 1357 764 1357 785 1357 787 1358 771 1358 770 1358 789 1359 774 1359 767 1359 787 1360 746 1360 773 1360 790 1361 767 1361 769 1361 791 1362 759 1362 760 1362 792 1363 752 1363 768 1363 792 1364 775 1364 752 1364 791 1365 760 1365 793 1365 790 1366 789 1366 767 1366 791 1367 776 1367 759 1367 794 1368 757 1368 795 1368 794 1369 778 1369 757 1369 796 1370 783 1370 766 1370 797 1371 777 1371 779 1371 796 1372 766 1372 776 1372 798 1373 740 1373 774 1373 799 1374 772 1374 748 1374 800 1375 801 1375 771 1375 799 1376 763 1376 772 1376 800 1377 773 1377 781 1377 799 1378 748 1378 775 1378 800 1379 771 1379 787 1379 799 1380 802 1380 763 1380 800 1381 787 1381 773 1381 798 1382 762 1382 740 1382 803 1383 782 1383 777 1383 804 1384 781 1384 765 1384 805 1385 780 1385 756 1385 804 1386 765 1386 783 1386 805 1387 756 1387 778 1387 805 1388 778 1388 794 1388 806 1389 769 1389 780 1389 807 1390 758 1390 782 1390 806 1391 790 1391 769 1391 807 1392 785 1392 758 1392 807 1393 782 1393 803 1393 808 1394 776 1394 791 1394 808 1395 796 1395 776 1395 809 1396 788 1396 785 1396 810 1397 798 1397 774 1397 811 1398 783 1398 796 1398 810 1399 774 1399 789 1399 812 1400 802 1400 799 1400 813 1401 790 1401 806 1401 812 1402 775 1402 792 1402 813 1403 789 1403 790 1403 814 1404 781 1404 804 1404 812 1405 799 1405 775 1405 815 1406 788 1406 809 1406 814 1407 801 1407 800 1407 813 1408 810 1408 789 1408 814 1409 800 1409 781 1409 815 1410 768 1410 788 1410 816 1411 794 1411 795 1411 815 1412 792 1412 768 1412 817 1413 793 1413 818 1413 817 1414 791 1414 793 1414 819 1415 797 1415 779 1415 817 1416 808 1416 791 1416 820 1417 805 1417 794 1417 819 1418 779 1418 821 1418 822 1419 796 1419 808 1419 822 1420 811 1420 796 1420 823 1421 803 1421 777 1421 824 1422 762 1422 798 1422 823 1423 797 1423 819 1423 824 1424 825 1424 786 1424 823 1425 777 1425 797 1425 826 1426 804 1426 783 1426 824 1427 786 1427 784 1427 827 1428 807 1428 803 1428 826 1429 783 1429 811 1429 824 1430 784 1430 762 1430 828 1431 806 1431 780 1431 827 1432 803 1432 823 1432 828 1433 780 1433 805 1433 828 1434 805 1434 820 1434 829 1435 813 1435 806 1435 830 1436 807 1436 827 1436 831 1437 808 1437 817 1437 831 1438 822 1438 808 1438 830 1439 809 1439 785 1439 830 1440 785 1440 807 1440 832 1441 825 1441 824 1441 833 1442 811 1442 822 1442 834 1443 815 1443 809 1443 832 1444 824 1444 798 1444 835 1445 836 1445 801 1445 832 1446 798 1446 810 1446 837 1447 810 1447 813 1447 835 1448 804 1448 826 1448 837 1449 832 1449 810 1449 835 1450 801 1450 814 1450 835 1451 814 1451 804 1451 838 1452 819 1452 821 1452 839 1453 840 1453 841 1453 842 1454 795 1454 843 1454 844 1455 802 1455 812 1455 839 1456 818 1456 840 1456 844 1457 815 1457 834 1457 844 1458 812 1458 792 1458 839 1459 817 1459 818 1459 842 1460 816 1460 795 1460 844 1461 792 1461 815 1461 844 1462 845 1462 802 1462 846 1463 820 1463 794 1463 847 1464 822 1464 831 1464 848 1465 823 1465 819 1465 846 1466 794 1466 816 1466 849 1467 828 1467 820 1467 850 1468 823 1468 848 1468 851 1469 826 1469 811 1469 850 1470 827 1470 823 1470 851 1471 811 1471 833 1471 852 1472 806 1472 828 1472 853 1473 817 1473 839 1473 852 1474 829 1474 806 1474 852 1475 828 1475 849 1475 854 1476 830 1476 827 1476 854 1477 827 1477 850 1477 855 1478 837 1478 813 1478 856 1479 809 1479 830 1479 856 1480 830 1480 854 1480 853 1481 831 1481 817 1481 857 1482 822 1482 847 1482 856 1483 834 1483 809 1483 855 1484 813 1484 829 1484 858 1485 844 1485 834 1485 858 1486 845 1486 844 1486 859 1487 842 1487 843 1487 857 1488 833 1488 822 1488 860 1489 839 1489 841 1489 861 1490 825 1490 832 1490 862 1491 819 1491 838 1491 861 1492 863 1492 825 1492 862 1493 848 1493 819 1493 860 1494 841 1494 864 1494 861 1495 832 1495 837 1495 860 1496 853 1496 839 1496 865 1497 826 1497 851 1497 865 1498 866 1498 836 1498 867 1499 838 1499 821 1499 868 1500 816 1500 842 1500 865 1501 836 1501 835 1501 865 1502 835 1502 826 1502 868 1503 846 1503 816 1503 869 1504 847 1504 831 1504 867 1505 821 1505 870 1505 871 1506 820 1506 846 1506 872 1507 850 1507 848 1507 871 1508 849 1508 820 1508 869 1509 831 1509 853 1509 873 1510 833 1510 857 1510 874 1511 852 1511 849 1511 875 1512 854 1512 850 1512 875 1513 850 1513 872 1513 873 1514 851 1514 833 1514 876 1515 853 1515 860 1515 877 1516 837 1516 855 1516 877 1517 863 1517 861 1517 877 1518 861 1518 837 1518 878 1519 867 1519 870 1519 879 1520 829 1520 852 1520 879 1521 855 1521 829 1521 876 1522 869 1522 853 1522 880 1523 856 1523 854 1523 879 1524 852 1524 874 1524 881 1525 858 1525 834 1525 882 1526 847 1526 869 1526 883 1527 843 1527 884 1527 881 1528 834 1528 856 1528 882 1529 857 1529 847 1529 881 1530 845 1530 858 1530 885 1531 860 1531 864 1531 881 1532 856 1532 880 1532 883 1533 859 1533 843 1533 881 1534 886 1534 845 1534 887 1535 859 1535 883 1535 885 1536 876 1536 860 1536 887 1537 842 1537 859 1537 888 1538 848 1538 862 1538 889 1539 851 1539 873 1539 888 1540 872 1540 848 1540 889 1541 890 1541 866 1541 887 1542 868 1542 842 1542 889 1543 866 1543 865 1543 889 1544 865 1544 851 1544 891 1545 846 1545 868 1545 892 1546 862 1546 838 1546 891 1547 871 1547 846 1547 892 1548 838 1548 867 1548 892 1549 867 1549 878 1549 893 1550 869 1550 876 1550 894 1551 873 1551 857 1551 895 1552 875 1552 872 1552 894 1553 857 1553 882 1553 896 1554 849 1554 871 1554 896 1555 874 1555 849 1555 897 1556 854 1556 875 1556 897 1557 875 1557 895 1557 897 1558 880 1558 854 1558 898 1559 879 1559 874 1559 899 1560 893 1560 876 1560 899 1561 876 1561 885 1561 900 1562 869 1562 893 1562 901 1563 883 1563 884 1563 900 1564 882 1564 869 1564 902 1565 892 1565 878 1565 903 1566 881 1566 880 1566 904 1567 879 1567 898 1567 903 1568 886 1568 881 1568 904 1569 905 1569 863 1569 904 1570 863 1570 877 1570 906 1571 885 1571 864 1571 904 1572 855 1572 879 1572 904 1573 877 1573 855 1573 907 1574 878 1574 870 1574 906 1575 864 1575 908 1575 907 1576 870 1576 909 1576 910 1577 873 1577 894 1577 910 1578 911 1578 890 1578 912 1579 887 1579 883 1579 913 1580 868 1580 887 1580 914 1581 895 1581 872 1581 910 1582 890 1582 889 1582 913 1583 891 1583 868 1583 914 1584 872 1584 888 1584 910 1585 889 1585 873 1585 915 1586 900 1586 893 1586 913 1587 887 1587 912 1587 916 1588 871 1588 891 1588 915 1589 893 1589 899 1589 916 1590 896 1590 871 1590 917 1591 892 1591 902 1591 917 1592 888 1592 862 1592 916 1593 891 1593 913 1593 917 1594 862 1594 892 1594 918 1595 903 1595 880 1595 919 1596 908 1596 920 1596 919 1597 906 1597 908 1597 921 1598 874 1598 896 1598 918 1599 880 1599 897 1599 921 1600 898 1600 874 1600 918 1601 886 1601 903 1601 922 1602 894 1602 882 1602 918 1603 923 1603 886 1603 922 1604 882 1604 900 1604 924 1605 897 1605 895 1605 925 1606 904 1606 898 1606 924 1607 918 1607 897 1607 925 1608 905 1608 904 1608 926 1609 899 1609 885 1609 927 1610 912 1610 883 1610 927 1611 883 1611 901 1611 928 1612 917 1612 902 1612 926 1613 885 1613 906 1613 929 1614 884 1614 930 1614 931 1615 922 1615 900 1615 931 1616 900 1616 915 1616 929 1617 901 1617 884 1617 932 1618 902 1618 878 1618 933 1619 913 1619 912 1619 932 1620 878 1620 907 1620 934 1621 924 1621 895 1621 934 1622 895 1622 914 1622 935 1623 906 1623 919 1623 935 1624 926 1624 906 1624 936 1625 916 1625 913 1625 937 1626 917 1626 928 1626 936 1627 913 1627 933 1627 937 1628 888 1628 917 1628 937 1629 914 1629 888 1629 938 1630 919 1630 920 1630 939 1631 923 1631 918 1631 940 1632 941 1632 911 1632 942 1633 929 1633 930 1633 939 1634 918 1634 924 1634 940 1635 894 1635 922 1635 940 1636 910 1636 894 1636 943 1637 932 1637 907 1637 940 1638 911 1638 910 1638 944 1639 921 1639 896 1639 945 1640 899 1640 926 1640 943 1641 909 1641 946 1641 945 1642 915 1642 899 1642 944 1643 896 1643 916 1643 943 1644 907 1644 909 1644 947 1645 898 1645 921 1645 947 1646 925 1646 898 1646 947 1647 905 1647 925 1647 948 1648 920 1648 949 1648 947 1649 950 1649 905 1649 951 1650 937 1650 928 1650 952 1651 933 1651 912 1651 948 1652 938 1652 920 1652 953 1653 922 1653 931 1653 952 1654 912 1654 927 1654 953 1655 940 1655 922 1655 954 1656 902 1656 932 1656 954 1657 928 1657 902 1657 955 1658 927 1658 901 1658 956 1659 924 1659 934 1659 956 1660 923 1660 939 1660 955 1661 901 1661 929 1661 956 1662 939 1662 924 1662 956 1663 957 1663 923 1663 958 1664 926 1664 935 1664 959 1665 934 1665 914 1665 958 1666 945 1666 926 1666 960 1667 933 1667 952 1667 959 1668 914 1668 937 1668 960 1669 936 1669 933 1669 959 1670 937 1670 951 1670 961 1671 935 1671 919 1671 961 1672 919 1672 938 1672 962 1673 932 1673 943 1673 963 1674 944 1674 916 1674 963 1675 916 1675 936 1675 963 1676 936 1676 960 1676 962 1677 954 1677 932 1677 964 1678 931 1678 915 1678 964 1679 915 1679 945 1679 965 1680 955 1680 929 1680 964 1681 945 1681 958 1681 966 1682 959 1682 951 1682 965 1683 929 1683 942 1683 967 1684 948 1684 949 1684 968 1685 951 1685 928 1685 968 1686 928 1686 954 1686 969 1687 947 1687 921 1687 969 1688 921 1688 944 1688 969 1689 950 1689 947 1689 970 1690 956 1690 934 1690 971 1691 938 1691 948 1691 970 1692 957 1692 956 1692 971 1693 961 1693 938 1693 972 1694 930 1694 973 1694 970 1695 959 1695 966 1695 970 1696 934 1696 959 1696 971 1697 948 1697 967 1697 974 1698 975 1698 941 1698 976 1699 943 1699 946 1699 974 1700 941 1700 940 1700 972 1701 942 1701 930 1701 977 1702 960 1702 952 1702 974 1703 940 1703 953 1703 976 1704 946 1704 978 1704 979 1705 964 1705 958 1705 980 1706 954 1706 962 1706 981 1707 961 1707 971 1707 982 1708 927 1708 955 1708 982 1709 952 1709 927 1709 980 1710 968 1710 954 1710 981 1711 935 1711 961 1711 983 1712 984 1712 957 1712 983 1713 970 1713 966 1713 981 1714 958 1714 935 1714 983 1715 957 1715 970 1715 985 1716 969 1716 944 1716 986 1717 949 1717 987 1717 985 1718 944 1718 963 1718 985 1719 988 1719 950 1719 989 1720 966 1720 951 1720 985 1721 950 1721 969 1721 986 1722 967 1722 949 1722 989 1723 951 1723 968 1723 990 1724 953 1724 931 1724 991 1725 963 1725 960 1725 992 1726 943 1726 976 1726 991 1727 985 1727 963 1727 992 1728 962 1728 943 1728 993 1729 955 1729 965 1729 990 1730 931 1730 964 1730 993 1731 982 1731 955 1731 994 1732 968 1732 980 1732 995 1733 971 1733 967 1733 994 1734 989 1734 968 1734 996 1735 971 1735 995 1735 996 1736 981 1736 971 1736 997 1737 965 1737 942 1737 998 1738 984 1738 983 1738 997 1739 942 1739 972 1739 998 1740 983 1740 966 1740 998 1741 966 1741 989 1741 999 1742 990 1742 964 1742 999 1743 964 1743 979 1743 1000 1744 991 1744 960 1744 1001 1745 976 1745 978 1745 1000 1746 960 1746 977 1746 1002 1747 979 1747 958 1747 1002 1748 981 1748 996 1748 1001 1749 978 1749 1003 1749 1004 1750 977 1750 952 1750 1004 1751 952 1751 982 1751 1002 1752 958 1752 981 1752 1005 1753 980 1753 962 1753 1005 1754 962 1754 992 1754 1004 1755 982 1755 993 1755 1006 1756 986 1756 987 1756 1007 1757 988 1757 985 1757 1007 1758 985 1758 991 1758 1008 1759 989 1759 994 1759 1009 1760 967 1760 986 1760 1008 1761 998 1761 989 1761 1010 1762 973 1762 1011 1762 1010 1763 972 1763 973 1763 1012 1764 976 1764 1001 1764 1009 1765 986 1765 1006 1765 1009 1766 995 1766 967 1766 1013 1767 974 1767 953 1767 1012 1768 992 1768 976 1768 1013 1769 1014 1769 975 1769 1013 1770 953 1770 990 1770 1013 1771 975 1771 974 1771 1015 1772 996 1772 995 1772 1016 1773 1004 1773 993 1773 1017 1774 994 1774 980 1774 1017 1775 980 1775 1005 1775 1018 1776 1002 1776 996 1776 1019 1777 1020 1777 984 1777 1021 1778 993 1778 965 1778 1019 1779 1022 1779 1020 1779 1019 1780 984 1780 998 1780 1019 1781 998 1781 1008 1781 1021 1782 965 1782 997 1782 1018 1783 996 1783 1015 1783 1023 1784 988 1784 1007 1784 1023 1785 991 1785 1000 1785 1024 1786 1012 1786 1001 1786 1023 1787 1025 1787 988 1787 1026 1788 1014 1788 1013 1788 1026 1789 1013 1789 990 1789 1023 1790 1007 1790 991 1790 1024 1791 1027 1791 1028 1791 1026 1792 990 1792 999 1792 1024 1793 1003 1793 1027 1793 1029 1794 1023 1794 1000 1794 1024 1795 1001 1795 1003 1795 1030 1796 979 1796 1002 1796 1029 1797 1000 1797 977 1797 1030 1798 1026 1798 999 1798 1029 1799 977 1799 1004 1799 1031 1800 1005 1800 992 1800 1030 1801 999 1801 979 1801 1032 1802 1006 1802 987 1802 1031 1803 992 1803 1012 1803 1033 1804 972 1804 1010 1804 1033 1805 997 1805 972 1805 1032 1806 987 1806 1034 1806 1035 1807 1008 1807 994 1807 1035 1808 994 1808 1017 1808 1036 1809 1004 1809 1016 1809 1037 1810 1009 1810 1006 1810 1038 1811 995 1811 1009 1811 1039 1812 1012 1812 1024 1812 1038 1813 1009 1813 1037 1813 1036 1814 1029 1814 1004 1814 1039 1815 1031 1815 1012 1815 1040 1816 1016 1816 993 1816 1038 1817 1015 1817 995 1817 1040 1818 993 1818 1021 1818 1041 1819 1017 1819 1005 1819 1042 1820 1018 1820 1015 1820 1041 1821 1005 1821 1031 1821 1043 1822 1025 1822 1023 1822 1044 1823 1030 1823 1002 1823 1043 1824 1023 1824 1029 1824 1045 1825 1011 1825 581 1825 1044 1826 1002 1826 1018 1826 1045 1827 581 1827 580 1827 1044 1828 1018 1828 1042 1828 1045 1829 1033 1829 1010 1829 1046 1830 1024 1830 1028 1830 1045 1831 1010 1831 1011 1831 1046 1832 1039 1832 1024 1832 1045 1833 580 1833 609 1833 1047 1834 1048 1834 1022 1834 1047 1835 1008 1835 1035 1835 1047 1836 1022 1836 1019 1836 1049 1837 997 1837 1033 1837 1047 1838 1019 1838 1008 1838 1050 1839 1032 1839 1034 1839 1051 1840 1026 1840 1030 1840 1051 1841 1052 1841 1014 1841 1051 1842 1014 1842 1026 1842 1049 1843 1021 1843 997 1843 1053 1844 1031 1844 1039 1844 1053 1845 1041 1845 1031 1845 1054 1846 1006 1846 1032 1846 1055 1847 1025 1847 1043 1847 1054 1848 1037 1848 1006 1848 1055 1849 1029 1849 1036 1849 1055 1850 1043 1850 1029 1850 1055 1851 1056 1851 1025 1851 1057 1852 1017 1852 1041 1852 1058 1853 1036 1853 1016 1853 1057 1854 1035 1854 1017 1854 1059 1855 1039 1855 1046 1855 1060 1856 1038 1856 1037 1856 1058 1857 1016 1857 1040 1857 1061 1858 1049 1858 1033 1858 1062 1859 1038 1859 1060 1859 1061 1860 1033 1860 1045 1860 1059 1861 1053 1861 1039 1861 1061 1862 1045 1862 609 1862 1062 1863 1015 1863 1038 1863 1062 1864 1042 1864 1015 1864 1061 1865 609 1865 619 1865 1063 1866 1041 1866 1053 1866 1063 1867 1057 1867 1041 1867 1064 1868 1051 1868 1030 1868 1065 1869 1021 1869 1049 1869 1066 1870 1046 1870 1028 1870 1064 1871 1030 1871 1044 1871 1064 1872 1052 1872 1051 1872 1065 1873 1040 1873 1021 1873 1066 1874 1028 1874 1067 1874 1068 1875 1044 1875 1042 1875 1069 1876 1036 1876 1058 1876 1069 1877 1055 1877 1036 1877 1068 1878 1064 1878 1044 1878 1069 1879 1056 1879 1055 1879 1070 1880 1047 1880 1035 1880 1070 1881 1035 1881 1057 1881 1071 1882 1034 1882 1072 1882 1073 1883 1049 1883 1061 1883 1070 1884 1048 1884 1047 1884 1073 1885 1061 1885 619 1885 1073 1886 619 1886 629 1886 1071 1887 1050 1887 1034 1887 1074 1888 1053 1888 1059 1888 1075 1889 1054 1889 1032 1889 1076 1890 1058 1890 1040 1890 1075 1891 1032 1891 1050 1891 1077 1892 1057 1892 1063 1892 1076 1893 1040 1893 1065 1893 1077 1894 1070 1894 1057 1894 1078 1895 1037 1895 1054 1895 1079 1896 1065 1896 1049 1896 211 1897 1046 1897 1066 1897 1079 1898 1049 1898 1073 1898 1078 1899 1060 1899 1037 1899 1079 1900 1073 1900 629 1900 1079 1901 629 1901 631 1901 1080 1902 1058 1902 1076 1902 1080 1903 1069 1903 1058 1903 215 1904 1062 1904 1060 1904 211 1905 1059 1905 1046 1905 1080 1906 1056 1906 1069 1906 1080 1907 1081 1907 1056 1907 226 1908 1063 1908 1053 1908 226 1909 1053 1909 1074 1909 1082 1910 1076 1910 1065 1910 1083 1911 1042 1911 1062 1911 1082 1912 1065 1912 1079 1912 1083 1913 1068 1913 1042 1913 1082 1914 1079 1914 631 1914 1083 1915 1062 1915 215 1915 1082 1916 631 1916 642 1916 1084 1917 1066 1917 1067 1917 1085 1918 1076 1918 1082 1918 1085 1919 1082 1919 642 1919 1085 1920 1080 1920 1076 1920 1085 1921 1081 1921 1080 1921 1084 1922 1067 1922 1086 1922 1085 1923 1087 1923 1081 1923 1085 1924 660 1924 1087 1924 238 1925 1071 1925 1072 1925 1088 1926 1089 1926 1048 1926 1085 1927 642 1927 660 1927 1090 1928 223 1928 1052 1928 1090 1929 1052 1929 1064 1929 1088 1930 1070 1930 1077 1930 1090 1931 1064 1931 1068 1931 1088 1932 1048 1932 1070 1932 241 1933 1074 1933 1059 1933 241 1934 1059 1934 211 1934 231 1935 1050 1935 1071 1935 231 1936 1075 1936 1050 1936 1091 1937 1075 1937 231 1937 236 1938 1084 1938 1086 1938 1091 1939 1078 1939 1054 1939 1091 1940 1054 1940 1075 1940 236 1941 1086 1941 219 1941 216 1942 1078 1942 1091 1942 225 1943 1077 1943 1063 1943 216 1944 1060 1944 1078 1944 225 1945 1063 1945 226 1945 216 1946 215 1946 1060 1946 212 1947 1066 1947 1084 1947 212 1948 211 1948 1066 1948 214 1949 1083 1949 215 1949 222 1950 1090 1950 1068 1950 222 1951 1083 1951 214 1951 222 1952 223 1952 1090 1952 228 1953 1074 1953 241 1953 222 1954 1068 1954 1083 1954 228 1955 226 1955 1074 1955 234 1956 231 1956 1071 1956 234 1957 1071 1957 238 1957 233 1958 1084 1958 236 1958 239 1959 238 1959 1072 1959 239 1960 1072 1960 255 1960 233 1961 212 1961 1084 1961 218 1962 236 1962 219 1962 230 1963 1091 1963 231 1963 253 1964 252 1964 1089 1964 253 1965 1088 1965 1077 1965 243 1966 1091 1966 230 1966 253 1967 1089 1967 1088 1967 253 1968 1077 1968 225 1968 243 1969 216 1969 1091 1969 210 1970 241 1970 211 1970 246 1971 239 1971 255 1971 1092 1972 1093 1972 1094 1972 1095 1973 1096 1973 1097 1973 1098 1974 1099 1974 1100 1974 1101 1975 1102 1975 1103 1975 1104 1976 1101 1976 1103 1976 1105 1977 1106 1977 1100 1977 1106 1978 1098 1978 1100 1978 1102 1979 1107 1979 1103 1979 1108 1980 1109 1980 1110 1980 1111 1981 1108 1981 1110 1981 1112 1982 1095 1982 1113 1982 1094 1983 1093 1983 1114 1983 1115 1984 1104 1984 1116 1984 1117 1985 1115 1985 1116 1985 1093 1986 1105 1986 1114 1986 1097 1987 1117 1987 1116 1987 1118 1988 1119 1988 1120 1988 1099 1989 1118 1989 1120 1989 1104 1990 1103 1990 1121 1990 1122 1991 1123 1991 1124 1991 1125 1992 1126 1992 1127 1992 1128 1993 1129 1993 1127 1993 1123 1994 1130 1994 1124 1994 1107 1995 1128 1995 1127 1995 1119 1996 1122 1996 1124 1996 1105 1997 1100 1997 1131 1997 1129 1998 1125 1998 1127 1998 1114 1999 1105 1999 1131 1999 1095 2000 1097 2000 1132 2000 1113 2001 1095 2001 1132 2001 1092 2002 1094 2002 1133 2002 1109 2003 1092 2003 1133 2003 1097 2004 1116 2004 1134 2004 1110 2005 1109 2005 1133 2005 1135 2006 1112 2006 1136 2006 1112 2007 1113 2007 1136 2007 1094 2008 1114 2008 1137 2008 1100 2009 1099 2009 1138 2009 1099 2010 1120 2010 1138 2010 1103 2011 1107 2011 1139 2011 1107 2012 1127 2012 1139 2012 1111 2013 1110 2013 1140 2013 1113 2014 1132 2014 1141 2014 1116 2015 1104 2015 1142 2015 1120 2016 1119 2016 1143 2016 1119 2017 1124 2017 1143 2017 1104 2018 1121 2018 1142 2018 1124 2019 1130 2019 1143 2019 1134 2020 1116 2020 1142 2020 1121 2021 1103 2021 1144 2021 1110 2022 1133 2022 1145 2022 1103 2023 1139 2023 1144 2023 1114 2024 1131 2024 1146 2024 1135 2025 1136 2025 1147 2025 1137 2026 1114 2026 1146 2026 1111 2027 1140 2027 1148 2027 1149 2028 1111 2028 1148 2028 1132 2029 1097 2029 1150 2029 1097 2030 1134 2030 1150 2030 1141 2031 1132 2031 1150 2031 1100 2032 1138 2032 1151 2032 1150 2033 1134 2033 1152 2033 1131 2034 1100 2034 1151 2034 1146 2035 1131 2035 1151 2035 1134 2036 1142 2036 1152 2036 1133 2037 1094 2037 1153 2037 1094 2038 1137 2038 1153 2038 1126 2039 1154 2039 1155 2039 1127 2040 1126 2040 1155 2040 1139 2041 1127 2041 1155 2041 1147 2042 1136 2042 1156 2042 1120 2043 1143 2043 1157 2043 1138 2044 1120 2044 1157 2044 1143 2045 1130 2045 1157 2045 1136 2046 1113 2046 1156 2046 1130 2047 1158 2047 1157 2047 1113 2048 1141 2048 1156 2048 1137 2049 1146 2049 1159 2049 1160 2050 1135 2050 1161 2050 1135 2051 1147 2051 1161 2051 1140 2052 1110 2052 1162 2052 1148 2053 1140 2053 1162 2053 1141 2054 1150 2054 1163 2054 1110 2055 1145 2055 1162 2055 1154 2056 1164 2056 1165 2056 1139 2057 1155 2057 1165 2057 1133 2058 1153 2058 1166 2058 1155 2059 1154 2059 1165 2059 1145 2060 1133 2060 1166 2060 1144 2061 1139 2061 1165 2061 1152 2062 1142 2062 1167 2062 1159 2063 1146 2063 1168 2063 1142 2064 1121 2064 1167 2064 1146 2065 1151 2065 1168 2065 1121 2066 1144 2066 1167 2066 1161 2067 1147 2067 1169 2067 1147 2068 1156 2068 1169 2068 1151 2069 1138 2069 1170 2069 1138 2070 1157 2070 1170 2070 1168 2071 1151 2071 1170 2071 1157 2072 1158 2072 1170 2072 1149 2073 1148 2073 1171 2073 1163 2074 1150 2074 1172 2074 1150 2075 1152 2075 1172 2075 1152 2076 1167 2076 1173 2076 1148 2077 1162 2077 1174 2077 1171 2078 1148 2078 1174 2078 1156 2079 1141 2079 1175 2079 1153 2080 1137 2080 1176 2080 1169 2081 1156 2081 1175 2081 1137 2082 1159 2082 1176 2082 1166 2083 1153 2083 1176 2083 1141 2084 1163 2084 1175 2084 1160 2085 1161 2085 1177 2085 1159 2086 1168 2086 1178 2086 1165 2087 1164 2087 1179 2087 1144 2088 1165 2088 1179 2088 1162 2089 1145 2089 1180 2089 1167 2090 1144 2090 1179 2090 1173 2091 1167 2091 1179 2091 1145 2092 1166 2092 1180 2092 1177 2093 1161 2093 1181 2093 1178 2094 1168 2094 1182 2094 1158 2095 1183 2095 1182 2095 1170 2096 1158 2096 1182 2096 1161 2097 1169 2097 1181 2097 1168 2098 1170 2098 1182 2098 1166 2099 1176 2099 1184 2099 1163 2100 1172 2100 1185 2100 1186 2101 1160 2101 1187 2101 1160 2102 1177 2102 1187 2102 1171 2103 1174 2103 1188 2103 1162 2104 1180 2104 1189 2104 1169 2105 1175 2105 1190 2105 1174 2106 1162 2106 1189 2106 1181 2107 1169 2107 1190 2107 1188 2108 1174 2108 1189 2108 1172 2109 1152 2109 1191 2109 1176 2110 1159 2110 1192 2110 1152 2111 1173 2111 1191 2111 1159 2112 1178 2112 1192 2112 1185 2113 1172 2113 1191 2113 1164 2114 1193 2114 1194 2114 1173 2115 1179 2115 1194 2115 1179 2116 1164 2116 1194 2116 1178 2117 1182 2117 1195 2117 1182 2118 1183 2118 1195 2118 1175 2119 1163 2119 1196 2119 1163 2120 1185 2120 1196 2120 1197 2121 1149 2121 1198 2121 1190 2122 1175 2122 1196 2122 1199 2123 1197 2123 1198 2123 1177 2124 1181 2124 1200 2124 1149 2125 1171 2125 1198 2125 1187 2126 1177 2126 1200 2126 1189 2127 1180 2127 1201 2127 1180 2128 1166 2128 1201 2128 1166 2129 1184 2129 1201 2129 1181 2130 1190 2130 1202 2130 1176 2131 1192 2131 1203 2131 1184 2132 1176 2132 1203 2132 1185 2133 1191 2133 1204 2133 1188 2134 1189 2134 1205 2134 1186 2135 1187 2135 1206 2135 1189 2136 1201 2136 1207 2136 1191 2137 1173 2137 1208 2137 1205 2138 1189 2138 1207 2138 1173 2139 1194 2139 1208 2139 1192 2140 1178 2140 1209 2140 1204 2141 1191 2141 1208 2141 1194 2142 1193 2142 1208 2142 1195 2143 1183 2143 1209 2143 1183 2144 1210 2144 1209 2144 1187 2145 1200 2145 1211 2145 1178 2146 1195 2146 1209 2146 1206 2147 1187 2147 1211 2147 1171 2148 1188 2148 1212 2148 1198 2149 1171 2149 1212 2149 1190 2150 1196 2150 1213 2150 1202 2151 1190 2151 1213 2151 1214 2152 1186 2152 1215 2152 1203 2153 1192 2153 1216 2153 1192 2154 1209 2154 1216 2154 1186 2155 1206 2155 1215 2155 1209 2156 1210 2156 1216 2156 1196 2157 1185 2157 1217 2157 1184 2158 1203 2158 1218 2158 1201 2159 1184 2159 1218 2159 1185 2160 1204 2160 1217 2160 1213 2161 1196 2161 1217 2161 1199 2162 1198 2162 1219 2162 1198 2163 1212 2163 1219 2163 1200 2164 1181 2164 1220 2164 1181 2165 1202 2165 1220 2165 1193 2166 1221 2166 1222 2166 1208 2167 1193 2167 1222 2167 1204 2168 1208 2168 1222 2168 1205 2169 1207 2169 1223 2169 1202 2170 1213 2170 1224 2170 1207 2171 1201 2171 1225 2171 1201 2172 1218 2172 1225 2172 1220 2173 1202 2173 1224 2173 1223 2174 1207 2174 1225 2174 1188 2175 1205 2175 1226 2175 1206 2176 1211 2176 1227 2176 1212 2177 1188 2177 1226 2177 1215 2178 1206 2178 1227 2178 1203 2179 1216 2179 1228 2179 1218 2180 1203 2180 1228 2180 1211 2181 1200 2181 1229 2181 1216 2182 1210 2182 1228 2182 1200 2183 1220 2183 1229 2183 1210 2184 1230 2184 1228 2184 1212 2185 1226 2185 1231 2185 1213 2186 1217 2186 1232 2186 1224 2187 1213 2187 1232 2187 1219 2188 1212 2188 1231 2188 1232 2189 1217 2189 1233 2189 1225 2190 1218 2190 1234 2190 1218 2191 1228 2191 1234 2191 1222 2192 1221 2192 1233 2192 1217 2193 1204 2193 1233 2193 1228 2194 1230 2194 1234 2194 1204 2195 1222 2195 1233 2195 1225 2196 1234 2196 1235 2196 1223 2197 1225 2197 1235 2197 1236 2198 1214 2198 1237 2198 1214 2199 1215 2199 1237 2199 1199 2200 1219 2200 1238 2200 1239 2201 1199 2201 1238 2201 1240 2202 1239 2202 1238 2202 1215 2203 1227 2203 1241 2203 1242 2204 1240 2204 1238 2204 1243 2205 1242 2205 1238 2205 1237 2206 1215 2206 1241 2206 1219 2207 1231 2207 1238 2207 1226 2208 1205 2208 1244 2208 1205 2209 1223 2209 1244 2209 1220 2210 1224 2210 1245 2210 1229 2211 1220 2211 1245 2211 1224 2212 1232 2212 1246 2212 1226 2213 1244 2213 1247 2213 1211 2214 1229 2214 1248 2214 1231 2215 1226 2215 1247 2215 1235 2216 1234 2216 1249 2216 1227 2217 1211 2217 1248 2217 1241 2218 1227 2218 1248 2218 1230 2219 1250 2219 1249 2219 1234 2220 1230 2220 1249 2220 1221 2221 1251 2221 1252 2221 1253 2222 1243 2222 1254 2222 1232 2223 1233 2223 1252 2223 1243 2224 1238 2224 1254 2224 1246 2225 1232 2225 1252 2225 1238 2226 1231 2226 1254 2226 1233 2227 1221 2227 1252 2227 1231 2228 1247 2228 1254 2228 1229 2229 1245 2229 1255 2229 1244 2230 1223 2230 1256 2230 1223 2231 1235 2231 1256 2231 1248 2232 1229 2232 1255 2232 1237 2233 1241 2233 1257 2233 1247 2234 1244 2234 1258 2234 1244 2235 1256 2235 1258 2235 1247 2236 1258 2236 1259 2236 1260 2237 1253 2237 1259 2237 1241 2238 1248 2238 1261 2238 1253 2239 1254 2239 1259 2239 1254 2240 1247 2240 1259 2240 1250 2241 1262 2241 1263 2241 1235 2242 1249 2242 1263 2242 1245 2243 1224 2243 1264 2243 1256 2244 1235 2244 1263 2244 1224 2245 1246 2245 1264 2245 1249 2246 1250 2246 1263 2246 1256 2247 1263 2247 1265 2247 1246 2248 1252 2248 1266 2248 1252 2249 1251 2249 1266 2249 1258 2250 1256 2250 1265 2250 1260 2251 1259 2251 1267 2251 1237 2252 1257 2252 1268 2252 1236 2253 1237 2253 1268 2253 1269 2254 1260 2254 1267 2254 1259 2255 1258 2255 1267 2255 1262 2256 1270 2256 1271 2256 1261 2257 1248 2257 1272 2257 1265 2258 1263 2258 1271 2258 1263 2259 1262 2259 1271 2259 1248 2260 1255 2260 1272 2260 1265 2261 1271 2261 1273 2261 1258 2262 1265 2262 1273 2262 1255 2263 1245 2263 1274 2263 1269 2264 1267 2264 1273 2264 1267 2265 1258 2265 1273 2265 1245 2266 1264 2266 1274 2266 1275 2267 1269 2267 1273 2267 1273 2268 1271 2268 1276 2268 1275 2269 1273 2269 1276 2269 1277 2270 1275 2270 1276 2270 1271 2271 1270 2271 1276 2271 1270 2272 1277 2272 1276 2272 1257 2273 1241 2273 1278 2273 1241 2274 1261 2274 1278 2274 1261 2275 1272 2275 1279 2275 1278 2276 1261 2276 1279 2276 1266 2277 1251 2277 1280 2277 1251 2278 1281 2278 1280 2278 1246 2279 1266 2279 1280 2279 1274 2280 1264 2280 1280 2280 1264 2281 1246 2281 1280 2281 1257 2282 1278 2282 1282 2282 1268 2283 1257 2283 1282 2283 1280 2284 1281 2284 1283 2284 1274 2285 1280 2285 1283 2285 1272 2286 1255 2286 1284 2286 1255 2287 1274 2287 1284 2287 1285 2288 1236 2288 1286 2288 1287 2289 1285 2289 1286 2289 1236 2290 1268 2290 1286 2290 1278 2291 1279 2291 1288 2291 1272 2292 1284 2292 1289 2292 1279 2293 1272 2293 1289 2293 1282 2294 1278 2294 1290 2294 1278 2295 1288 2295 1290 2295 1281 2296 1291 2296 1292 2296 1283 2297 1281 2297 1292 2297 1274 2298 1283 2298 1292 2298 1284 2299 1274 2299 1292 2299 1268 2300 1282 2300 1293 2300 1286 2301 1268 2301 1293 2301 1292 2302 1291 2302 1294 2302 1289 2303 1284 2303 1294 2303 1284 2304 1292 2304 1294 2304 1288 2305 1279 2305 1295 2305 1279 2306 1289 2306 1295 2306 1287 2307 1286 2307 1296 2307 1286 2308 1293 2308 1296 2308 1290 2309 1288 2309 1297 2309 1288 2310 1295 2310 1297 2310 1282 2311 1290 2311 1298 2311 1293 2312 1282 2312 1298 2312 1291 2313 1299 2313 1300 2313 1294 2314 1291 2314 1300 2314 1289 2315 1294 2315 1300 2315 1295 2316 1289 2316 1300 2316 1293 2317 1298 2317 1301 2317 1296 2318 1293 2318 1301 2318 1297 2319 1295 2319 1302 2319 1295 2320 1300 2320 1302 2320 1303 2321 1287 2321 1304 2321 1287 2322 1296 2322 1304 2322 1290 2323 1297 2323 1305 2323 1298 2324 1290 2324 1305 2324 1301 2325 1298 2325 1306 2325 1298 2326 1305 2326 1306 2326 1299 2327 1307 2327 1308 2327 1302 2328 1300 2328 1308 2328 1300 2329 1299 2329 1308 2329 1304 2330 1296 2330 1309 2330 1296 2331 1301 2331 1309 2331 1305 2332 1297 2332 1310 2332 1297 2333 1302 2333 1310 2333 1311 2334 1303 2334 1312 2334 1303 2335 1304 2335 1312 2335 1306 2336 1305 2336 1313 2336 1305 2337 1310 2337 1313 2337 1309 2338 1301 2338 1314 2338 1301 2339 1306 2339 1314 2339 1307 2340 1315 2340 1316 2340 1308 2341 1307 2341 1316 2341 1302 2342 1308 2342 1316 2342 1310 2343 1302 2343 1316 2343 1312 2344 1304 2344 1317 2344 1304 2345 1309 2345 1317 2345 1318 2346 1311 2346 1319 2346 1312 2347 1317 2347 1319 2347 1311 2348 1312 2348 1319 2348 1313 2349 1310 2349 1320 2349 1306 2350 1313 2350 1321 2350 1314 2351 1306 2351 1321 2351 1309 2352 1314 2352 1322 2352 1317 2353 1309 2353 1322 2353 1315 2354 1323 2354 1324 2354 1316 2355 1315 2355 1324 2355 1310 2356 1316 2356 1324 2356 1320 2357 1310 2357 1324 2357 1317 2358 1322 2358 1325 2358 1319 2359 1317 2359 1325 2359 1326 2360 1318 2360 1327 2360 1319 2361 1325 2361 1327 2361 1318 2362 1319 2362 1327 2362 1313 2363 1320 2363 1328 2363 1321 2364 1313 2364 1328 2364 1314 2365 1321 2365 1329 2365 1322 2366 1314 2366 1329 2366 1325 2367 1322 2367 1330 2367 1322 2368 1329 2368 1330 2368 1328 2369 1320 2369 1331 2369 1324 2370 1323 2370 1331 2370 1320 2371 1324 2371 1331 2371 1323 2372 1332 2372 1331 2372 1325 2373 1330 2373 1333 2373 1327 2374 1325 2374 1333 2374 1326 2375 1327 2375 1334 2375 1327 2376 1333 2376 1334 2376 1335 2377 1326 2377 1334 2377 1321 2378 1328 2378 1336 2378 1329 2379 1321 2379 1336 2379 1330 2380 1329 2380 1337 2380 1329 2381 1336 2381 1337 2381 1330 2382 1337 2382 1338 2382 1333 2383 1330 2383 1338 2383 1328 2384 1331 2384 1339 2384 1336 2385 1328 2385 1339 2385 1331 2386 1332 2386 1339 2386 1332 2387 1340 2387 1339 2387 1334 2388 1333 2388 1341 2388 1333 2389 1338 2389 1341 2389 1342 2390 1335 2390 1343 2390 1335 2391 1334 2391 1343 2391 1334 2392 1341 2392 1343 2392 1337 2393 1336 2393 1344 2393 1338 2394 1337 2394 1345 2394 1337 2395 1344 2395 1345 2395 1342 2396 1343 2396 1346 2396 1338 2397 1345 2397 1347 2397 1341 2398 1338 2398 1347 2398 1336 2399 1339 2399 1348 2399 1344 2400 1336 2400 1348 2400 1339 2401 1340 2401 1348 2401 1340 2402 1349 2402 1348 2402 1343 2403 1341 2403 1350 2403 1346 2404 1343 2404 1350 2404 1341 2405 1347 2405 1350 2405 1275 2406 1277 2406 1351 2406 1352 2407 1240 2407 1353 2407 1354 2408 1342 2408 1355 2408 1240 2409 1242 2409 1353 2409 1342 2410 1346 2410 1355 2410 1345 2411 1344 2411 1356 2411 1242 2412 1243 2412 1357 2412 1355 2413 1346 2413 1358 2413 1346 2414 1350 2414 1358 2414 1353 2415 1242 2415 1357 2415 1359 2416 1352 2416 1360 2416 1345 2417 1356 2417 1361 2417 1352 2418 1353 2418 1360 2418 1347 2419 1345 2419 1361 2419 1243 2420 1253 2420 1362 2420 1354 2421 1355 2421 1363 2421 1357 2422 1243 2422 1362 2422 1347 2423 1361 2423 1364 2423 1350 2424 1347 2424 1364 2424 1353 2425 1357 2425 1365 2425 1360 2426 1353 2426 1365 2426 1356 2427 1344 2427 1366 2427 1344 2428 1348 2428 1366 2428 1367 2429 1359 2429 1368 2429 1348 2430 1349 2430 1366 2430 1349 2431 1369 2431 1366 2431 1359 2432 1360 2432 1368 2432 1363 2433 1355 2433 1370 2433 1355 2434 1358 2434 1370 2434 1253 2435 1260 2435 1371 2435 1358 2436 1350 2436 1372 2436 1350 2437 1364 2437 1372 2437 1362 2438 1253 2438 1371 2438 1365 2439 1357 2439 1373 2439 1354 2440 1363 2440 1374 2440 1357 2441 1362 2441 1373 2441 1375 2442 1354 2442 1374 2442 1360 2443 1365 2443 1376 2443 1361 2444 1356 2444 1377 2444 1368 2445 1360 2445 1376 2445 1378 2446 1367 2446 1379 2446 1363 2447 1370 2447 1380 2447 1367 2448 1368 2448 1379 2448 1374 2449 1363 2449 1380 2449 1364 2450 1361 2450 1381 2450 1361 2451 1377 2451 1381 2451 1372 2452 1364 2452 1381 2452 1260 2453 1269 2453 1382 2453 1371 2454 1260 2454 1382 2454 1375 2455 1374 2455 1383 2455 1362 2456 1371 2456 1384 2456 1373 2457 1362 2457 1384 2457 1380 2458 1370 2458 1385 2458 1365 2459 1373 2459 1386 2459 1358 2460 1372 2460 1385 2460 1370 2461 1358 2461 1385 2461 1376 2462 1365 2462 1386 2462 1372 2463 1381 2463 1387 2463 1382 2464 1269 2464 1388 2464 1385 2465 1372 2465 1387 2465 1351 2466 1389 2466 1388 2466 1269 2467 1275 2467 1388 2467 1275 2468 1351 2468 1388 2468 1356 2469 1366 2469 1390 2469 1366 2470 1369 2470 1390 2470 1379 2471 1368 2471 1391 2471 1377 2472 1356 2472 1390 2472 1369 2473 1392 2473 1390 2473 1368 2474 1376 2474 1391 2474 1374 2475 1380 2475 1393 2475 1394 2476 1378 2476 1395 2476 1380 2477 1385 2477 1396 2477 1378 2478 1379 2478 1395 2478 1371 2479 1382 2479 1397 2479 1393 2480 1380 2480 1396 2480 1398 2481 1375 2481 1399 2481 1384 2482 1371 2482 1397 2482 1375 2483 1383 2483 1399 2483 1381 2484 1377 2484 1400 2484 1386 2485 1373 2485 1401 2485 1377 2486 1390 2486 1400 2486 1373 2487 1384 2487 1401 2487 1383 2488 1374 2488 1402 2488 1374 2489 1393 2489 1402 2489 1394 2490 1395 2490 1403 2490 1385 2491 1387 2491 1404 2491 1396 2492 1385 2492 1404 2492 1376 2493 1386 2493 1405 2493 1391 2494 1376 2494 1405 2494 1381 2495 1400 2495 1406 2495 1389 2496 1407 2496 1408 2496 1387 2497 1381 2497 1406 2497 1388 2498 1389 2498 1408 2498 1397 2499 1382 2499 1408 2499 1382 2500 1388 2500 1408 2500 1379 2501 1391 2501 1409 2501 1403 2502 1395 2502 1409 2502 1395 2503 1379 2503 1409 2503 1398 2504 1399 2504 1410 2504 1411 2505 1394 2505 1412 2505 1393 2506 1396 2506 1413 2506 1394 2507 1403 2507 1412 2507 1396 2508 1404 2508 1414 2508 1413 2509 1396 2509 1414 2509 1401 2510 1384 2510 1415 2510 1384 2511 1397 2511 1415 2511 1390 2512 1392 2512 1416 2512 1400 2513 1390 2513 1416 2513 1403 2514 1409 2514 1417 2514 1392 2515 1418 2515 1416 2515 1383 2516 1402 2516 1419 2516 1412 2517 1403 2517 1417 2517 1410 2518 1399 2518 1419 2518 1399 2519 1383 2519 1419 2519 1386 2520 1401 2520 1420 2520 1401 2521 1415 2521 1420 2521 1405 2522 1386 2522 1420 2522 1421 2523 1398 2523 1422 2523 1398 2524 1410 2524 1422 2524 1402 2525 1393 2525 1423 2525 1393 2526 1413 2526 1423 2526 1411 2527 1412 2527 1424 2527 1416 2528 1418 2528 1425 2528 1400 2529 1416 2529 1425 2529 1391 2530 1405 2530 1426 2530 1406 2531 1400 2531 1425 2531 1409 2532 1391 2532 1426 2532 1418 2533 1427 2533 1425 2533 1397 2534 1408 2534 1428 2534 1407 2535 1429 2535 1428 2535 1387 2536 1406 2536 1430 2536 1404 2537 1387 2537 1430 2537 1408 2538 1407 2538 1428 2538 1415 2539 1397 2539 1428 2539 1414 2540 1404 2540 1430 2540 1410 2541 1419 2541 1431 2541 1424 2542 1412 2542 1432 2542 1412 2543 1417 2543 1432 2543 1422 2544 1410 2544 1431 2544 1413 2545 1414 2545 1433 2545 1417 2546 1409 2546 1434 2546 1432 2547 1417 2547 1434 2547 1409 2548 1426 2548 1434 2548 1411 2549 1424 2549 1435 2549 1436 2550 1411 2550 1435 2550 1414 2551 1430 2551 1437 2551 1433 2552 1414 2552 1437 2552 1431 2553 1419 2553 1438 2553 1419 2554 1402 2554 1438 2554 1420 2555 1415 2555 1439 2555 1402 2556 1423 2556 1438 2556 1421 2557 1422 2557 1440 2557 1424 2558 1432 2558 1441 2558 1406 2559 1425 2559 1442 2559 1425 2560 1427 2560 1442 2560 1426 2561 1405 2561 1443 2561 1437 2562 1430 2562 1442 2562 1405 2563 1420 2563 1443 2563 1430 2564 1406 2564 1442 2564 1420 2565 1439 2565 1443 2565 1434 2566 1426 2566 1443 2566 1422 2567 1431 2567 1444 2567 1440 2568 1422 2568 1444 2568 1436 2569 1435 2569 1445 2569 1423 2570 1413 2570 1446 2570 1413 2571 1433 2571 1446 2571 1432 2572 1434 2572 1447 2572 1421 2573 1440 2573 1448 2573 1447 2574 1434 2574 1449 2574 1450 2575 1421 2575 1448 2575 1434 2576 1443 2576 1449 2576 1431 2577 1438 2577 1451 2577 1429 2578 1452 2578 1453 2578 1428 2579 1429 2579 1453 2579 1439 2580 1415 2580 1453 2580 1415 2581 1428 2581 1453 2581 1435 2582 1424 2582 1454 2582 1424 2583 1441 2583 1454 2583 1433 2584 1437 2584 1455 2584 1445 2585 1435 2585 1454 2585 1437 2586 1442 2586 1456 2586 1455 2587 1437 2587 1456 2587 1432 2588 1447 2588 1457 2588 1442 2589 1427 2589 1456 2589 1441 2590 1432 2590 1457 2590 1427 2591 1458 2591 1456 2591 1438 2592 1423 2592 1459 2592 1451 2593 1438 2593 1459 2593 1423 2594 1446 2594 1459 2594 1460 2595 1436 2595 1461 2595 1436 2596 1445 2596 1461 2596 1448 2597 1440 2597 1462 2597 1440 2598 1444 2598 1462 2598 1443 2599 1439 2599 1463 2599 1444 2600 1431 2600 1464 2600 1431 2601 1451 2601 1464 2601 1462 2602 1444 2602 1464 2602 1461 2603 1445 2603 1465 2603 1445 2604 1454 2604 1465 2604 1446 2605 1433 2605 1466 2605 1447 2606 1449 2606 1467 2606 1433 2607 1455 2607 1466 2607 1457 2608 1447 2608 1467 2608 1443 2609 1463 2609 1468 2609 1449 2610 1443 2610 1468 2610 1450 2611 1448 2611 1469 2611 1467 2612 1449 2612 1468 2612 1455 2613 1456 2613 1470 2613 1456 2614 1458 2614 1470 2614 1460 2615 1461 2615 1471 2615 1469 2616 1448 2616 1472 2616 1448 2617 1462 2617 1472 2617 1441 2618 1457 2618 1473 2618 1454 2619 1441 2619 1473 2619 1451 2620 1459 2620 1474 2620 1465 2621 1454 2621 1473 2621 1464 2622 1451 2622 1474 2622 1457 2623 1467 2623 1475 2623 1450 2624 1469 2624 1476 2624 1477 2625 1450 2625 1476 2625 1453 2626 1452 2626 1478 2626 1439 2627 1453 2627 1478 2627 1452 2628 1479 2628 1478 2628 1468 2629 1463 2629 1478 2629 1459 2630 1446 2630 1480 2630 1446 2631 1466 2631 1480 2631 1463 2632 1439 2632 1478 2632 1474 2633 1459 2633 1480 2633 1461 2634 1465 2634 1481 2634 1471 2635 1461 2635 1481 2635 1462 2636 1464 2636 1482 2636 1483 2637 1460 2637 1484 2637 1466 2638 1455 2638 1485 2638 1460 2639 1471 2639 1484 2639 1455 2640 1470 2640 1485 2640 1470 2641 1458 2641 1485 2641 1458 2642 1486 2642 1485 2642 1464 2643 1474 2643 1487 2643 1482 2644 1464 2644 1487 2644 1465 2645 1473 2645 1488 2645 1478 2646 1479 2646 1489 2646 1468 2647 1478 2647 1489 2647 1479 2648 1490 2648 1489 2648 1476 2649 1469 2649 1491 2649 1468 2650 1489 2650 1492 2650 1469 2651 1472 2651 1491 2651 1467 2652 1468 2652 1492 2652 1472 2653 1462 2653 1493 2653 1462 2654 1482 2654 1493 2654 1471 2655 1481 2655 1494 2655 1484 2656 1471 2656 1494 2656 1491 2657 1472 2657 1493 2657 1457 2658 1475 2658 1495 2658 1474 2659 1480 2659 1496 2659 1473 2660 1457 2660 1495 2660 1488 2661 1473 2661 1495 2661 1480 2662 1466 2662 1497 2662 1466 2663 1485 2663 1497 2663 1496 2664 1480 2664 1497 2664 1485 2665 1486 2665 1497 2665 1467 2666 1492 2666 1498 2666 1475 2667 1467 2667 1498 2667 1477 2668 1476 2668 1499 2668 1465 2669 1488 2669 1500 2669 1494 2670 1481 2670 1500 2670 1481 2671 1465 2671 1500 2671 1476 2672 1491 2672 1501 2672 1483 2673 1484 2673 1502 2673 1482 2674 1487 2674 1503 2674 1493 2675 1482 2675 1503 2675 1492 2676 1489 2676 1504 2676 1489 2677 1490 2677 1504 2677 1487 2678 1474 2678 1505 2678 1503 2679 1487 2679 1505 2679 1484 2680 1494 2680 1506 2680 1474 2681 1496 2681 1505 2681 1501 2682 1491 2682 1507 2682 1500 2683 1488 2683 1508 2683 1491 2684 1493 2684 1507 2684 1488 2685 1495 2685 1508 2685 1505 2686 1496 2686 1509 2686 1497 2687 1486 2687 1509 2687 1486 2688 1510 2688 1509 2688 1511 2689 1483 2689 1512 2689 1496 2690 1497 2690 1509 2690 1493 2691 1503 2691 1513 2691 1483 2692 1502 2692 1512 2692 1507 2693 1493 2693 1513 2693 1494 2694 1500 2694 1514 2694 1506 2695 1494 2695 1514 2695 1499 2696 1476 2696 1515 2696 1475 2697 1498 2697 1516 2697 1476 2698 1501 2698 1515 2698 1508 2699 1495 2699 1516 2699 1501 2700 1507 2700 1517 2700 1495 2701 1475 2701 1516 2701 1492 2702 1504 2702 1518 2702 1498 2703 1492 2703 1518 2703 1490 2704 1519 2704 1518 2704 1503 2705 1505 2705 1520 2705 1504 2706 1490 2706 1518 2706 1514 2707 1500 2707 1521 2707 1509 2708 1510 2708 1522 2708 1500 2709 1508 2709 1521 2709 1520 2710 1505 2710 1522 2710 1505 2711 1509 2711 1522 2711 1502 2712 1484 2712 1523 2712 1524 2713 1477 2713 1525 2713 1484 2714 1506 2714 1523 2714 1526 2715 1524 2715 1525 2715 1512 2716 1502 2716 1523 2716 1477 2717 1499 2717 1525 2717 1517 2718 1507 2718 1527 2718 1506 2719 1514 2719 1528 2719 1507 2720 1513 2720 1527 2720 1527 2721 1513 2721 1529 2721 1508 2722 1516 2722 1530 2722 1503 2723 1520 2723 1529 2723 1513 2724 1503 2724 1529 2724 1501 2725 1517 2725 1531 2725 1515 2726 1501 2726 1531 2726 1511 2727 1512 2727 1532 2727 1516 2728 1498 2728 1533 2728 1498 2729 1518 2729 1533 2729 1517 2730 1527 2730 1534 2730 1518 2731 1519 2731 1533 2731 1530 2732 1516 2732 1533 2732 1522 2733 1510 2733 1535 2733 1512 2734 1523 2734 1536 2734 1520 2735 1522 2735 1535 2735 1529 2736 1520 2736 1535 2736 1510 2737 1537 2737 1535 2737 1525 2738 1499 2738 1538 2738 1514 2739 1521 2739 1539 2739 1528 2740 1514 2740 1539 2740 1511 2741 1532 2741 1540 2741 1499 2742 1515 2742 1538 2742 1541 2743 1511 2743 1540 2743 1529 2744 1535 2744 1542 2744 1535 2745 1537 2745 1542 2745 1527 2746 1529 2746 1543 2746 1521 2747 1508 2747 1544 2747 1529 2748 1542 2748 1543 2748 1508 2749 1530 2749 1544 2749 1539 2750 1521 2750 1544 2750 1526 2751 1525 2751 1545 2751 1546 2752 1526 2752 1545 2752 1523 2753 1506 2753 1547 2753 1506 2754 1528 2754 1547 2754 1525 2755 1538 2755 1545 2755 1531 2756 1517 2756 1548 2756 1533 2757 1519 2757 1549 2757 1517 2758 1534 2758 1548 2758 1519 2759 1550 2759 1549 2759 1530 2760 1533 2760 1549 2760 1534 2761 1527 2761 1551 2761 1527 2762 1543 2762 1551 2762 1528 2763 1539 2763 1552 2763 1515 2764 1531 2764 1553 2764 1538 2765 1515 2765 1553 2765 1540 2766 1532 2766 1554 2766 1532 2767 1512 2767 1554 2767 1512 2768 1536 2768 1554 2768 1523 2769 1547 2769 1555 2769 1542 2770 1537 2770 1556 2770 1543 2771 1542 2771 1556 2771 1537 2772 1557 2772 1556 2772 1536 2773 1523 2773 1555 2773 1552 2774 1539 2774 1558 2774 1538 2775 1553 2775 1559 2775 1545 2776 1538 2776 1559 2776 1539 2777 1544 2777 1558 2777 1551 2778 1543 2778 1560 2778 1549 2779 1550 2779 1561 2779 1530 2780 1549 2780 1561 2780 1543 2781 1556 2781 1560 2781 1556 2782 1557 2782 1560 2782 1558 2783 1544 2783 1561 2783 1548 2784 1534 2784 1562 2784 1544 2785 1530 2785 1561 2785 1534 2786 1551 2786 1562 2786 1541 2787 1540 2787 1563 2787 1546 2788 1545 2788 1564 2788 1545 2789 1559 2789 1564 2789 1563 2790 1540 2790 1565 2790 1540 2791 1554 2791 1565 2791 1547 2792 1528 2792 1566 2792 1531 2793 1548 2793 1567 2793 1553 2794 1531 2794 1567 2794 1555 2795 1547 2795 1566 2795 1528 2796 1552 2796 1566 2796 1559 2797 1553 2797 1568 2797 1552 2798 1558 2798 1569 2798 1553 2799 1567 2799 1568 2799 1536 2800 1555 2800 1570 2800 1562 2801 1551 2801 1571 2801 1551 2802 1560 2802 1571 2802 1560 2803 1557 2803 1571 2803 1565 2804 1554 2804 1570 2804 1557 2805 1572 2805 1571 2805 1554 2806 1536 2806 1570 2806 1561 2807 1550 2807 1573 2807 1558 2808 1561 2808 1573 2808 1550 2809 1574 2809 1573 2809 1559 2810 1568 2810 1575 2810 1569 2811 1558 2811 1573 2811 1564 2812 1559 2812 1575 2812 1555 2813 1566 2813 1576 2813 1548 2814 1562 2814 1577 2814 1567 2815 1548 2815 1577 2815 1546 2816 1564 2816 1578 2816 1579 2817 1546 2817 1578 2817 1563 2818 1565 2818 1580 2818 1565 2819 1570 2819 1581 2819 1564 2820 1575 2820 1578 2820 1580 2821 1565 2821 1581 2821 1568 2822 1567 2822 1582 2822 1567 2823 1577 2823 1582 2823 1566 2824 1552 2824 1583 2824 1552 2825 1569 2825 1583 2825 1575 2826 1568 2826 1584 2826 1573 2827 1574 2827 1585 2827 1568 2828 1582 2828 1584 2828 1569 2829 1573 2829 1585 2829 1541 2830 1563 2830 1586 2830 1587 2831 1541 2831 1586 2831 1562 2832 1571 2832 1588 2832 1577 2833 1562 2833 1588 2833 1572 2834 1589 2834 1588 2834 1571 2835 1572 2835 1588 2835 1575 2836 1584 2836 1590 2836 1578 2837 1575 2837 1590 2837 1570 2838 1555 2838 1591 2838 1555 2839 1576 2839 1591 2839 1581 2840 1570 2840 1591 2840 1582 2841 1577 2841 1592 2841 1576 2842 1566 2842 1593 2842 1566 2843 1583 2843 1593 2843 1578 2844 1590 2844 1594 2844 1595 2845 1579 2845 1594 2845 1579 2846 1578 2846 1594 2846 1580 2847 1581 2847 1596 2847 1584 2848 1582 2848 1597 2848 1582 2849 1592 2849 1597 2849 1581 2850 1591 2850 1598 2850 1596 2851 1581 2851 1598 2851 1574 2852 1599 2852 1600 2852 1585 2853 1574 2853 1600 2853 1583 2854 1569 2854 1600 2854 1569 2855 1585 2855 1600 2855 1584 2856 1597 2856 1601 2856 1590 2857 1584 2857 1601 2857 1588 2858 1589 2858 1602 2858 1577 2859 1588 2859 1602 2859 1592 2860 1577 2860 1602 2860 1586 2861 1563 2861 1603 2861 1589 2862 1604 2862 1602 2862 1590 2863 1601 2863 1605 2863 1563 2864 1580 2864 1603 2864 1594 2865 1590 2865 1605 2865 1600 2866 1599 2866 1606 2866 1593 2867 1583 2867 1606 2867 1583 2868 1600 2868 1606 2868 1594 2869 1605 2869 1607 2869 1591 2870 1576 2870 1608 2870 1576 2871 1593 2871 1608 2871 1609 2872 1595 2872 1607 2872 1595 2873 1594 2873 1607 2873 1587 2874 1586 2874 1610 2874 1611 2875 1587 2875 1610 2875 1612 2876 1611 2876 1610 2876 1597 2877 1592 2877 1613 2877 1592 2878 1602 2878 1613 2878 1601 2879 1597 2879 1614 2879 1596 2880 1598 2880 1615 2880 1605 2881 1601 2881 1616 2881 1601 2882 1614 2882 1616 2882 1591 2883 1608 2883 1617 2883 1598 2884 1591 2884 1617 2884 1615 2885 1598 2885 1617 2885 1602 2886 1604 2886 1618 2886 1580 2887 1596 2887 1619 2887 1613 2888 1602 2888 1618 2888 1603 2889 1580 2889 1619 2889 1604 2890 1620 2890 1618 2890 1605 2891 1616 2891 1621 2891 1607 2892 1605 2892 1621 2892 1599 2893 1622 2893 1623 2893 1606 2894 1599 2894 1623 2894 1593 2895 1606 2895 1623 2895 1608 2896 1593 2896 1623 2896 1624 2897 1609 2897 1625 2897 1610 2898 1586 2898 1626 2898 1609 2899 1607 2899 1625 2899 1597 2900 1613 2900 1627 2900 1586 2901 1603 2901 1626 2901 1614 2902 1597 2902 1627 2902 1613 2903 1618 2903 1627 2903 1623 2904 1622 2904 1628 2904 1617 2905 1608 2905 1628 2905 1608 2906 1623 2906 1628 2906 1615 2907 1617 2907 1629 2907 1614 2908 1627 2908 1630 2908 1616 2909 1614 2909 1630 2909 1617 2910 1628 2910 1629 2910 1621 2911 1616 2911 1631 2911 1612 2912 1610 2912 1632 2912 1616 2913 1630 2913 1631 2913 1610 2914 1626 2914 1632 2914 1618 2915 1620 2915 1633 2915 1627 2916 1618 2916 1633 2916 1619 2917 1596 2917 1634 2917 1620 2918 1635 2918 1633 2918 1607 2919 1621 2919 1636 2919 1596 2920 1615 2920 1634 2920 1625 2921 1607 2921 1636 2921 1637 2922 1624 2922 1638 2922 1603 2923 1619 2923 1639 2923 1626 2924 1603 2924 1639 2924 1629 2925 1628 2925 1640 2925 1624 2926 1625 2926 1638 2926 1622 2927 1641 2927 1640 2927 1625 2928 1636 2928 1638 2928 1628 2929 1622 2929 1640 2929 1632 2930 1626 2930 1642 2930 1630 2931 1627 2931 1643 2931 1626 2932 1639 2932 1642 2932 1630 2933 1643 2933 1644 2933 1615 2934 1629 2934 1645 2934 1631 2935 1630 2935 1644 2935 1634 2936 1615 2936 1645 2936 1636 2937 1621 2937 1646 2937 1621 2938 1631 2938 1646 2938 1647 2939 1612 2939 1648 2939 1612 2940 1632 2940 1648 2940 1643 2941 1627 2941 1649 2941 1627 2942 1633 2942 1649 2942 1633 2943 1635 2943 1649 2943 1619 2944 1634 2944 1650 2944 1635 2945 1651 2945 1649 2945 1639 2946 1619 2946 1650 2946 1636 2947 1646 2947 1652 2947 1638 2948 1636 2948 1652 2948 1653 2949 1637 2949 1654 2949 1639 2950 1650 2950 1655 2950 1637 2951 1638 2951 1654 2951 1642 2952 1639 2952 1655 2952 1640 2953 1641 2953 1656 2953 1641 2954 1657 2954 1656 2954 1644 2955 1643 2955 1658 2955 1645 2956 1629 2956 1656 2956 1629 2957 1640 2957 1656 2957 1631 2958 1644 2958 1659 2958 1646 2959 1631 2959 1659 2959 1648 2960 1632 2960 1660 2960 1632 2961 1642 2961 1660 2961 1634 2962 1645 2962 1661 2962 1653 2963 1654 2963 1662 2963 1650 2964 1634 2964 1661 2964 1663 2965 1647 2965 1664 2965 1652 2966 1646 2966 1665 2966 1647 2967 1648 2967 1664 2967 1646 2968 1659 2968 1665 2968 1648 2969 1660 2969 1664 2969 1643 2970 1649 2970 1666 2970 1651 2971 1667 2971 1666 2971 1658 2972 1643 2972 1666 2972 1655 2973 1650 2973 1668 2973 1649 2974 1651 2974 1666 2974 1650 2975 1661 2975 1668 2975 1642 2976 1655 2976 1669 2976 1654 2977 1638 2977 1670 2977 1662 2978 1654 2978 1670 2978 1638 2979 1652 2979 1670 2979 1660 2980 1642 2980 1669 2980 1671 2981 1653 2981 1672 2981 1657 2982 1673 2982 1674 2982 1656 2983 1657 2983 1674 2983 1645 2984 1656 2984 1674 2984 1661 2985 1645 2985 1674 2985 1653 2986 1662 2986 1672 2986 1659 2987 1644 2987 1675 2987 1664 2988 1660 2988 1676 2988 1660 2989 1669 2989 1676 2989 1644 2990 1658 2990 1675 2990 1677 2991 1663 2991 1678 2991 1672 2992 1662 2992 1679 2992 1663 2993 1664 2993 1678 2993 1662 2994 1670 2994 1679 2994 1665 2995 1659 2995 1680 2995 1668 2996 1661 2996 1681 2996 1661 2997 1674 2997 1681 2997 1659 2998 1675 2998 1680 2998 1669 2999 1655 2999 1682 2999 1655 3000 1668 3000 1682 3000 1671 3001 1672 3001 1683 3001 1670 3002 1652 3002 1684 3002 1669 3003 1682 3003 1685 3003 1679 3004 1670 3004 1684 3004 1676 3005 1669 3005 1685 3005 1673 3006 1686 3006 1687 3006 1652 3007 1665 3007 1684 3007 1674 3008 1673 3008 1687 3008 1681 3009 1674 3009 1687 3009 1666 3010 1667 3010 1688 3010 1658 3011 1666 3011 1688 3011 1675 3012 1658 3012 1688 3012 1667 3013 1689 3013 1688 3013 1664 3014 1676 3014 1690 3014 1683 3015 1672 3015 1691 3015 1678 3016 1664 3016 1690 3016 1672 3017 1679 3017 1691 3017 1692 3018 1677 3018 1693 3018 1677 3019 1678 3019 1693 3019 1679 3020 1684 3020 1694 3020 1695 3021 1671 3021 1696 3021 1668 3022 1681 3022 1697 3022 1682 3023 1668 3023 1697 3023 1671 3024 1683 3024 1696 3024 1680 3025 1675 3025 1698 3025 1685 3026 1682 3026 1699 3026 1682 3027 1697 3027 1699 3027 1676 3028 1685 3028 1700 3028 1690 3029 1676 3029 1700 3029 1683 3030 1691 3030 1701 3030 1686 3031 1702 3031 1703 3031 1684 3032 1665 3032 1704 3032 1694 3033 1684 3033 1704 3033 1681 3034 1687 3034 1703 3034 1697 3035 1681 3035 1703 3035 1687 3036 1686 3036 1703 3036 1665 3037 1680 3037 1704 3037 1678 3038 1690 3038 1705 3038 1693 3039 1678 3039 1705 3039 1695 3040 1696 3040 1706 3040 1707 3041 1692 3041 1708 3041 1679 3042 1694 3042 1709 3042 1692 3043 1693 3043 1708 3043 1691 3044 1679 3044 1709 3044 1694 3045 1704 3045 1710 3045 1699 3046 1697 3046 1711 3046 1709 3047 1694 3047 1710 3047 1697 3048 1703 3048 1711 3048 1675 3049 1688 3049 1712 3049 1698 3050 1675 3050 1712 3050 1685 3051 1699 3051 1713 3051 1688 3052 1689 3052 1712 3052 1700 3053 1685 3053 1713 3053 1689 3054 1714 3054 1712 3054 1696 3055 1683 3055 1715 3055 1683 3056 1701 3056 1715 3056 1690 3057 1700 3057 1716 3057 1705 3058 1690 3058 1716 3058 1701 3059 1691 3059 1717 3059 1702 3060 1718 3060 1719 3060 1691 3061 1709 3061 1717 3061 1711 3062 1703 3062 1719 3062 1703 3063 1702 3063 1719 3063 1720 3064 1695 3064 1721 3064 1693 3065 1705 3065 1722 3065 1695 3066 1706 3066 1721 3066 1708 3067 1693 3067 1722 3067 1708 3068 1722 3068 1723 3068 1704 3069 1680 3069 1724 3069 1680 3070 1698 3070 1724 3070 1725 3071 1707 3071 1723 3071 1710 3072 1704 3072 1724 3072 1707 3073 1708 3073 1723 3073 1696 3074 1715 3074 1726 3074 1706 3075 1696 3075 1726 3075 1721 3076 1706 3076 1726 3076 1699 3077 1711 3077 1727 3077 1713 3078 1699 3078 1727 3078 1709 3079 1710 3079 1728 3079 1717 3080 1709 3080 1728 3080 1700 3081 1713 3081 1729 3081 1716 3082 1700 3082 1729 3082 1710 3083 1724 3083 1730 3083 1725 3084 1723 3084 1731 3084 1720 3085 1721 3085 1732 3085 1705 3086 1716 3086 1733 3086 1715 3087 1701 3087 1098 3087 1701 3088 1717 3088 1098 3088 1722 3089 1705 3089 1733 3089 1711 3090 1719 3090 1734 3090 1718 3091 1735 3091 1734 3091 1719 3092 1718 3092 1734 3092 1727 3093 1711 3093 1734 3093 1717 3094 1728 3094 1118 3094 1722 3095 1733 3095 1736 3095 1731 3096 1723 3096 1736 3096 1724 3097 1698 3097 1737 3097 1723 3098 1722 3098 1736 3098 1712 3099 1714 3099 1737 3099 1730 3100 1724 3100 1737 3100 1738 3101 1725 3101 1739 3101 1714 3102 1740 3102 1737 3102 1698 3103 1712 3103 1737 3103 1725 3104 1731 3104 1739 3104 1732 3105 1721 3105 1741 3105 1713 3106 1727 3106 1128 3106 1721 3107 1726 3107 1741 3107 1108 3108 1720 3108 1092 3108 1729 3109 1713 3109 1128 3109 1720 3110 1732 3110 1092 3110 1726 3111 1715 3111 1106 3111 1731 3112 1736 3112 1115 3112 1715 3113 1098 3113 1106 3113 1733 3114 1716 3114 1102 3114 1716 3115 1729 3115 1102 3115 1740 3116 1123 3116 1742 3116 1730 3117 1737 3117 1742 3117 1737 3118 1740 3118 1742 3118 1728 3119 1710 3119 1743 3119 1710 3120 1730 3120 1743 3120 1738 3121 1739 3121 1096 3121 1092 3122 1732 3122 1093 3122 1736 3123 1733 3123 1101 3123 1733 3124 1102 3124 1101 3124 1115 3125 1736 3125 1101 3125 1732 3126 1741 3126 1093 3126 1735 3127 1125 3127 1129 3127 1734 3128 1735 3128 1129 3128 1098 3129 1717 3129 1099 3129 1727 3130 1734 3130 1129 3130 1128 3131 1727 3131 1129 3131 1717 3132 1118 3132 1099 3132 1739 3133 1731 3133 1117 3133 1731 3134 1115 3134 1117 3134 1096 3135 1739 3135 1117 3135 1118 3136 1728 3136 1119 3136 1728 3137 1743 3137 1119 3137 1726 3138 1106 3138 1105 3138 1115 3139 1101 3139 1104 3139 1741 3140 1726 3140 1105 3140 1093 3141 1741 3141 1105 3141 1738 3142 1096 3142 1095 3142 1112 3143 1738 3143 1095 3143 1108 3144 1092 3144 1109 3144 1102 3145 1729 3145 1107 3145 1730 3146 1742 3146 1122 3146 1729 3147 1128 3147 1107 3147 1119 3148 1743 3148 1122 3148 1743 3149 1730 3149 1122 3149 1742 3150 1123 3150 1122 3150 1096 3151 1117 3151 1097 3151 605 3152 1744 3152 1745 3152 605 3153 1745 3153 1746 3153 605 3154 582 3154 1744 3154 615 3155 1746 3155 1747 3155 615 3156 605 3156 1746 3156 616 3157 1747 3157 1748 3157 616 3158 615 3158 1747 3158 656 3159 1748 3159 1749 3159 656 3160 616 3160 1748 3160 666 3161 1749 3161 1750 3161 666 3162 656 3162 1749 3162 698 3163 1750 3163 1751 3163 698 3164 666 3164 1750 3164 737 3165 698 3165 1751 3165 737 3166 1751 3166 1752 3166 779 3167 737 3167 1752 3167 779 3168 1752 3168 1753 3168 821 3169 1753 3169 1754 3169 821 3170 779 3170 1753 3170 870 3171 821 3171 1754 3171 909 3172 870 3172 1754 3172 909 3173 1754 3173 1755 3173 946 3174 1755 3174 1756 3174 946 3175 1756 3175 1757 3175 946 3176 909 3176 1755 3176 978 3177 946 3177 1757 3177 1003 3178 1757 3178 1758 3178 1003 3179 978 3179 1757 3179 1027 3180 1758 3180 1759 3180 1027 3181 1003 3181 1758 3181 1028 3182 1759 3182 1760 3182 1028 3183 1027 3183 1759 3183 1067 3184 1760 3184 1761 3184 1067 3185 1028 3185 1760 3185 1086 3186 1761 3186 1762 3186 1086 3187 1067 3187 1761 3187 219 3188 1762 3188 1763 3188 219 3189 1086 3189 1762 3189 220 3190 1763 3190 1764 3190 220 3191 219 3191 1763 3191 262 3192 1764 3192 1765 3192 262 3193 220 3193 1764 3193 293 3194 1765 3194 1766 3194 293 3195 262 3195 1765 3195 323 3196 1766 3196 1767 3196 323 3197 293 3197 1766 3197 353 3198 1767 3198 1768 3198 353 3199 323 3199 1767 3199 382 3200 1768 3200 1769 3200 382 3201 353 3201 1768 3201 405 3202 1769 3202 1770 3202 405 3203 382 3203 1769 3203 426 3204 1770 3204 1771 3204 426 3205 405 3205 1770 3205 445 3206 1771 3206 1772 3206 445 3207 426 3207 1771 3207 460 3208 1772 3208 1773 3208 460 3209 445 3209 1772 3209 473 3210 1773 3210 1774 3210 473 3211 460 3211 1773 3211 474 3212 1774 3212 1775 3212 474 3213 473 3213 1774 3213 489 3214 474 3214 1775 3214 489 3215 1775 3215 1776 3215 513 3216 489 3216 1776 3216 513 3217 1776 3217 1777 3217 534 3218 513 3218 1777 3218 534 3219 1777 3219 1778 3219 559 3220 534 3220 1778 3220 559 3221 1778 3221 1779 3221 591 3222 559 3222 1779 3222 591 3223 1779 3223 1780 3223 634 3224 591 3224 1780 3224 634 3225 1780 3225 1781 3225 681 3226 634 3226 1781 3226 681 3227 1781 3227 1782 3227 723 3228 681 3228 1782 3228 723 3229 1782 3229 1783 3229 760 3230 723 3230 1783 3230 760 3231 1783 3231 1784 3231 793 3232 760 3232 1784 3232 793 3233 1784 3233 1785 3233 818 3234 1785 3234 1786 3234 818 3235 793 3235 1785 3235 840 3236 1786 3236 1787 3236 840 3237 818 3237 1786 3237 841 3238 840 3238 1787 3238 841 3239 1787 3239 1788 3239 864 3240 1788 3240 1789 3240 864 3241 841 3241 1788 3241 908 3242 1789 3242 1790 3242 908 3243 864 3243 1789 3243 920 3244 1790 3244 1791 3244 920 3245 908 3245 1790 3245 949 3246 1791 3246 1792 3246 949 3247 920 3247 1791 3247 987 3248 1792 3248 1793 3248 987 3249 949 3249 1792 3249 1034 3250 1793 3250 1794 3250 1034 3251 987 3251 1793 3251 1072 3252 1794 3252 1795 3252 1072 3253 1034 3253 1794 3253 255 3254 1795 3254 1796 3254 255 3255 1072 3255 1795 3255 256 3256 1796 3256 1797 3256 256 3257 255 3257 1796 3257 279 3258 1797 3258 1798 3258 279 3259 256 3259 1797 3259 301 3260 1798 3260 1799 3260 301 3261 279 3261 1798 3261 320 3262 1799 3262 1800 3262 320 3263 301 3263 1799 3263 334 3264 1800 3264 1801 3264 334 3265 320 3265 1800 3265 335 3266 334 3266 1801 3266 335 3267 1801 3267 1802 3267 349 3268 335 3268 1802 3268 349 3269 1802 3269 1803 3269 377 3270 349 3270 1803 3270 377 3271 1803 3271 1804 3271 387 3272 377 3272 1804 3272 387 3273 1804 3273 1805 3273 407 3274 387 3274 1805 3274 407 3275 1805 3275 1806 3275 433 3276 407 3276 1806 3276 433 3277 1806 3277 1807 3277 464 3278 433 3278 1807 3278 464 3279 1807 3279 1808 3279 491 3280 464 3280 1808 3280 491 3281 1808 3281 1809 3281 521 3282 491 3282 1809 3282 521 3283 1809 3283 1810 3283 548 3284 521 3284 1810 3284 548 3285 1810 3285 1811 3285 572 3286 548 3286 1811 3286 572 3287 1811 3287 1812 3287 598 3288 572 3288 1812 3288 598 3289 1812 3289 1813 3289 627 3290 598 3290 1813 3290 627 3291 1813 3291 1814 3291 648 3292 627 3292 1814 3292 648 3293 1814 3293 1815 3293 648 3294 1815 3294 1816 3294 649 3295 648 3295 1816 3295 694 3296 649 3296 1816 3296 694 3297 1816 3297 1817 3297 715 3298 694 3298 1817 3298 715 3299 1817 3299 1818 3299 729 3300 715 3300 1818 3300 729 3301 1818 3301 1819 3301 729 3302 1819 3302 1820 3302 757 3303 1820 3303 1821 3303 757 3304 729 3304 1820 3304 795 3305 1821 3305 1822 3305 795 3306 757 3306 1821 3306 843 3307 1822 3307 1823 3307 843 3308 795 3308 1822 3308 884 3309 1823 3309 1824 3309 884 3310 843 3310 1823 3310 930 3311 1824 3311 1825 3311 930 3312 884 3312 1824 3312 973 3313 1825 3313 1826 3313 973 3314 930 3314 1825 3314 1011 3315 973 3315 1826 3315 1011 3316 1826 3316 1827 3316 581 3317 1011 3317 1827 3317 582 3318 581 3318 1827 3318 582 3319 1827 3319 1744 3319 1303 3320 1828 3320 1829 3320 1287 3321 1829 3321 1830 3321 1287 3322 1303 3322 1829 3322 1285 3323 1830 3323 1831 3323 1285 3324 1287 3324 1830 3324 1236 3325 1831 3325 1832 3325 1236 3326 1285 3326 1831 3326 1214 3327 1832 3327 1833 3327 1214 3328 1236 3328 1832 3328 1186 3329 1833 3329 1834 3329 1186 3330 1214 3330 1833 3330 1160 3331 1834 3331 1835 3331 1160 3332 1186 3332 1834 3332 1135 3333 1835 3333 1836 3333 1135 3334 1160 3334 1835 3334 1112 3335 1836 3335 1837 3335 1112 3336 1135 3336 1836 3336 1738 3337 1837 3337 1838 3337 1738 3338 1112 3338 1837 3338 1725 3339 1838 3339 1839 3339 1725 3340 1738 3340 1838 3340 1707 3341 1839 3341 1840 3341 1707 3342 1725 3342 1839 3342 1692 3343 1840 3343 1841 3343 1692 3344 1707 3344 1840 3344 1677 3345 1841 3345 1842 3345 1677 3346 1692 3346 1841 3346 1663 3347 1842 3347 1843 3347 1663 3348 1677 3348 1842 3348 1647 3349 1843 3349 1844 3349 1647 3350 1663 3350 1843 3350 1612 3351 1844 3351 1845 3351 1612 3352 1647 3352 1844 3352 1611 3353 1845 3353 1846 3353 1611 3354 1612 3354 1845 3354 1587 3355 1846 3355 1847 3355 1587 3356 1611 3356 1846 3356 1541 3357 1587 3357 1847 3357 1541 3358 1847 3358 1848 3358 1511 3359 1541 3359 1848 3359 1511 3360 1848 3360 1849 3360 1483 3361 1511 3361 1849 3361 1483 3362 1849 3362 1850 3362 1460 3363 1483 3363 1850 3363 1460 3364 1850 3364 1851 3364 1436 3365 1460 3365 1851 3365 1436 3366 1851 3366 1852 3366 1411 3367 1852 3367 1853 3367 1411 3368 1436 3368 1852 3368 1394 3369 1853 3369 1854 3369 1394 3370 1411 3370 1853 3370 1378 3371 1854 3371 1855 3371 1378 3372 1394 3372 1854 3372 1367 3373 1855 3373 1856 3373 1367 3374 1378 3374 1855 3374 1359 3375 1856 3375 1857 3375 1359 3376 1367 3376 1856 3376 1352 3377 1857 3377 1858 3377 1352 3378 1359 3378 1857 3378 1240 3379 1858 3379 1859 3379 1240 3380 1859 3380 1860 3380 1240 3381 1352 3381 1858 3381 1239 3382 1860 3382 1861 3382 1239 3383 1240 3383 1860 3383 1199 3384 1861 3384 1862 3384 1199 3385 1239 3385 1861 3385 1197 3386 1862 3386 1863 3386 1197 3387 1199 3387 1862 3387 1149 3388 1863 3388 1864 3388 1149 3389 1197 3389 1863 3389 1111 3390 1864 3390 1865 3390 1111 3391 1149 3391 1864 3391 1108 3392 1865 3392 1866 3392 1108 3393 1111 3393 1865 3393 1720 3394 1866 3394 1867 3394 1720 3395 1108 3395 1866 3395 1695 3396 1867 3396 1868 3396 1695 3397 1720 3397 1867 3397 1671 3398 1868 3398 1869 3398 1671 3399 1695 3399 1868 3399 1653 3400 1869 3400 1870 3400 1653 3401 1671 3401 1869 3401 1637 3402 1870 3402 1871 3402 1637 3403 1653 3403 1870 3403 1624 3404 1871 3404 1872 3404 1624 3405 1637 3405 1871 3405 1609 3406 1624 3406 1872 3406 1609 3407 1872 3407 1873 3407 1595 3408 1609 3408 1873 3408 1595 3409 1873 3409 1874 3409 1579 3410 1595 3410 1874 3410 1579 3411 1874 3411 1875 3411 1546 3412 1579 3412 1875 3412 1546 3413 1875 3413 1876 3413 1526 3414 1546 3414 1876 3414 1526 3415 1876 3415 1877 3415 1524 3416 1526 3416 1877 3416 1524 3417 1877 3417 1878 3417 1477 3418 1524 3418 1878 3418 1477 3419 1878 3419 1879 3419 1450 3420 1477 3420 1879 3420 1450 3421 1879 3421 1880 3421 1421 3422 1450 3422 1880 3422 1421 3423 1880 3423 1881 3423 1398 3424 1421 3424 1881 3424 1398 3425 1881 3425 1882 3425 1375 3426 1398 3426 1882 3426 1375 3427 1882 3427 1883 3427 1354 3428 1375 3428 1883 3428 1354 3429 1883 3429 1884 3429 1342 3430 1354 3430 1884 3430 1342 3431 1884 3431 1885 3431 1335 3432 1342 3432 1885 3432 1335 3433 1885 3433 1886 3433 1326 3434 1335 3434 1886 3434 1326 3435 1886 3435 1887 3435 1318 3436 1887 3436 1888 3436 1318 3437 1326 3437 1887 3437 1311 3438 1888 3438 1889 3438 1311 3439 1318 3439 1888 3439 1303 3440 1889 3440 1828 3440 1303 3441 1311 3441 1889 3441 1829 3442 1890 3442 1891 3442 1829 3443 1828 3443 1890 3443 1830 3444 1891 3444 1892 3444 1830 3445 1829 3445 1891 3445 1831 3446 1892 3446 1893 3446 1831 3447 1830 3447 1892 3447 1832 3448 1893 3448 1894 3448 1832 3449 1831 3449 1893 3449 1833 3450 1894 3450 1895 3450 1833 3451 1832 3451 1894 3451 1834 3452 1895 3452 1896 3452 1834 3453 1833 3453 1895 3453 1835 3454 1896 3454 1897 3454 1835 3455 1834 3455 1896 3455 1836 3456 1835 3456 1897 3456 1837 3457 1897 3457 1898 3457 1837 3458 1836 3458 1897 3458 1838 3459 1898 3459 1899 3459 1838 3460 1837 3460 1898 3460 1839 3461 1899 3461 1900 3461 1839 3462 1838 3462 1899 3462 1840 3463 1900 3463 1901 3463 1840 3464 1839 3464 1900 3464 1841 3465 1901 3465 1902 3465 1841 3466 1840 3466 1901 3466 1842 3467 1902 3467 1903 3467 1842 3468 1841 3468 1902 3468 1843 3469 1842 3469 1903 3469 1844 3470 1903 3470 1904 3470 1844 3471 1843 3471 1903 3471 1845 3472 1904 3472 1905 3472 1845 3473 1844 3473 1904 3473 1846 3474 1905 3474 1906 3474 1846 3475 1845 3475 1905 3475 1847 3476 1906 3476 1907 3476 1847 3477 1846 3477 1906 3477 1848 3478 1907 3478 1908 3478 1848 3479 1847 3479 1907 3479 1849 3480 1848 3480 1908 3480 1849 3481 1908 3481 1909 3481 1850 3482 1849 3482 1909 3482 1850 3483 1909 3483 1910 3483 1851 3484 1850 3484 1910 3484 1852 3485 1851 3485 1910 3485 1852 3486 1910 3486 1911 3486 1853 3487 1852 3487 1911 3487 1853 3488 1911 3488 1912 3488 1854 3489 1853 3489 1912 3489 1854 3490 1912 3490 1913 3490 1855 3491 1913 3491 1914 3491 1855 3492 1854 3492 1913 3492 1856 3493 1914 3493 1915 3493 1856 3494 1855 3494 1914 3494 1857 3495 1915 3495 1916 3495 1857 3496 1856 3496 1915 3496 1858 3497 1916 3497 1917 3497 1858 3498 1857 3498 1916 3498 1859 3499 1858 3499 1917 3499 1860 3500 1917 3500 1918 3500 1860 3501 1859 3501 1917 3501 1861 3502 1918 3502 1919 3502 1861 3503 1860 3503 1918 3503 1862 3504 1919 3504 1920 3504 1862 3505 1861 3505 1919 3505 1863 3506 1920 3506 1921 3506 1863 3507 1862 3507 1920 3507 1864 3508 1921 3508 1922 3508 1864 3509 1863 3509 1921 3509 1865 3510 1922 3510 1923 3510 1865 3511 1864 3511 1922 3511 1866 3512 1923 3512 1924 3512 1866 3513 1865 3513 1923 3513 1867 3514 1866 3514 1924 3514 1868 3515 1924 3515 1925 3515 1868 3516 1867 3516 1924 3516 1869 3517 1925 3517 1926 3517 1869 3518 1868 3518 1925 3518 1870 3519 1926 3519 1927 3519 1870 3520 1869 3520 1926 3520 1871 3521 1927 3521 1928 3521 1871 3522 1870 3522 1927 3522 1872 3523 1928 3523 1929 3523 1872 3524 1871 3524 1928 3524 1873 3525 1929 3525 1930 3525 1873 3526 1872 3526 1929 3526 1874 3527 1873 3527 1930 3527 1875 3528 1930 3528 1931 3528 1875 3529 1874 3529 1930 3529 1876 3530 1931 3530 1932 3530 1876 3531 1875 3531 1931 3531 1877 3532 1876 3532 1932 3532 1877 3533 1932 3533 1933 3533 1878 3534 1877 3534 1933 3534 1878 3535 1933 3535 1934 3535 1879 3536 1878 3536 1934 3536 1879 3537 1934 3537 1935 3537 1880 3538 1879 3538 1935 3538 1880 3539 1935 3539 1936 3539 1881 3540 1880 3540 1936 3540 1881 3541 1936 3541 1937 3541 1882 3542 1881 3542 1937 3542 1883 3543 1882 3543 1937 3543 1883 3544 1937 3544 1938 3544 1884 3545 1883 3545 1938 3545 1884 3546 1938 3546 1939 3546 1885 3547 1884 3547 1939 3547 1885 3548 1939 3548 1940 3548 1886 3549 1885 3549 1940 3549 1886 3550 1940 3550 1941 3550 1887 3551 1886 3551 1941 3551 1887 3552 1941 3552 1942 3552 1888 3553 1887 3553 1942 3553 1888 3554 1942 3554 1943 3554 1889 3555 1888 3555 1943 3555 1889 3556 1943 3556 1890 3556 1828 3557 1889 3557 1890 3557 725 3558 1944 3558 688 3558 1945 3559 1946 3559 366 3559 251 3560 281 3560 1947 3560 1945 3561 366 3561 381 3561 1945 3562 381 3562 401 3562 1945 3563 401 3563 424 3563 1945 3564 424 3564 452 3564 763 3565 1944 3565 725 3565 1945 3566 452 3566 478 3566 1945 3567 478 3567 505 3567 1945 3568 505 3568 532 3568 1945 3569 532 3569 556 3569 1945 3570 556 3570 583 3570 1945 3571 583 3571 604 3571 252 3572 251 3572 1947 3572 1945 3573 604 3573 623 3573 1945 3574 623 3574 675 3574 802 3575 1944 3575 763 3575 700 3576 1945 3576 675 3576 1089 3577 252 3577 1947 3577 845 3578 1944 3578 802 3578 1048 3579 1089 3579 1947 3579 1048 3580 1947 3580 1944 3580 1948 3581 890 3581 1946 3581 1948 3582 607 3582 653 3582 886 3583 1944 3583 845 3583 1948 3584 653 3584 697 3584 1948 3585 697 3585 735 3585 1948 3586 735 3586 771 3586 1948 3587 771 3587 801 3587 1022 3588 1048 3588 1944 3588 1948 3589 801 3589 836 3589 1948 3590 836 3590 866 3590 1948 3591 866 3591 890 3591 923 3592 1944 3592 886 3592 1020 3593 1022 3593 1944 3593 957 3594 1944 3594 923 3594 576 3595 607 3595 1948 3595 984 3596 1020 3596 1944 3596 984 3597 1944 3597 957 3597 550 3598 576 3598 1948 3598 527 3599 550 3599 1948 3599 1949 3600 1945 3600 700 3600 1949 3601 700 3601 720 3601 1949 3602 720 3602 750 3602 1949 3603 750 3603 786 3603 1949 3604 786 3604 825 3604 863 3605 1949 3605 825 3605 507 3606 527 3606 1948 3606 905 3607 1949 3607 863 3607 493 3608 507 3608 1948 3608 950 3609 1949 3609 905 3609 1947 3610 493 3610 1948 3610 456 3611 493 3611 1947 3611 988 3612 1949 3612 950 3612 441 3613 456 3613 1947 3613 1025 3614 1949 3614 988 3614 431 3615 441 3615 1947 3615 1056 3616 1949 3616 1025 3616 412 3617 431 3617 1947 3617 1081 3618 1949 3618 1056 3618 389 3619 412 3619 1947 3619 1087 3620 1949 3620 1081 3620 1946 3621 890 3621 911 3621 1946 3622 911 3622 941 3622 364 3623 389 3623 1947 3623 1946 3624 941 3624 975 3624 1946 3625 975 3625 1014 3625 1946 3626 1014 3626 1052 3626 1946 3627 1052 3627 223 3627 1946 3628 223 3628 227 3628 1946 3629 227 3629 264 3629 660 3630 1944 3630 1949 3630 1946 3631 264 3631 287 3631 1946 3632 287 3632 308 3632 660 3633 1949 3633 1087 3633 1946 3634 308 3634 317 3634 1946 3635 317 3635 332 3635 1946 3636 332 3636 366 3636 338 3637 364 3637 1947 3637 661 3638 1944 3638 660 3638 307 3639 338 3639 1947 3639 688 3640 1944 3640 661 3640 281 3641 307 3641 1947 3641 1918 3642 1890 3642 1919 3642 1903 3643 1902 3643 1890 3643 1917 3644 1890 3644 1918 3644 1916 3645 1890 3645 1917 3645 1905 3646 1904 3646 1903 3646 1905 3647 1903 3647 1890 3647 1914 3648 1916 3648 1915 3648 1907 3649 1906 3649 1905 3649 1913 3650 1890 3650 1916 3650 1913 3651 1916 3651 1914 3651 1908 3652 1905 3652 1890 3652 1908 3653 1907 3653 1905 3653 1911 3654 1913 3654 1912 3654 1890 3655 1933 3655 1932 3655 1890 3656 1934 3656 1933 3656 1890 3657 1935 3657 1934 3657 1910 3658 1909 3658 1908 3658 1890 3659 1936 3659 1935 3659 1910 3660 1908 3660 1890 3660 1890 3661 1937 3661 1936 3661 1910 3662 1890 3662 1913 3662 1890 3663 1938 3663 1937 3663 1910 3664 1913 3664 1911 3664 1890 3665 1939 3665 1938 3665 1890 3666 1940 3666 1939 3666 1890 3667 1941 3667 1940 3667 1890 3668 1942 3668 1941 3668 1890 3669 1943 3669 1942 3669 1930 3670 1932 3670 1931 3670 1930 3671 1890 3671 1932 3671 1929 3672 1890 3672 1930 3672 1892 3673 1891 3673 1890 3673 1928 3674 1890 3674 1929 3674 1893 3675 1892 3675 1890 3675 1927 3676 1890 3676 1928 3676 1894 3677 1893 3677 1890 3677 1926 3678 1890 3678 1927 3678 1895 3679 1894 3679 1890 3679 1896 3680 1895 3680 1890 3680 1924 3681 1890 3681 1926 3681 1924 3682 1926 3682 1925 3682 1897 3683 1896 3683 1890 3683 1923 3684 1890 3684 1924 3684 1898 3685 1897 3685 1890 3685 1899 3686 1898 3686 1890 3686 1921 3687 1923 3687 1922 3687 1900 3688 1899 3688 1890 3688 1920 3689 1923 3689 1921 3689 1919 3690 1890 3690 1923 3690 1919 3691 1923 3691 1920 3691 1902 3692 1901 3692 1900 3692 1902 3693 1900 3693 1890 3693 1769 3694 1768 3694 1657 3694 1770 3695 1769 3695 1657 3695 1770 3696 1657 3696 1641 3696 1781 3697 1429 3697 1782 3697 1781 3698 1452 3698 1429 3698 1780 3699 1452 3699 1781 3699 1780 3700 1479 3700 1452 3700 1771 3701 1770 3701 1641 3701 1771 3702 1641 3702 1622 3702 1779 3703 1479 3703 1780 3703 1779 3704 1490 3704 1479 3704 1772 3705 1622 3705 1599 3705 1772 3706 1771 3706 1622 3706 1778 3707 1490 3707 1779 3707 1773 3708 1772 3708 1599 3708 1774 3709 1773 3709 1599 3709 1774 3710 1599 3710 1574 3710 1777 3711 1490 3711 1778 3711 1777 3712 1519 3712 1490 3712 1776 3713 1519 3713 1777 3713 1776 3714 1550 3714 1519 3714 1775 3715 1550 3715 1776 3715 1775 3716 1774 3716 1574 3716 1775 3717 1574 3717 1550 3717 1486 3718 1818 3718 1817 3718 1458 3719 1818 3719 1486 3719 1458 3720 1819 3720 1818 3720 1510 3721 1486 3721 1817 3721 1510 3722 1817 3722 1816 3722 1427 3723 1819 3723 1458 3723 1427 3724 1820 3724 1819 3724 1427 3725 1821 3725 1820 3725 1537 3726 1510 3726 1816 3726 1537 3727 1815 3727 1814 3727 1537 3728 1816 3728 1815 3728 1557 3729 1537 3729 1814 3729 1557 3730 1814 3730 1813 3730 1418 3731 1822 3731 1821 3731 1418 3732 1821 3732 1427 3732 1392 3733 1822 3733 1418 3733 1392 3734 1823 3734 1822 3734 1572 3735 1557 3735 1813 3735 1572 3736 1813 3736 1812 3736 1589 3737 1572 3737 1812 3737 1589 3738 1811 3738 1810 3738 1589 3739 1812 3739 1811 3739 1369 3740 1824 3740 1823 3740 1369 3741 1825 3741 1824 3741 1369 3742 1823 3742 1392 3742 1604 3743 1589 3743 1810 3743 1604 3744 1810 3744 1809 3744 1349 3745 1825 3745 1369 3745 1349 3746 1826 3746 1825 3746 1620 3747 1604 3747 1809 3747 1620 3748 1809 3748 1808 3748 1340 3749 1826 3749 1349 3749 1340 3750 1827 3750 1826 3750 1635 3751 1620 3751 1808 3751 1635 3752 1807 3752 1806 3752 1635 3753 1808 3753 1807 3753 1332 3754 1745 3754 1744 3754 1332 3755 1827 3755 1340 3755 1332 3756 1744 3756 1827 3756 1651 3757 1635 3757 1806 3757 1651 3758 1806 3758 1805 3758 1323 3759 1746 3759 1745 3759 1323 3760 1745 3760 1332 3760 1667 3761 1651 3761 1805 3761 1667 3762 1805 3762 1804 3762 1315 3763 1747 3763 1746 3763 1315 3764 1746 3764 1323 3764 1689 3765 1667 3765 1804 3765 1689 3766 1803 3766 1802 3766 1689 3767 1804 3767 1803 3767 1307 3768 1748 3768 1747 3768 1307 3769 1749 3769 1748 3769 1307 3770 1747 3770 1315 3770 1714 3771 1689 3771 1802 3771 1714 3772 1802 3772 1801 3772 1299 3773 1749 3773 1307 3773 1299 3774 1750 3774 1749 3774 1740 3775 1714 3775 1801 3775 1740 3776 1801 3776 1800 3776 1291 3777 1751 3777 1750 3777 1291 3778 1750 3778 1299 3778 1123 3779 1740 3779 1800 3779 1123 3780 1800 3780 1799 3780 1281 3781 1752 3781 1751 3781 1281 3782 1751 3782 1291 3782 1798 3783 1123 3783 1799 3783 1753 3784 1752 3784 1281 3784 1130 3785 1123 3785 1798 3785 1251 3786 1753 3786 1281 3786 1797 3787 1130 3787 1798 3787 1754 3788 1753 3788 1251 3788 1158 3789 1130 3789 1797 3789 1221 3790 1754 3790 1251 3790 1796 3791 1158 3791 1797 3791 1755 3792 1754 3792 1221 3792 1183 3793 1158 3793 1796 3793 1193 3794 1755 3794 1221 3794 1795 3795 1183 3795 1796 3795 1756 3796 1755 3796 1193 3796 1210 3797 1183 3797 1795 3797 1164 3798 1756 3798 1193 3798 1794 3799 1210 3799 1795 3799 1757 3800 1756 3800 1164 3800 1793 3801 1210 3801 1794 3801 1793 3802 1230 3802 1210 3802 1758 3803 1757 3803 1164 3803 1758 3804 1164 3804 1154 3804 1792 3805 1230 3805 1793 3805 1792 3806 1250 3806 1230 3806 1759 3807 1154 3807 1126 3807 1759 3808 1758 3808 1154 3808 1791 3809 1250 3809 1792 3809 1791 3810 1262 3810 1250 3810 1760 3811 1126 3811 1125 3811 1760 3812 1759 3812 1126 3812 1790 3813 1262 3813 1791 3813 1761 3814 1760 3814 1125 3814 1789 3815 1262 3815 1790 3815 1789 3816 1270 3816 1262 3816 1762 3817 1125 3817 1735 3817 1762 3818 1761 3818 1125 3818 1788 3819 1270 3819 1789 3819 1788 3820 1277 3820 1270 3820 1763 3821 1735 3821 1718 3821 1763 3822 1762 3822 1735 3822 1787 3823 1351 3823 1277 3823 1787 3824 1277 3824 1788 3824 1764 3825 1718 3825 1702 3825 1764 3826 1763 3826 1718 3826 1786 3827 1351 3827 1787 3827 1765 3828 1764 3828 1702 3828 1785 3829 1351 3829 1786 3829 1785 3830 1389 3830 1351 3830 1766 3831 1702 3831 1686 3831 1766 3832 1765 3832 1702 3832 1784 3833 1407 3833 1389 3833 1784 3834 1389 3834 1785 3834 1767 3835 1686 3835 1673 3835 1767 3836 1766 3836 1686 3836 1783 3837 1407 3837 1784 3837 1783 3838 1429 3838 1407 3838 1768 3839 1673 3839 1657 3839 1768 3840 1767 3840 1673 3840 1782 3841 1429 3841 1783 3841 198 3842 1944 3842 1947 3842 198 3843 1950 3843 1944 3843 1951 3844 198 3844 1947 3844 1949 3845 1944 3845 190 3845 1944 3846 1950 3846 190 3846 1949 3847 190 3847 1952 3847 178 3848 1945 3848 1949 3848 178 3849 1953 3849 1945 3849 1952 3850 178 3850 1949 3850 142 3851 1946 3851 1945 3851 142 3852 1954 3852 1946 3852 1953 3853 142 3853 1945 3853 1948 3854 1946 3854 16 3854 1946 3855 1954 3855 16 3855 1948 3856 16 3856 1955 3856 1947 3857 1948 3857 206 3857 1948 3858 1955 3858 206 3858 1947 3859 206 3859 1951 3859 164 3860 127 3860 1954 3860 132 3861 164 3861 1954 3861 133 3862 132 3862 1954 3862 1954 3863 127 3863 126 3863 1954 3864 126 3864 124 3864 1954 3865 124 3865 17 3865 17 3866 16 3866 1954 3866 133 3867 1954 3867 142 3867 169 3868 168 3868 1953 3868 1953 3869 168 3869 167 3869 1953 3870 167 3870 157 3870 1953 3871 157 3871 156 3871 1953 3872 156 3872 155 3872 1953 3873 155 3873 143 3873 143 3874 142 3874 1953 3874 169 3875 1953 3875 178 3875 184 3876 1952 3876 185 3876 1952 3877 184 3877 179 3877 185 3878 1952 3878 186 3878 186 3879 1952 3879 187 3879 187 3880 1952 3880 188 3880 188 3881 1952 3881 189 3881 179 3882 178 3882 1952 3882 189 3883 1952 3883 190 3883 192 3884 191 3884 1950 3884 193 3885 192 3885 1950 3885 193 3886 1950 3886 194 3886 194 3887 1950 3887 195 3887 195 3888 1950 3888 196 3888 191 3889 190 3889 1950 3889 197 3890 1950 3890 198 3890 196 3891 1950 3891 197 3891 200 3892 199 3892 1951 3892 201 3893 200 3893 1951 3893 202 3894 201 3894 1951 3894 203 3895 202 3895 1951 3895 203 3896 1951 3896 204 3896 204 3897 1951 3897 205 3897 199 3898 198 3898 1951 3898 205 3899 1951 3899 206 3899 176 3900 175 3900 1955 3900 151 3901 176 3901 1955 3901 152 3902 151 3902 1955 3902 154 3903 152 3903 1955 3903 103 3904 154 3904 1955 3904 207 3905 206 3905 1955 3905 175 3906 207 3906 1955 3906 103 3907 1955 3907 16 3907

+
+
+
+ + + + 7 -11.5 88.5 6.991445 -11.36947 88.5 6.861707 -11.34806 88.42783 6.738606 -11.36976 88.35566 6.704769 -11.24348 88.35566 6.383022 -11.17861 88.21132 6.541266 -11.1875 88.28349 6.401742 -11.02122 88.28349 6.574533 -11.01791 88.35566 6.375 -10.85048 88.35566 6.25 -11.06699 88.21132 5.956588 -11.2538 88.06699 5.875 -11.28349 88.06699 5.933987 -11.34696 88.01887 5.971059 -11.33587 88.01887 6.043412 -11.2538 88.06699 6 -11.125 88.13916 6.086824 -11.0076 88.21132 5.913176 -11.0076 88.21132 6.128258 -11.14762 88.13916 6.130236 -10.76139 88.35566 6.213763 -10.91269 88.28349 5.871742 -11.14762 88.13916 5.75 -11.06699 88.21132 5.869764 -10.76139 88.35566 6 -10.875 88.28349 5.758955 -11.21273 88.13916 5.808489 -11.3393 88.06699 5.616978 -11.17861 88.21132 5.786237 -10.91269 88.28349 5.625 -10.85048 88.35566 5.67524 -11.3125 88.13916 5.765077 -11.41449 88.06699 5.530154 -11.32899 88.21132 5.598258 -11.02122 88.28349 5.425467 -11.01791 88.35566 5.75 -11.5 88.06699 5.630697 -11.43488 88.13916 5.5 -11.5 88.21132 5.458734 -11.1875 88.28349 5.295231 -11.24348 88.35566 5.630697 -11.56512 88.13916 5.530154 -11.67101 88.21132 5.765077 -11.58551 88.06699 5.25 -11.5 88.35566 5.384495 -11.39147 88.28349 5.67524 -11.6875 88.13916 5.808489 -11.6607 88.06699 5.616978 -11.82139 88.21132 5.875 -11.71651 88.06699 5.956588 -11.7462 88.06699 5.933987 -11.65304 88.01887 5.384495 -11.60853 88.28349 5.295231 -11.75652 88.35566 5.75 -11.93301 88.21132 5.758955 -11.78727 88.13916 5.971059 -11.66413 88.01887 5.425467 -11.98209 88.35566 5.458734 -11.8125 88.28349 6.043412 -11.7462 88.06699 6.009691 -11.66638 88.01887 6 -11.625 87.99482 6.021706 -11.6231 87.99482 5.913176 -11.9924 88.21132 5.871742 -11.85238 88.13916 6.125 -11.71651 88.06699 6.042753 -11.61746 87.99482 5.598258 -11.97878 88.28349 5.625 -12.14952 88.35566 6.0625 -11.60825 87.99482 6 -11.875 88.13916 6.086824 -11.9924 88.21132 6.191511 -11.6607 88.06699 6.080348 -11.59576 87.99482 5.786237 -12.08731 88.28349 5.869764 -12.23861 88.35566 6.095756 -11.58035 87.99482 6.128258 -11.85238 88.13916 6.25 -11.93301 88.21132 6.234923 -11.58551 88.06699 6.108253 -11.5625 87.99482 6 -12.125 88.28349 6.130236 -12.23861 88.35566 6.117462 -11.54275 87.99482 6.241045 -11.78727 88.13916 6.383022 -11.82139 88.21132 6.213763 -12.08731 88.28349 6.375 -12.14952 88.35566 6.32476 -11.6875 88.13916 6.469846 -11.67101 88.21132 6.246202 -11.54341 88.06699 6.123101 -11.52171 87.99482 6 -11.5 87.92265 6.401742 -11.97878 88.28349 6.574533 -11.98209 88.35566 6.541266 -11.8125 88.28349 6.704769 -11.75652 88.35566 6.738606 -11.63024 88.35566 6.991445 -11.63053 88.5 6.861707 -11.65194 88.42783 6.123101 -11.47829 87.99482 6.117462 -11.45725 87.99482 6.06037 -11.48382 87.95873 6.058731 -11.47862 87.95873 6.056644 -11.47359 87.95873 6.108253 -11.4375 87.99482 6.054127 -11.46875 87.95873 6.051197 -11.46415 87.95873 6.095756 -11.41965 87.99482 6.047878 -11.45983 87.95873 6.044194 -11.45581 87.95873 6.080348 -11.40424 87.99482 6.0625 -11.39175 87.99482 6.622622 -11.44553 88.28349 6.246202 -11.45659 88.06699 6.469846 -11.32899 88.21132 5.958333 -11.42783 87.97076 6.880962 -11.17936 88.46392 6.965926 -11.24118 88.5 6.92388 -11.11732 88.5 6.866025 -11 88.5 5.848464 -11.35703 88.04293 5.955806 -11.45581 87.95873 5.867691 -11.42361 88.01086 5.82594 -11.38552 88.04293 5.857179 -11.47051 88.00685 5.875 -11.5 87.99482 5.833333 -11.5 88.01887 5.805556 -11.5 88.03491 5.871427 -11.55253 88.00284 6.707107 -10.79289 88.5 6.608761 -10.70665 88.5 5.82594 -11.61448 88.04293 5.848464 -11.64297 88.04293 6.044194 -11.54419 87.95873 6.047878 -11.54017 87.95873 6.051197 -11.53585 87.95873 6.054127 -11.53125 87.95873 6.056644 -11.52641 87.95873 6.058731 -11.52138 87.95873 6.5 -10.63397 88.5 6.382683 -10.57612 88.5 6.06037 -11.51618 87.95873 6.373573 -11.53268 88.13916 6.866025 -12 88.5 6.92388 -11.88268 88.5 6.880962 -11.82064 88.46392 6.965926 -11.75882 88.5 6.011959 -11.47113 87.94069 6.042753 -11.38254 87.99482 6.009518 -11.42771 87.96475 6.021706 -11.3769 87.99482 6 -11.375 87.99482 6 -11.4375 87.95873 6.258819 -10.53407 88.5 6.130526 -10.50856 88.5 6 -10.5 88.5 6.730709 -11.07813 88.40979 6.793353 -10.89124 88.5 5.901288 -11.48012 87.98079 5.955806 -11.54419 87.95873 5.988041 -11.52887 87.94069 5.92643 -11.60953 87.99883 5.980116 -11.59871 87.98079 6 -11.54167 87.94671 5.869474 -10.50856 88.5 5.741181 -10.53407 88.5 5.617317 -10.57612 88.5 6.707107 -12.20711 88.5 6.793353 -12.10876 88.5 6.730709 -11.92188 88.40979 5.991319 -11.48701 87.93167 5.971129 -11.48804 87.94069 5.9375 -11.5 87.95873 5.954026 -11.50914 87.94971 5.5 -10.63397 88.5 5.391239 -10.70665 88.5 5.292893 -10.79289 88.5 5.206647 -10.89124 88.5 5.133975 -11 88.5 5.07612 -11.11732 88.5 5.034074 -11.24118 88.5 5.008555 -11.36947 88.5 5 -11.5 88.5 5.008555 -11.63053 88.5 5.034074 -11.75882 88.5 5.07612 -11.88268 88.5 5.133975 -12 88.5 5.206647 -12.10876 88.5 5.292893 -12.20711 88.5 5.391239 -12.29335 88.5 5.5 -12.36603 88.5 5.617317 -12.42388 88.5 5.741181 -12.46593 88.5 5.869474 -12.49144 88.5 6 -12.5 88.5 6.130526 -12.49144 88.5 6.258819 -12.46593 88.5 6.382683 -12.42388 88.5 6.5 -12.36603 88.5 6.608761 -12.29335 88.5 6.234923 -11.41449 88.06699 6.191511 -11.3393 88.06699 6.125 -11.28349 88.06699 6.32476 -11.3125 88.13916 6.241045 -11.21273 88.13916 6.009691 -11.33362 88.01887 7.972533 -9.684155 89.89132 8.097431 -9.770261 89.83346 8.000197 -9.658689 89.83346 8.068423 -9.794184 89.89132 5.688213 -14.20074 89.83346 5.55252 -14.1816 89.83346 5.548671 -14.20467 89.76854 7.958866 -9.61478 89.83346 5.558709 -14.14451 89.89132 8.054865 -10.05464 89.99346 8.051058 -10.15998 90 8.103194 -10.12591 89.99346 5.685531 -14.22397 89.76854 7.933394 -9.995179 90 8.103583 -10.02037 89.97414 8.029543 -9.920343 89.97414 8.152179 -9.986191 89.93905 5.499033 -14.08312 89.93905 5.302767 -14.0372 89.93905 5.489547 -14.13204 89.89132 5.31851 -13.97991 89.97414 8.076429 -9.883851 89.93905 7.931775 -9.640853 89.89132 5.894971 -14.24005 89.76854 5.773562 -14.2327 89.76854 5.894667 -14.24798 89.7 7.841311 -9.499803 89.83346 7.975717 -9.598563 89.76854 5.775493 -14.20939 89.83346 7.85715 -9.482597 89.76854 5.334293 -13.92247 89.99346 5.398561 -13.87503 90 5.204486 -13.81725 90 7.984147 -9.863686 89.97414 5.150808 -13.8644 89.99346 5.130675 -13.92046 89.97414 8.029984 -9.825885 89.93905 7.935876 -9.717901 89.93905 5.56691 -14.09537 89.93905 7.982539 -9.956928 89.99346 5.692525 -14.16339 89.89132 7.684211 -9.336126 89.76854 7.829646 -9.446979 89.7 6 -14.24206 89.76854 6.105333 -14.24798 89.7 7.66712 -9.312945 89.7 7.895875 -9.675403 89.93905 5.510345 -14.0248 89.97414 5.895867 -14.21668 89.83346 7.815845 -9.527467 89.89132 7.938194 -9.901583 89.99346 5.778598 -14.17192 89.89132 7.802524 -9.84066 90 7.892164 -9.75814 89.97414 5.576689 -14.03676 89.97414 5.698239 -14.11389 89.93905 6.105029 -14.24005 89.76854 7.669847 -9.354581 89.83346 7.853066 -9.716603 89.97414 6 -14.21868 89.83346 7.782099 -9.564124 89.93905 5.521685 -13.96632 89.99346 5.596743 -13.91659 90 7.848342 -9.798481 89.99346 5.897307 -14.17911 89.89132 5.782713 -14.12227 89.93905 7.499767 -9.204435 89.76854 7.494811 -9.191745 89.7 5.586493 -13.97801 89.99346 7.646752 -9.384253 89.89132 6.226438 -14.2327 89.76854 6.315379 -14.23186 89.7 7.81015 -9.757906 89.99346 7.65934 -9.697476 90 5.705053 -14.05487 89.97414 7.74186 -9.607836 89.97414 6.104133 -14.21668 89.83346 7.486976 -9.224014 89.83346 6 -14.18108 89.89132 7.616149 -9.423571 89.93905 7.701519 -9.651658 89.99346 5.899216 -14.12932 89.93905 6.314469 -14.22397 89.76854 7.309939 -9.091063 89.76854 7.31373 -9.084091 89.7 5.787619 -14.06306 89.97414 7.466411 -9.255491 89.89132 5.711884 -13.9957 89.99346 5.797681 -13.94163 90 7.579657 -9.470457 89.97414 6.224507 -14.20939 89.83346 7.298766 -9.111608 89.83346 7.439159 -9.297203 89.93905 6.102693 -14.17911 89.89132 6 -14.13125 89.93905 7.121693 -8.997856 89.76854 7.124939 -8.990615 89.7 5.901492 -14.06995 89.97414 7.543072 -9.517461 89.99346 7.504821 -9.566606 90 5.792538 -14.0037 89.99346 7.280804 -9.14464 89.89132 6.311787 -14.20074 89.83346 7.406663 -9.346942 89.97414 6.451329 -14.20467 89.76854 6.523576 -14.1997 89.7 7.112126 -9.019196 89.83346 6.221402 -14.17192 89.89132 7.257002 -9.188412 89.93905 6.100784 -14.12932 89.93905 6.926864 -8.919333 89.76854 6.929546 -8.911865 89.7 6.522065 -14.19191 89.76854 7.374085 -9.396806 89.99346 7.340023 -9.448942 90 6 -14.07184 89.97414 7.096745 -9.053506 89.89132 5.903773 -14.01043 89.99346 6 -13.95 90 7.228619 -9.240607 89.97414 6.307475 -14.16339 89.89132 6.44748 -14.1816 89.83346 6.918959 -8.941343 89.83346 7.076363 -9.098972 89.93905 6.217287 -14.12227 89.93905 6.098508 -14.06995 89.97414 6.726596 -8.855955 89.76854 6.728699 -8.848303 89.7 7.200164 -9.292934 89.99346 6.517612 -14.16895 89.83346 7.166071 -9.345289 90 6 -14.01228 89.99346 6.90625 -8.97673 89.89132 6.673137 -14.15816 89.76854 6.728699 -14.1517 89.7 7.052059 -9.153187 89.97414 6.301761 -14.11389 89.93905 6.720399 -8.878505 89.83346 6.889408 -9.023622 89.93905 6.441291 -14.14451 89.89132 6.212381 -14.06306 89.97414 6.522065 -8.808092 89.76854 6.523576 -8.800302 89.7 6.096227 -14.01043 89.99346 6.202319 -13.94163 90 7.027694 -9.207539 89.99346 6.984154 -9.256355 90 6.710436 -8.914761 89.89132 6.510453 -14.13204 89.89132 6.667396 -14.13549 89.83346 6.451329 -8.795334 89.76854 6.315379 -8.768144 89.7 6.869325 -9.079538 89.97414 6.294947 -14.05487 89.97414 6.43309 -14.09537 89.93905 6.517612 -8.831051 89.83346 6.207462 -14.0037 89.99346 6.697233 -8.962805 89.93905 6.890347 -14.09349 89.76854 6.929546 -14.08814 89.7 6.44748 -8.818401 89.83346 6.500967 -14.08312 89.93905 6.314469 -8.776027 89.76854 6.849192 -9.135596 89.99346 6.795514 -9.182748 90 6.658166 -14.09904 89.89132 6.288116 -13.9957 89.99346 6.403257 -13.91659 90 6.510453 -8.867963 89.89132 6.423311 -14.03676 89.97414 6.226438 -8.767301 89.76854 6.105333 -8.752018 89.7 6.882753 -14.07137 89.83346 6.68149 -9.020094 89.97414 6.489655 -14.0248 89.97414 6.441291 -8.855488 89.89132 6.645935 -14.05074 89.93905 6.311787 -8.799259 89.83346 6.413507 -13.97801 89.99346 6.500967 -8.916877 89.93905 7.101475 -14.01111 89.76854 7.124939 -14.00938 89.7 6.105029 -8.759948 89.76854 6.224507 -8.790607 89.83346 6.870545 -14.03581 89.89132 6.478315 -13.96632 89.99346 6.601439 -13.87503 90 6.665707 -9.077529 89.99346 6.601439 -9.124969 90 6.631349 -13.99314 89.97414 6.43309 -8.904633 89.93905 6.307475 -8.836611 89.89132 7.092081 -13.98969 89.83346 6 -8.757935 89.76854 5.894667 -8.752018 89.7 6.854367 -13.98868 89.93905 6.489655 -8.975203 89.97414 6.616727 -13.9354 89.99346 6.104133 -8.783317 89.83346 7.305079 -13.91157 89.76854 7.31373 -13.91591 89.7 7.076977 -13.95526 89.89132 6.221402 -8.828079 89.89132 6.423311 -8.963237 89.97414 6.835075 -13.93249 89.97414 6.301761 -8.886107 89.93905 5.894971 -8.759948 89.76854 7.293948 -13.89101 89.83346 7.056962 -13.90963 89.93905 6 -8.781322 89.83346 6.478315 -9.033677 89.99346 7.490497 -13.80159 89.76854 6.403257 -9.083415 90 6.102693 -8.820889 89.89132 7.494811 -13.80825 89.7 6.815735 -13.87615 89.99346 6.795514 -13.81725 90 6.217287 -8.877734 89.93905 7.276052 -13.85794 89.89132 6.413507 -9.021988 89.99346 5.773562 -8.767301 89.76854 5.684621 -8.768144 89.7 7.033096 -13.85522 89.97414 7.477785 -13.78196 89.83346 6.294947 -8.945129 89.97414 5.895867 -8.783317 89.83346 7.252338 -13.81412 89.93905 6 -8.818922 89.89132 6.100784 -8.870677 89.93905 7.662309 -13.68074 89.76854 7.66712 -13.68706 89.7 7.00917 -13.80068 89.99346 6.984154 -13.74364 90 5.685531 -8.776027 89.76854 7.457347 -13.7504 89.89132 6.212381 -8.936944 89.97414 7.224061 -13.76187 89.97414 6.288116 -9.004299 89.99346 6.202319 -9.058368 90 7.648132 -13.66215 89.83346 5.775493 -8.790607 89.83346 7.430264 -13.70858 89.93905 5.897307 -8.820889 89.89132 7.824366 -13.5471 89.76854 6 -8.868747 89.93905 7.829646 -13.55302 89.7 7.195711 -13.70948 89.99346 7.166071 -13.65471 90 6.098508 -8.930047 89.97414 6.207462 -8.996304 89.99346 7.625338 -13.63224 89.89132 7.397969 -13.65871 89.97414 5.688213 -8.799259 89.83346 5.548671 -8.795334 89.76854 5.476424 -8.800302 89.7 7.808807 -13.52964 89.83346 5.778598 -8.828079 89.89132 7.595133 -13.59262 89.93905 5.899216 -8.870677 89.93905 7.975717 -13.40144 89.76854 7.981434 -13.40694 89.7 7.365592 -13.60872 89.99346 7.340023 -13.55106 90 5.477935 -8.808092 89.76854 6 -8.92816 89.97414 6.096227 -8.989567 89.99346 6 -9.05 90 8.017403 -13.35715 89.76854 8.121595 -13.24967 89.7 5.692525 -8.836611 89.89132 7.78379 -13.50157 89.89132 5.55252 -8.818401 89.83346 7.559115 -13.54537 89.97414 5.782713 -8.877734 89.93905 7.958866 -13.38522 89.83346 5.901492 -8.930047 89.97414 8.000197 -13.34131 89.83346 5.482388 -8.831051 89.83346 6 -8.987723 89.99346 7.750641 -13.46437 89.93905 5.326863 -8.841842 89.76854 5.271301 -8.848303 89.7 5.698239 -8.886107 89.93905 8.115473 -13.24462 89.76854 7.523006 -13.498 89.99346 7.504821 -13.43339 90 5.558709 -8.855488 89.89132 7.931775 -13.35915 89.89132 5.787619 -8.936944 89.97414 5.903773 -8.989567 89.99346 8.163874 -13.18421 89.76854 8.249306 -13.08213 89.7 5.797681 -9.058368 90 5.489547 -8.867963 89.89132 7.972533 -13.31584 89.89132 7.711111 -13.42002 89.97414 5.332604 -8.864513 89.83346 5.705053 -8.945129 89.97414 8.097431 -13.22974 89.83346 5.56691 -8.904633 89.93905 7.895875 -13.3246 89.93905 5.792538 -8.996304 89.99346 5.109653 -8.906508 89.76854 5.070454 -8.911865 89.7 8.242815 -13.07756 89.76854 8.145419 -13.16985 89.83346 5.499033 -8.916877 89.93905 7.671482 -13.37555 89.99346 7.65934 -13.30252 90 5.341834 -8.900962 89.89132 7.935876 -13.2821 89.93905 5.711884 -9.004299 89.99346 5.596743 -9.083415 90 8.068423 -13.20582 89.89132 5.576689 -8.963237 89.97414 5.117247 -8.928627 89.83346 8.295565 -12.99977 89.76854 8.363816 -12.9053 89.7 7.853066 -13.2834 89.97414 8.223687 -13.06411 89.83346 5.510345 -8.975203 89.97414 5.354065 -8.949262 89.93905 8.115747 -13.14675 89.89132 5.586493 -9.021988 89.99346 7.892164 -13.24186 89.97414 4.898525 -8.98889 89.76854 4.875061 -8.990615 89.7 5.129455 -8.96419 89.89132 8.029984 -13.17412 89.93905 8.356995 -12.90125 89.76854 5.521685 -9.033677 89.99346 5.398561 -9.124969 90 8.275986 -12.98698 89.83346 5.368651 -9.006858 89.97414 7.81015 -13.24209 89.99346 7.802524 -13.15934 90 4.907919 -9.010307 89.83346 8.192933 -13.04247 89.89132 8.076429 -13.11615 89.93905 5.145633 -9.011315 89.93905 7.848342 -13.20152 89.99346 5.383273 -9.064598 89.99346 8.411574 -12.80508 89.76854 4.694921 -9.088426 89.76854 4.68627 -9.084091 89.7 8.464455 -12.72023 89.7 7.984147 -13.13631 89.97414 4.923023 -9.04474 89.89132 8.336893 -12.8893 89.83346 5.164925 -9.067509 89.97414 8.244509 -12.96641 89.89132 4.706052 -9.108994 89.83346 8.152179 -13.01381 89.93905 4.943038 -9.090368 89.93905 8.029543 -13.07966 89.97414 8.457344 -12.71671 89.76854 4.509503 -9.198406 89.76854 4.505189 -9.191745 89.7 8.391006 -12.79395 89.83346 5.184265 -9.123845 89.99346 3.257935 -11.5 89.76854 3.258069 -11.28949 89.7 3.25 -11.5 89.7 7.938194 -13.09842 89.99346 7.933394 -13.00482 90 5.204486 -9.182748 90 4.723948 -9.142062 89.89132 8.304573 -12.87008 89.89132 4.966904 -9.144778 89.97414 8.202797 -12.93916 89.93905 7.982539 -13.04307 89.99346 4.522215 -9.218035 89.83346 8.103583 -12.97963 89.97414 4.747662 -9.185882 89.93905 8.51111 -12.60147 89.76854 8.550632 -12.528 89.7 4.337691 -9.319256 89.76854 4.33288 -9.312945 89.7 4.170354 -9.446979 89.7 8.436386 -12.70633 89.83346 4.99083 -9.199324 89.99346 8.357938 -12.77605 89.89132 5.015846 -9.256355 90 3.265981 -11.7099 89.76854 4.542653 -9.249596 89.89132 3.258069 -11.71051 89.7 3.282229 -11.91979 89.7 8.261745 -12.84462 89.93905 4.775939 -9.238134 89.97414 3.289299 -11.70811 89.83346 3.281322 -11.5 89.83346 8.543272 -12.52503 89.76854 4.351868 -9.337855 89.83346 8.153058 -12.90666 89.97414 3.290071 -11.91857 89.76854 8.054865 -12.94536 89.99346 8.051058 -12.84002 90 4.569736 -9.291417 89.93905 3.326789 -11.70523 89.89132 3.318922 -11.5 89.89132 4.175634 -9.452903 89.76854 8.489693 -12.59208 89.83346 3.313183 -11.915 89.83346 4.804289 -9.290519 89.99346 8.40269 -12.68965 89.89132 4.833929 -9.345289 90 4.374662 -9.367758 89.89132 3.376467 -11.70142 89.93905 3.368746 -11.5 89.93905 8.314118 -12.75234 89.93905 3.330064 -12.12479 89.76854 4.602031 -9.341286 89.97414 3.322338 -12.1266 89.7 3.37816 -12.32973 89.7 8.210675 -12.81426 89.97414 8.103194 -12.87409 89.99346 3.350343 -11.90926 89.89132 4.191193 -9.470362 89.83346 8.521581 -12.51629 89.83346 3.435706 -11.69687 89.97414 3.42816 -11.5 89.97414 4.404867 -9.407383 89.93905 3.487724 -11.5 89.99347 8.593492 -12.39035 89.76854 3.352835 -12.11946 89.83346 8.62184 -12.32973 89.7 4.024283 -9.598563 89.76854 4.018566 -9.593061 89.7 8.45526 -12.57698 89.89132 4.634408 -9.391282 89.99346 4.659977 -9.448942 90 3.399584 -11.90166 89.93905 3.982597 -9.64285 89.76854 3.878405 -9.750333 89.7 3.385725 -12.32734 89.76854 8.358039 -12.66754 89.93905 8.614275 -12.32734 89.76854 3.495095 -11.69231 89.99346 3.55 -11.5 90 3.558368 -11.70232 90 4.21621 -9.498432 89.89132 8.261866 -12.72406 89.97414 3.389446 -12.11089 89.89132 4.440885 -9.454634 89.97414 8.159477 -12.78382 89.99346 3.406508 -12.39035 89.76854 8.154711 -12.66607 90 4.041134 -9.61478 89.83346 3.449368 -12.528 89.7 8.486707 -12.50223 89.89132 3.458301 -11.89259 89.97414 8.571373 -12.38275 89.83346 3.408022 -12.32028 89.83346 3.999803 -9.658689 89.83346 3.437961 -12.09954 89.93905 8.409632 -12.55696 89.93905 4.249359 -9.535629 89.93905 3.884527 -9.755382 89.76854 8.304794 -12.64118 89.97414 3.428627 -12.38275 89.83346 4.476994 -9.502004 89.99346 4.495179 -9.566606 90 3.456728 -12.52503 89.76854 8.591978 -12.32028 89.83346 8.209481 -12.69571 89.99346 4.068225 -9.640853 89.89132 3.517166 -11.8835 89.99346 3.583415 -11.90326 90 3.836126 -9.815789 89.76854 8.658158 -12.17314 89.76854 8.677662 -12.1266 89.7 3.750694 -9.917874 89.7 3.44387 -12.30894 89.89132 8.440494 -12.48361 89.93905 4.027467 -9.684155 89.89132 3.48889 -12.60147 89.76854 3.535545 -12.72023 89.7 3.495811 -12.086 89.97414 4.288889 -9.579985 89.97414 8.53581 -12.37054 89.89132 8.251416 -12.61475 89.99346 8.243645 -12.48415 90 3.902569 -9.770261 89.83346 3.46419 -12.37054 89.89132 8.355222 -12.5331 89.97414 4.104125 -9.675403 89.93905 3.478419 -12.51629 89.83346 8.55613 -12.30894 89.89132 3.491372 -12.2939 89.93905 8.635487 -12.1674 89.83346 3.757185 -9.922439 89.76854 3.854581 -9.830153 89.83346 3.542656 -12.71671 89.76854 8.385388 -12.4614 89.97414 3.510307 -12.59208 89.83346 4.328518 -9.624452 89.99346 4.34066 -9.697476 90 8.488685 -12.35437 89.93905 4.064124 -9.717901 89.93905 3.553808 -12.07243 89.99346 3.624969 -12.10144 90 8.300676 -12.50917 89.99346 3.931577 -9.794184 89.89132 3.511315 -12.35437 89.93905 8.704666 -11.95133 89.76854 8.717771 -11.91979 89.7 3.704435 -10.00023 89.76854 3.513293 -12.50223 89.89132 3.636184 -10.0947 89.7 4.146934 -9.716603 89.97414 8.508628 -12.2939 89.93905 3.588426 -12.80508 89.76854 3.636184 -12.9053 89.7 8.599038 -12.15817 89.89132 3.776313 -9.935894 89.83346 3.548017 -12.27598 89.97414 8.330143 -12.43913 89.99346 8.317252 -12.29551 90 3.884253 -9.853248 89.89132 3.563614 -12.70633 89.83346 8.432491 -12.33508 89.97414 4.107836 -9.75814 89.97414 3.54474 -12.57698 89.89132 3.970016 -9.825885 89.93905 8.681599 -11.94748 89.83346 3.567509 -12.33508 89.97414 8.451983 -12.27598 89.97414 3.559506 -12.48361 89.93905 3.643005 -10.09875 89.76854 3.724014 -10.01302 89.83346 3.643005 -12.90125 89.76854 8.550738 -12.14593 89.93905 8.376155 -12.31573 89.99346 4.18985 -9.757906 89.99346 3.608994 -12.79395 89.83346 4.197476 -9.84066 90 3.807067 -9.957526 89.89132 3.604805 -12.25801 89.99346 8.732699 -11.72644 89.76854 8.741931 -11.71051 89.7 3.923571 -9.883851 89.93905 3.682748 -12.29551 90 3.59731 -12.68965 89.89132 4.151658 -9.798481 89.99346 8.644512 -11.94129 89.89132 3.590368 -12.55696 89.93905 8.395195 -12.25801 89.99346 3.588426 -10.19492 89.76854 3.535545 -10.27977 89.7 8.375031 -12.10144 90 3.623845 -12.31573 89.99346 8.493142 -12.13135 89.97414 4.015853 -9.863686 89.97414 3.704435 -12.99977 89.76854 3.750694 -13.08213 89.7 8.709393 -11.72451 89.83346 3.614612 -12.4614 89.97414 3.663107 -10.1107 89.83346 8.595367 -11.93309 89.93905 3.663107 -12.8893 89.83346 3.755491 -10.03359 89.89132 3.847821 -9.986191 89.93905 8.435402 -12.11673 89.99346 3.642062 -12.77605 89.89132 3.970457 -9.920343 89.97414 8.742065 -11.5 89.76854 3.641961 -12.66754 89.93905 8.75 -11.5 89.7 3.644778 -12.5331 89.97414 3.542656 -10.28329 89.76854 8.671921 -11.7214 89.89132 3.757185 -13.07756 89.76854 3.608994 -10.20605 89.83346 3.669857 -12.43913 89.99346 8.536763 -11.92331 89.97414 4.061806 -9.901583 89.99346 4.066606 -9.995179 90 3.756355 -12.48415 90 3.724014 -12.98698 89.83346 8.718678 -11.5 89.83346 3.695427 -10.12992 89.89132 3.797203 -10.06084 89.93905 3.695427 -12.87008 89.89132 8.622266 -11.71729 89.93905 4.017461 -9.956928 89.99346 3.685882 -12.75234 89.93905 3.896417 -10.02037 89.97414 8.734019 -11.2901 89.76854 8.741931 -11.28949 89.7 3.699324 -12.50917 89.99346 3.695206 -12.64118 89.97414 8.478012 -11.91351 89.99346 8.416585 -11.90326 90 3.48889 -10.39853 89.76854 3.449368 -10.472 89.7 3.563614 -10.29367 89.83346 8.681078 -11.5 89.89132 3.836126 -13.18421 89.76854 3.878405 -13.24967 89.7 3.642062 -10.22395 89.89132 8.563056 -11.71238 89.97414 3.776313 -13.06411 89.83346 3.755491 -12.96641 89.89132 8.710701 -11.29189 89.83346 3.738255 -10.15538 89.93905 3.738255 -12.84462 89.93905 3.456728 -10.47497 89.76854 8.631253 -11.5 89.93905 3.846942 -10.09334 89.97414 3.884527 -13.24462 89.76854 8.709929 -11.08143 89.76854 8.717771 -11.08021 89.7 8.677662 -10.8734 89.7 3.945135 -10.05464 89.99346 3.948942 -10.15998 90 3.738134 -12.72406 89.97414 3.510307 -10.40792 89.83346 8.503696 -11.70746 89.99346 8.441632 -11.70232 90 3.748584 -12.61475 89.99346 3.845289 -12.66607 90 8.673211 -11.29477 89.89132 3.854581 -13.16985 89.83346 3.59731 -10.31035 89.89132 3.685882 -10.24766 89.93905 8.57184 -11.5 89.97414 3.789325 -10.18574 89.97414 3.807067 -13.04247 89.89132 8.686817 -11.085 89.83346 3.896806 -10.12591 89.99346 3.797203 -12.93916 89.93905 8.623533 -11.29858 89.93905 3.478419 -10.48371 89.83346 3.789325 -12.81426 89.97414 3.902569 -13.22974 89.83346 3.406508 -10.60965 89.76854 3.37816 -10.67027 89.7 8.669936 -10.87521 89.76854 8.512277 -11.5 89.99346 8.45 -11.5 90 3.54474 -10.42302 89.89132 3.790519 -12.69571 89.99346 3.641961 -10.33246 89.93905 8.649657 -11.09074 89.89132 3.982597 -13.35715 89.76854 4.018566 -13.40694 89.7 3.884253 -13.14675 89.89132 8.564294 -11.30313 89.97414 3.385725 -10.67266 89.76854 3.847821 -13.01381 89.93905 3.738134 -10.27594 89.97414 8.647165 -10.88054 89.83346 3.840523 -10.21618 89.99346 8.600416 -11.09834 89.93905 3.845289 -10.33393 90 4.024283 -13.40144 89.76854 3.513293 -10.49777 89.89132 3.846942 -12.90666 89.97414 8.614275 -10.67266 89.76854 8.62184 -10.67027 89.7 3.840523 -12.78382 89.99346 8.504905 -11.30769 89.99346 8.441632 -11.29768 90 3.428627 -10.61725 89.83346 3.948942 -12.84002 90 8.610554 -10.88911 89.89132 3.931577 -13.20582 89.89132 3.590368 -10.44304 89.93905 3.999803 -13.34131 89.83346 8.593492 -10.60965 89.76854 3.695206 -10.35882 89.97414 8.550632 -10.472 89.7 8.541699 -11.10741 89.97414 3.923571 -13.11615 89.93905 3.408022 -10.67972 89.83346 8.591978 -10.67972 89.83346 3.896417 -12.97963 89.97414 3.790519 -10.30429 89.99346 4.041134 -13.38522 89.83346 8.562039 -10.90046 89.93905 3.341842 -10.82686 89.76854 3.322338 -10.8734 89.7 8.571373 -10.61725 89.83346 3.896806 -12.87409 89.99346 3.559506 -10.51639 89.93905 4.14285 -13.5174 89.76854 3.46419 -10.62946 89.89132 4.170354 -13.55302 89.7 8.543272 -10.47497 89.76854 3.970016 -13.17412 89.93905 8.482834 -11.1165 89.99346 8.416585 -11.09674 90 3.748584 -10.38525 89.99346 3.756355 -10.51585 90 8.55613 -10.69106 89.89132 4.027467 -13.31584 89.89132 3.644778 -10.4669 89.97414 8.51111 -10.39853 89.76854 3.945135 -12.94536 89.99346 8.464455 -10.27977 89.7 4.066606 -13.00482 90 3.970457 -13.07966 89.97414 8.504189 -10.914 89.97414 3.44387 -10.69106 89.89132 4.068225 -13.35915 89.89132 3.364513 -10.8326 89.83346 8.53581 -10.62946 89.89132 8.521581 -10.48371 89.83346 3.614612 -10.5386 89.97414 4.158689 -13.5002 89.83346 4.015853 -13.13631 89.97414 3.511315 -10.64563 89.93905 8.508628 -10.7061 89.93905 3.699324 -10.49083 89.99346 4.064124 -13.2821 89.93905 8.457344 -10.28329 89.76854 3.295334 -11.04867 89.76854 3.282229 -11.08021 89.7 4.017461 -13.04307 89.99346 4.315789 -13.66387 89.76854 8.489693 -10.40792 89.83346 3.491372 -10.7061 89.93905 8.446192 -10.92757 89.99346 8.375031 -10.89856 90 4.33288 -13.68706 89.7 8.488685 -10.64563 89.93905 3.400962 -10.84183 89.89132 4.104125 -13.3246 89.93905 8.486707 -10.49777 89.89132 3.669857 -10.56087 89.99346 3.682748 -10.70449 90 4.184155 -13.47253 89.89132 3.567509 -10.66492 89.97414 4.061806 -13.09842 89.99346 8.411574 -10.19492 89.76854 8.363816 -10.0947 89.7 4.197476 -13.15934 90 8.451983 -10.72402 89.97414 3.318401 -11.05252 89.83346 4.107836 -13.24186 89.97414 3.548017 -10.72402 89.97414 4.330153 -13.64542 89.83346 8.436386 -10.29367 89.83346 4.146934 -13.2834 89.97414 3.449262 -10.85407 89.93905 8.45526 -10.42302 89.89132 8.432491 -10.66492 89.97414 4.217901 -13.43588 89.93905 3.623845 -10.68427 89.99346 8.440494 -10.51639 89.93905 3.267301 -11.27356 89.76854 4.151658 -13.20152 89.99346 3.355488 -11.05871 89.89132 4.500233 -13.79556 89.76854 8.356995 -10.09875 89.76854 4.505189 -13.80825 89.7 3.604805 -10.74199 89.99346 4.353248 -13.61575 89.89132 8.391006 -10.20605 89.83346 8.395195 -10.74199 89.99346 8.317252 -10.70449 90 3.624969 -10.89856 90 3.506858 -10.86865 89.97414 4.18985 -13.24209 89.99346 4.34066 -13.30252 90 8.40269 -10.31035 89.89132 4.25814 -13.39216 89.97414 3.290607 -11.27549 89.83346 4.513024 -13.77599 89.83346 8.409632 -10.44304 89.93905 3.404633 -11.06691 89.93905 8.376155 -10.68427 89.99346 4.383851 -13.57643 89.93905 8.295565 -10.00023 89.76854 8.249306 -9.917874 89.7 3.564598 -10.88327 89.99346 4.298481 -13.34834 89.99346 3.328079 -11.2786 89.89132 8.385388 -10.5386 89.97414 4.690061 -13.90894 89.76854 3.463237 -11.07669 89.97414 4.68627 -13.91591 89.7 8.336893 -10.1107 89.83346 8.357938 -10.22395 89.89132 4.533589 -13.74451 89.89132 3.377734 -11.28271 89.93905 4.420343 -13.52954 89.97414 8.358039 -10.33246 89.93905 3.521988 -11.08649 89.99346 3.583415 -11.09674 90 4.701234 -13.88839 89.83346 8.355222 -10.4669 89.97414 3.436944 -11.28762 89.97414 4.560841 -13.7028 89.93905 3.496304 -11.29254 89.99346 8.242815 -9.922439 89.76854 3.558368 -11.29768 90 8.330143 -10.56087 89.99346 4.878307 -14.00214 89.76854 8.243645 -10.51585 90 8.275986 -10.01302 89.83346 4.875061 -14.00938 89.7 5.070454 -14.08814 89.7 4.456928 -13.48254 89.99346 4.495179 -13.43339 90 8.304573 -10.12992 89.89132 4.719196 -13.85536 89.89132 4.593337 -13.65306 89.97414 8.314118 -10.24766 89.93905 8.300676 -10.49083 89.99346 8.304794 -10.35882 89.97414 4.887874 -13.9808 89.83346 8.163874 -9.815789 89.76854 8.121595 -9.750333 89.7 4.742998 -13.81159 89.93905 8.223687 -9.935894 89.83346 5.073136 -14.08067 89.76854 8.244509 -10.03359 89.89132 4.625915 -13.60319 89.99346 4.659977 -13.55106 90 8.261745 -10.15538 89.93905 4.903255 -13.94649 89.89132 4.771381 -13.75939 89.97414 8.115473 -9.755382 89.76854 8.261866 -10.27594 89.97414 8.251416 -10.38525 89.99346 5.081041 -14.05866 89.83346 8.154711 -10.33393 90 4.923637 -13.90103 89.93905 8.145419 -9.830153 89.83346 5.273404 -14.14405 89.76854 5.271301 -14.1517 89.7 5.476424 -14.1997 89.7 8.192933 -9.957526 89.89132 4.799836 -13.70707 89.99346 4.833929 -13.65471 90 8.202797 -10.06084 89.93905 5.09375 -14.02327 89.89132 8.210675 -10.18574 89.97414 4.947941 -13.84681 89.97414 5.279601 -14.1215 89.83346 8.209481 -10.30429 89.99346 5.110592 -13.97638 89.93905 8.017403 -9.64285 89.76854 7.981434 -9.593061 89.7 5.477935 -14.19191 89.76854 8.115747 -9.853248 89.89132 4.972306 -13.79246 89.99346 5.015846 -13.74364 90 5.289564 -14.08524 89.89132 8.153058 -10.09334 89.97414 5.684621 -14.23186 89.7 8.159477 -10.21618 89.99346 5.482388 -14.16895 89.83346 6.780866 -10.1475 87.99239 6.687777 -10.09787 87.99239 6.790245 -10.13125 87.99808 5.613689 -12.99202 87.9809 5.679562 -13.00754 87.9809 5.608548 -13.01188 87.99239 6.696039 -10.08103 87.99808 6.704631 -10.06351 88 6.846342 -10.14217 88 5.675298 -13.0276 87.99239 5.523736 -12.96579 87.9809 7.116771 -10.49446 87.92334 7.005545 -10.38323 87.92334 7.122817 -10.48901 87.9454 5.385462 -12.88028 87.9454 5.475257 -12.91685 87.9454 5.38015 -12.89221 87.96494 5.470721 -12.9291 87.96494 7.010989 -10.37718 87.9454 5.757716 -13.08155 88 5.598956 -13.04892 88 5.671397 -13.04595 87.99808 5.76067 -13.06227 87.99808 6.8261 -10.17465 87.99239 6.836023 -10.15873 87.99808 5.464726 -12.94528 87.9809 6.905907 -10.25313 87.9809 6.917963 -10.23653 87.99239 7.213525 -10.61832 87.9 7.114717 -10.4963 87.9 7.215761 -10.6167 87.92334 5.248618 -12.80143 87.92334 5.334609 -12.85649 87.9454 5.24455 -12.80848 87.9454 7.019728 -10.36748 87.96494 7.031278 -10.35465 87.9809 5.328857 -12.86822 87.96494 5.118322 -12.71353 87.9 5.205092 -12.77531 87.92334 5.116698 -12.71576 87.92334 7.132523 -10.48027 87.96494 6.928989 -10.22136 87.99808 5.517398 -12.9853 87.99239 6.97937 -10.23476 88 5.603846 -13.03004 87.99808 7.222343 -10.61192 87.9454 5.200789 -12.78222 87.9454 7.045002 -10.33941 87.99239 7.580489 -11.5 87.99808 7.6 -11.5 88 7.591791 -11.66187 88 5.373129 -12.90798 87.9809 7.299038 -10.75 87.9 7.301431 -10.74862 87.92334 7.370318 -10.8899 87.9 5.457602 -12.96452 87.99239 7.145351 -10.46872 87.9809 5.23802 -12.81979 87.96494 7.232909 -10.60424 87.96494 5.321255 -12.88372 87.9809 5.444312 -13.0004 88 5.511601 -13.00314 87.99808 7.057555 -10.32547 87.99808 7.102347 -10.34033 88 7.308477 -10.74455 87.9454 5.111916 -12.72234 87.9454 7.160593 -10.455 87.99239 5.19388 -12.7933 87.96494 4.996304 -12.61472 87.9 4.994455 -12.61677 87.92334 4.885283 -12.5037 87.9 7.372842 -10.88877 87.92334 7.246874 -10.59409 87.9809 5.364787 -12.92671 87.99239 5.451087 -12.98211 87.99808 7.319788 -10.73802 87.96494 5.229389 -12.83474 87.9809 7.174534 -10.44245 87.99808 5.312223 -12.90213 87.99239 7.214013 -10.4578 88 7.380275 -10.88546 87.9454 5.104239 -12.73291 87.96494 7.263467 -10.58204 87.99239 5.184749 -12.80795 87.9809 5.295369 -12.93649 88 5.357156 -12.94385 87.99808 7.429213 -11.03562 87.92334 7.426585 -11.03647 87.9 4.989011 -12.62282 87.9454 7.334737 -10.72939 87.9809 5.303961 -12.91897 87.99808 7.392206 -10.88015 87.96494 5.219134 -12.8525 87.99239 4.883229 -12.50554 87.92334 7.278644 -10.57101 87.99808 7.313222 -10.58597 88 7.436951 -11.03311 87.9454 5.094093 -12.74687 87.9809 5.1739 -12.82535 87.99239 7.352499 -10.71913 87.99239 4.980272 -12.63252 87.96494 7.467221 -11.18813 87.9 7.469924 -11.18756 87.92334 5.153658 -12.85783 88 5.209755 -12.86875 87.99808 7.407976 -10.87313 87.9809 4.877183 -12.51099 87.9454 5.163977 -12.84127 87.99808 7.449372 -11.02907 87.96494 5.082037 -12.76347 87.99239 7.368745 -10.70975 87.99808 7.398955 -10.72352 88 4.786475 -12.38168 87.9 4.784239 -12.3833 87.92334 7.477883 -11.18587 87.9454 4.968722 -12.64535 87.9809 7.426713 -10.86479 87.99239 7.494531 -11.34292 87.92334 7.491783 -11.34321 87.9 4.867477 -12.51973 87.96494 7.5 -11.5 87.9 7.502761 -11.5 87.92335 5.02063 -12.76524 88 5.071011 -12.77864 87.99808 7.465789 -11.02374 87.9809 4.777657 -12.38808 87.9454 4.700962 -12.25 87.9 4.698569 -12.25138 87.92334 7.490657 -11.18315 87.96494 4.629682 -12.1101 87.9 7.470332 -10.86903 88 7.44385 -10.85716 87.99808 7.502622 -11.34207 87.9454 4.954998 -12.66059 87.99239 7.510898 -11.5 87.9454 7.485295 -11.0174 87.99239 4.854649 -12.53128 87.9809 7.507542 -11.17956 87.9809 4.767091 -12.39576 87.96494 7.515611 -11.3407 87.96494 4.897653 -12.65967 88 4.942445 -12.67453 87.99808 7.523961 -11.5 87.96494 7.541222 -11.5 87.9809 7.503136 -11.0116 87.99808 7.526623 -11.02102 88 4.691523 -12.25545 87.9454 7.527604 -11.1753 87.99239 4.627158 -12.11123 87.92334 7.532779 -11.3389 87.9809 4.839407 -12.545 87.99239 7.545953 -11.1714 87.99808 7.567248 -11.17792 88 4.753126 -12.40591 87.9809 7.553176 -11.33675 87.99239 7.56173 -11.5 87.99239 7.591791 -11.33813 88 7.571833 -11.33479 87.99808 4.680212 -12.26198 87.96494 4.825466 -12.55755 87.99808 4.785987 -12.5422 88 4.619725 -12.11454 87.9454 4.573415 -11.96353 87.9 4.570787 -11.96438 87.92334 4.736533 -12.41796 87.99239 4.665263 -12.27061 87.9809 4.607794 -12.11985 87.96494 4.686778 -12.41403 88 4.721356 -12.42899 87.99808 4.563049 -11.96689 87.9454 4.647501 -12.28087 87.99239 4.532779 -11.81187 87.9 4.530076 -11.81244 87.92334 4.592024 -12.12687 87.9809 4.550628 -11.97093 87.96494 4.601045 -12.27648 88 4.631255 -12.29025 87.99808 4.522117 -11.81413 87.9454 4.573287 -12.13521 87.99239 4.508217 -11.65679 87.9 4.505469 -11.65708 87.92334 4.534211 -11.97626 87.9809 4.509343 -11.81685 87.96494 4.529668 -12.13097 88 4.55615 -12.14284 87.99808 4.497378 -11.65793 87.9454 4.514705 -11.9826 87.99239 4.5 -11.5 87.9 4.497237 -11.5 87.92334 4.492458 -11.82044 87.9809 4.484389 -11.6593 87.96494 4.473377 -11.97898 88 4.496864 -11.9884 87.99808 4.489101 -11.5 87.9454 4.508217 -11.34321 87.9 4.504947 -11.34797 87.92334 4.472396 -11.8247 87.99239 4.467221 -11.6611 87.9809 4.476041 -11.5 87.96494 4.432752 -11.82208 88 4.454047 -11.8286 87.99808 4.496853 -11.34714 87.9454 4.532779 -11.18813 87.9 4.527999 -11.1975 87.92334 4.446824 -11.66325 87.99239 4.458779 -11.5 87.9809 4.48386 -11.34582 87.96494 4.428167 -11.66521 87.99808 4.408209 -11.66187 88 4.520029 -11.19586 87.9454 4.573415 -11.03647 87.9 4.566155 -11.05013 87.92334 4.438268 -11.5 87.99239 4.466686 -11.34408 87.9809 4.507236 -11.19323 87.96494 4.419509 -11.5 87.99808 4.4 -11.5 88 4.558392 -11.04769 87.9454 4.619024 -10.90738 87.92334 4.629682 -10.8899 87.9 4.446281 -11.342 87.99239 4.490327 -11.18975 87.9809 4.545931 -11.04378 87.96494 4.427618 -11.3401 87.99808 4.408209 -11.33813 88 4.611547 -10.90417 87.9454 4.686064 -10.77071 87.92334 4.700962 -10.75 87.9 4.470237 -11.18563 87.99239 4.52946 -11.03862 87.9809 4.599546 -10.89902 87.96494 4.451862 -11.18185 87.99808 4.432752 -11.17792 88 4.67895 -10.76676 87.9454 4.766587 -10.64152 87.92334 4.786475 -10.61832 87.9 4.509891 -11.03248 87.99239 4.583682 -10.89221 87.9809 4.667531 -10.76042 87.96494 4.491992 -11.02686 87.99808 4.473377 -11.02102 88 4.759909 -10.63687 87.9454 4.859766 -10.52114 87.92334 4.885283 -10.4963 87.9 4.564834 -10.88412 87.99239 7.491783 -11.65679 87.9 7.495053 -11.65203 87.92334 4.652438 -10.75204 87.9809 7.503147 -11.65286 87.9454 4.74919 -10.62941 87.96494 7.467221 -11.81187 87.9 7.472001 -11.8025 87.92334 4.547595 -10.87672 87.99808 4.529668 -10.86903 88 7.51614 -11.65418 87.96494 4.853593 -10.51584 87.9454 7.479971 -11.80414 87.9454 4.964646 -10.41081 87.92334 4.996304 -10.38528 87.9 7.426585 -11.96353 87.9 7.433845 -11.94987 87.92334 4.634505 -10.74209 87.99239 4.735022 -10.61955 87.9809 7.533314 -11.65592 87.9809 4.843683 -10.50733 87.96494 7.492764 -11.80677 87.96494 4.618103 -10.73298 87.99808 7.441608 -11.95231 87.9454 4.601045 -10.72352 88 4.95904 -10.40491 87.9454 7.370318 -12.1101 87.9 7.380976 -12.09262 87.92334 5.08015 -10.31165 87.92334 5.118322 -10.28647 87.9 7.553719 -11.658 87.99239 4.718188 -10.60783 87.99239 7.509673 -11.81025 87.9809 4.830586 -10.49609 87.9809 7.454069 -11.95622 87.96494 4.950042 -10.39545 87.96494 7.572382 -11.6599 87.99808 4.702791 -10.59712 87.99808 7.388453 -12.09583 87.9454 4.686778 -10.58597 88 5.075169 -10.30522 87.9454 7.299038 -12.25 87.9 7.313936 -12.22929 87.92334 5.205092 -10.22469 87.92334 7.529763 -11.81437 87.99239 5.25 -10.20096 87.9 4.815023 -10.48273 87.99239 7.47054 -11.96138 87.9809 4.938149 -10.38293 87.9809 7.400454 -12.10098 87.96494 7.548138 -11.81815 87.99808 5.248618 -10.19857 87.92334 7.567248 -11.82208 88 5.067175 -10.29489 87.96494 7.32105 -12.23324 87.9454 4.80079 -10.47051 87.99808 7.213525 -12.38168 87.9 7.233413 -12.35848 87.92334 4.785987 -10.4578 88 5.200789 -10.21778 87.9454 7.490109 -11.96752 87.99239 5.389895 -10.12968 87.9 5.338192 -10.15081 87.92334 7.416318 -12.10779 87.9809 4.924019 -10.36807 87.99239 7.332469 -12.23958 87.96494 5.24455 -10.19152 87.9454 7.526623 -11.97898 88 7.508008 -11.97314 87.99808 5.056609 -10.28124 87.9809 7.240091 -12.36313 87.9454 7.114717 -12.5037 87.9 7.140234 -12.47886 87.92334 5.388771 -10.12716 87.92334 5.19388 -10.2067 87.96494 7.435166 -12.11588 87.99239 4.911094 -10.35447 87.99808 7.347562 -12.24796 87.9809 4.897653 -10.34033 88 5.334609 -10.14351 87.9454 7.25081 -12.37059 87.96494 5.23802 -10.18021 87.96494 7.470332 -12.13097 88 7.452405 -12.12328 87.99808 5.536475 -10.07342 87.9 5.478083 -10.09078 87.92334 7.146407 -12.48416 87.9454 7.035354 -12.58919 87.92334 7.003696 -12.61472 87.9 5.044055 -10.26502 87.99239 7.365495 -12.25791 87.99239 5.385462 -10.11972 87.9454 7.264978 -12.38045 87.9809 5.184749 -10.19205 87.9809 5.535621 -10.07079 87.92334 7.156317 -12.49267 87.96494 7.398955 -12.27648 88 7.381897 -12.26702 87.99808 5.328857 -10.13178 87.96494 7.04096 -12.59509 87.9454 5.229389 -10.16526 87.9809 6.881678 -12.71353 87.9 6.91985 -12.68835 87.92334 5.032572 -10.25019 87.99808 5.02063 -10.23476 88 5.475257 -10.08315 87.9454 7.281812 -12.39217 87.99239 7.169414 -12.50391 87.9809 5.38015 -10.10779 87.96494 7.049958 -12.60455 87.96494 5.688132 -10.03278 87.9 5.623329 -10.04521 87.92334 7.297209 -12.40288 87.99808 5.1739 -10.17465 87.99239 7.313222 -12.41403 88 5.533106 -10.06305 87.9454 6.924831 -12.69478 87.9454 6.75 -12.79904 87.9 6.794908 -12.77531 87.92334 5.321255 -10.11628 87.9809 5.219134 -10.1475 87.99239 7.184977 -12.51727 87.99239 5.687558 -10.03008 87.92334 5.470721 -10.0709 87.96494 7.061851 -12.61707 87.9809 6.751382 -12.80143 87.92334 5.373129 -10.09202 87.9809 6.932825 -12.70511 87.96494 5.163977 -10.15873 87.99808 7.214013 -12.5422 88 7.19921 -12.52949 87.99808 5.153658 -10.14217 88 6.799211 -12.78222 87.9454 5.621289 -10.03733 87.9454 5.529071 -10.05063 87.96494 6.610105 -12.87032 87.9 6.661808 -12.84919 87.92334 5.77244 -10.01457 87.92334 5.843207 -10.00822 87.9 7.075981 -12.63193 87.99239 5.209755 -10.13125 87.99808 5.295369 -10.06351 88 5.312223 -10.09787 87.99239 6.75545 -12.80848 87.9454 5.685866 -10.02212 87.9454 6.943391 -12.71876 87.9809 5.464726 -10.05472 87.9809 6.611229 -12.87284 87.92334 5.364787 -10.07329 87.99239 6.80612 -12.7933 87.96494 7.088906 -12.64553 87.99808 5.842918 -10.00547 87.92334 7.102347 -12.65967 88 5.618016 -10.02469 87.96494 6.665391 -12.85649 87.9454 5.523736 -10.03421 87.9809 5.303961 -10.08103 87.99808 6.76198 -12.81979 87.96494 6.463525 -12.92658 87.9 6.521917 -12.90922 87.92334 5.771208 -10.00652 87.9454 6.955945 -12.73498 87.99239 5.683151 -10.00934 87.96494 5.923886 -9.999166 87.92334 6.614538 -12.88028 87.9454 6 -10 87.9 6.815251 -12.80795 87.9809 5.457602 -10.03548 87.99239 6.464379 -12.92921 87.92334 5.357156 -10.05615 87.99808 5.444312 -9.999597 88 5.842068 -9.997378 87.9454 6.671143 -12.86822 87.96494 5.613689 -10.00798 87.9809 6.770611 -12.83474 87.9809 6.97937 -12.76524 88 6.967428 -12.74981 87.99808 5.517398 -10.0147 87.99239 6.524743 -12.91685 87.9454 6 -9.997237 87.92334 5.76923 -9.993614 87.96494 6.61985 -12.89221 87.96494 5.451087 -10.01789 87.99808 6.311868 -12.96722 87.9 6.376671 -12.95479 87.92334 5.679562 -9.992458 87.9809 6.8261 -12.82535 87.99239 5.923474 -9.99104 87.9454 6.466894 -12.93695 87.9454 6.076114 -9.999166 87.92334 6.678745 -12.88372 87.9809 6.156793 -10.00822 87.9 6.780866 -12.8525 87.99239 5.840703 -9.984389 87.96494 6.312442 -12.96992 87.92334 5.608548 -9.988123 87.99239 5.511601 -9.996864 87.99808 5.598956 -9.951077 88 6.529279 -12.9291 87.96494 6 -9.989101 87.9454 5.766616 -9.976551 87.9809 6.626871 -12.90798 87.9809 6.846342 -12.85783 88 6.836023 -12.84127 87.99808 5.675298 -9.972396 87.99239 6.378711 -12.96267 87.9454 6.157082 -10.00547 87.92334 6.470929 -12.94937 87.96494 5.922813 -9.977997 87.96494 6.22756 -12.98543 87.92334 6.156793 -12.99178 87.9 5.603846 -9.969963 87.99808 6.790245 -12.86875 87.99808 6.704631 -12.93649 88 6.076526 -9.99104 87.9454 6.687777 -12.90213 87.99239 5.838898 -9.967221 87.9809 6.314134 -12.97788 87.9454 6.22756 -10.01457 87.92334 6.535274 -12.94528 87.9809 6.311868 -10.03278 87.9 6 -9.976041 87.96494 6.635213 -12.92671 87.99239 6.157082 -12.99453 87.92334 5.76351 -9.956278 87.99239 5.671397 -9.954047 87.99808 6.381984 -12.97531 87.96494 5.757716 -9.918451 88 6.157932 -9.997378 87.9454 6.476264 -12.96579 87.9809 5.921938 -9.960757 87.9809 6.696039 -12.91897 87.99808 6.077187 -9.977997 87.96494 6.228792 -12.99348 87.9454 5.836755 -9.946824 87.99239 6.316849 -12.99066 87.96494 6 -13 87.9 6.076114 -13.00083 87.92334 6.312442 -10.03008 87.92334 6.542398 -12.96452 87.99239 5.76067 -9.937735 87.99808 6.228792 -10.00652 87.9454 6.555688 -13.0004 88 6.642844 -12.94385 87.99808 6 -9.958779 87.9809 6.157932 -13.00262 87.9454 6.463525 -10.07342 87.9 6.376671 -10.04521 87.92334 6.386311 -12.99202 87.9809 6.159297 -9.984389 87.96494 6.482602 -12.9853 87.99239 5.9209 -9.940273 87.99239 6 -13.00276 87.92334 5.834794 -9.928167 87.99808 5.918961 -9.902054 88 6.23077 -13.00639 87.96494 6.078062 -9.960757 87.9809 6.548913 -12.98211 87.99808 6.320438 -13.00754 87.9809 6.314134 -10.02212 87.9454 6.076526 -13.00896 87.9454 6.23077 -9.993614 87.96494 5.843207 -12.99178 87.9 5.923886 -13.00083 87.92334 6 -9.938268 87.99239 6.464379 -10.07079 87.92334 6.159297 -13.01561 87.96494 5.919949 -9.921538 87.99808 6.391452 -13.01188 87.99239 6.401044 -13.04892 88 6.488399 -13.00314 87.99808 6.378711 -10.03733 87.9454 6.161102 -9.967221 87.9809 6 -13.0109 87.9454 6.610105 -10.12968 87.9 6.521917 -10.09078 87.92334 6.233384 -13.02345 87.9809 6.0791 -9.940273 87.99239 6.316849 -10.00934 87.96494 6.324702 -13.0276 87.99239 5.842918 -12.99453 87.92334 6 -9.919509 87.99808 6.081039 -9.902054 88 6.077187 -13.022 87.96494 6.233384 -9.976551 87.9809 6.396154 -13.03004 87.99808 6.466894 -10.06305 87.9454 5.923474 -13.00896 87.9454 6.381984 -10.02469 87.96494 6.161102 -13.03278 87.9809 6.163245 -9.946824 87.99239 5.688132 -12.96722 87.9 5.77244 -12.98543 87.92334 6.611229 -10.12716 87.92334 6 -13.02396 87.96494 6.080051 -9.921538 87.99808 6.23649 -13.04372 87.99239 6.524743 -10.08315 87.9454 6.328603 -13.04595 87.99808 6.242284 -13.08155 88 5.842068 -13.00262 87.9454 6.320438 -9.992458 87.9809 6.661808 -10.15081 87.92334 6.75 -10.20096 87.9 6.078062 -13.03924 87.9809 6.23649 -9.956278 87.99239 5.922813 -13.022 87.96494 6.470929 -10.05063 87.96494 6.163245 -13.05318 87.99239 6.165206 -9.928167 87.99808 6.242284 -9.918451 88 5.687558 -12.96992 87.92334 6.386311 -10.00798 87.9809 6.23933 -13.06227 87.99808 6.614538 -10.11972 87.9454 5.771208 -12.99348 87.9454 6.529279 -10.0709 87.96494 6 -13.04122 87.9809 6.324702 -9.972396 87.99239 5.536475 -12.92658 87.9 5.623329 -12.95479 87.92334 6.751382 -10.19857 87.92334 5.840703 -13.01561 87.96494 6.23933 -9.937735 87.99808 6.0791 -13.05973 87.99239 6.665391 -10.14351 87.9454 6.081039 -13.09795 88 6.165206 -13.07183 87.99808 6.476264 -10.03421 87.9809 5.921938 -13.03924 87.9809 6.881678 -10.28647 87.9 6.794908 -10.22469 87.92334 5.685866 -12.97788 87.9454 5.76923 -13.00639 87.96494 6.391452 -9.988123 87.99239 6.61985 -10.10779 87.96494 6.328603 -9.954047 87.99808 6 -13.06173 87.99239 6.401044 -9.951077 88 6.535274 -10.05472 87.9809 5.535621 -12.92921 87.92334 6.080051 -13.07846 87.99808 6.75545 -10.19152 87.9454 5.621289 -12.96267 87.9454 6.671143 -10.13178 87.96494 5.838898 -13.03278 87.9809 6.482602 -10.0147 87.99239 5.389895 -12.87032 87.9 5.478083 -12.90922 87.92334 7.003696 -10.38528 87.9 6.883302 -10.28424 87.92334 5.9209 -13.05973 87.99239 6.396154 -9.969963 87.99808 5.683151 -12.99066 87.96494 6.799211 -10.21778 87.9454 5.918961 -13.09795 88 6 -13.08049 87.99808 6.626871 -10.09202 87.9809 5.766616 -13.02345 87.9809 6.542398 -10.03548 87.99239 5.533106 -12.93695 87.9454 6.76198 -10.18021 87.96494 5.618016 -12.97531 87.96494 6.678745 -10.11628 87.9809 6.488399 -9.996864 87.99808 5.836755 -13.05318 87.99239 6.555688 -9.999597 88 6.888084 -10.27766 87.9454 5.388771 -12.87284 87.92334 6.80612 -10.2067 87.96494 5.919949 -13.07846 87.99808 6.635213 -10.07329 87.99239 5.338192 -12.84919 87.92334 5.25 -12.79904 87.9 6.548913 -10.01789 87.99808 5.76351 -13.04372 87.99239 5.529071 -12.94937 87.96494 6.770611 -10.16526 87.9809 5.834794 -13.07183 87.99808 6.895761 -10.26709 87.96494 6.815251 -10.19205 87.9809 6.642844 -10.05615 87.99808 3.25 -11.5 88 3.258069 -11.71051 88 3.282229 -11.91979 88 3.322338 -12.1266 88 3.37816 -12.32973 88 3.449368 -12.528 88 3.535545 -12.72023 88 3.636184 -12.9053 88 3.750694 -13.08213 88 3.878405 -13.24967 88 4.018566 -13.40694 88 4.170354 -13.55302 88 4.33288 -13.68706 88 4.505189 -13.80825 88 4.68627 -13.91591 88 4.875061 -14.00938 88 5.070454 -14.08814 88 5.271301 -14.1517 88 5.476424 -14.1997 88 5.684621 -14.23186 88 5.894667 -14.24798 88 6.105333 -14.24798 88 6.315379 -14.23186 88 6.523576 -14.1997 88 6.728699 -14.1517 88 6.929546 -14.08814 88 7.124939 -14.00938 88 7.31373 -13.91591 88 7.494811 -13.80825 88 7.66712 -13.68706 88 7.829646 -13.55302 88 7.981434 -13.40694 88 8.121595 -13.24967 88 8.249306 -13.08213 88 8.363816 -12.9053 88 8.464455 -12.72023 88 8.550632 -12.528 88 8.62184 -12.32973 88 8.677662 -12.1266 88 8.717771 -11.91979 88 8.741931 -11.71051 88 8.75 -11.5 88 8.741931 -11.28949 88 8.717771 -11.08021 88 8.677662 -10.8734 88 8.62184 -10.67027 88 8.550632 -10.472 88 8.464455 -10.27977 88 8.363816 -10.0947 88 8.249306 -9.917874 88 8.121595 -9.750333 88 7.981434 -9.593061 88 7.829646 -9.446979 88 7.66712 -9.312945 88 7.494811 -9.191745 88 7.31373 -9.084091 88 7.124939 -8.990615 88 6.929546 -8.911865 88 6.728699 -8.848303 88 6.523576 -8.800302 88 6.315379 -8.768144 88 6.105333 -8.752018 88 5.894667 -8.752018 88 5.684621 -8.768144 88 5.476424 -8.800302 88 5.271301 -8.848303 88 5.070454 -8.911865 88 4.875061 -8.990615 88 4.68627 -9.084091 88 4.505189 -9.191745 88 4.33288 -9.312945 88 4.170354 -9.446979 88 4.018566 -9.593061 88 3.878405 -9.750333 88 3.750694 -9.917874 88 3.636184 -10.0947 88 3.535545 -10.27977 88 3.449368 -10.472 88 3.37816 -10.67027 88 3.322338 -10.8734 88 3.282229 -11.08021 88 3.258069 -11.28949 88 4.5 -11.5 78.2805 4.508217 -11.65679 78.2805 4.532779 -11.81187 78.2805 4.573415 -11.96353 78.2805 4.629682 -12.1101 78.2805 4.700962 -12.25 78.2805 4.786475 -12.38168 78.2805 4.885283 -12.5037 78.2805 4.996304 -12.61472 78.2805 5.118322 -12.71353 78.2805 5.25 -12.79904 78.2805 5.389895 -12.87032 78.2805 5.536475 -12.92658 78.2805 5.688132 -12.96722 78.2805 5.843207 -12.99178 78.2805 6 -13 78.2805 6.156793 -12.99178 78.2805 6.311868 -12.96722 78.2805 6.463525 -12.92658 78.2805 6.610105 -12.87032 78.2805 6.75 -12.79904 78.2805 6.881678 -12.71353 78.2805 7.003696 -12.61472 78.2805 7.114717 -12.5037 78.2805 7.213525 -12.38168 78.2805 7.299038 -12.25 78.2805 7.370318 -12.1101 78.2805 7.426585 -11.96353 78.2805 7.467221 -11.81187 78.2805 7.491783 -11.65679 78.2805 7.5 -11.5 78.2805 7.491783 -11.34321 78.2805 7.467221 -11.18813 78.2805 7.426585 -11.03647 78.2805 7.370318 -10.8899 78.2805 7.299038 -10.75 78.2805 7.213525 -10.61832 78.2805 7.114717 -10.4963 78.2805 7.003696 -10.38528 78.2805 6.881678 -10.28647 78.2805 6.75 -10.20096 78.2805 6.610105 -10.12968 78.2805 6.463525 -10.07342 78.2805 6.311868 -10.03278 78.2805 6.156793 -10.00822 78.2805 6 -10 78.2805 5.843207 -10.00822 78.2805 5.688132 -10.03278 78.2805 5.536475 -10.07342 78.2805 5.389895 -10.12968 78.2805 5.25 -10.20096 78.2805 5.118322 -10.28647 78.2805 4.996304 -10.38528 78.2805 4.885283 -10.4963 78.2805 4.786475 -10.61832 78.2805 4.700962 -10.75 78.2805 4.629682 -10.8899 78.2805 4.573415 -11.03647 78.2805 4.532779 -11.18813 78.2805 4.508217 -11.34321 78.2805 4.7805 -11.5 78 4.788746 -11.64158 78 4.813372 -11.78124 78 4.854045 -11.91709 78 4.910215 -12.04731 78 4.981123 -12.17013 78 5.065809 -12.28388 78 5.163128 -12.38703 78 5.271765 -12.47819 78 5.39025 -12.55612 78 5.516981 -12.61976 78 5.650243 -12.66827 78 5.788236 -12.70097 78 5.929092 -12.71744 78 6.070908 -12.71744 78 6.211764 -12.70097 78 6.349757 -12.66827 78 6.483019 -12.61976 78 6.60975 -12.55612 78 6.728235 -12.47819 78 6.836872 -12.38703 78 6.934191 -12.28388 78 7.018877 -12.17013 78 7.089785 -12.04731 78 7.145955 -11.91709 78 7.186628 -11.78124 78 7.211254 -11.64158 78 7.2195 -11.5 78 7.211254 -11.35842 78 7.186628 -11.21876 78 7.145955 -11.08291 78 7.089785 -10.95269 78 7.018877 -10.82987 78 6.934191 -10.71612 78 6.836872 -10.61297 78 6.728235 -10.52181 78 6.60975 -10.44388 78 6.483019 -10.38024 78 6.349757 -10.33173 78 6.211764 -10.29903 78 6.070908 -10.28256 78 5.929092 -10.28256 78 5.788236 -10.29903 78 5.650243 -10.33173 78 5.516981 -10.38024 78 5.39025 -10.44388 78 5.271765 -10.52181 78 5.163128 -10.61297 78 5.065809 -10.71612 78 4.981123 -10.82987 78 4.910215 -10.95269 78 4.854045 -11.08291 78 4.813372 -11.21876 78 4.788746 -11.35842 78 6 -10.3453 90 6 -12.6547 90 5 -12.07735 90 7 -10.92265 90 7 -12.07735 90 5 -10.92265 90 5 -12.07735 88.5 6 -12.6547 88.5 5 -10.92265 88.5 6 -10.3453 88.5 7 -10.92265 88.5 7 -12.07735 88.5 + + + + + + + + + + 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 0.5 -7.306142e-16 0.8660254 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.825 6.661338e-16 -6.058367e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -0.17 2.220446e-16 -1.248391e-16 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -2.75 3.205769e-15 -2.019456e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -1.5 1.748601e-15 -1.101521e-15 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -0.8623167 1.152346e-15 -0.8623167 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 7.343476e-16 1.706036e-16 -1 0.5 0.8660254 5.149209e-16 0.5 0.8660254 5.149209e-16 0.5 0.8660254 5.149209e-16 1 4.338833e-16 7.343476e-16 1 4.338833e-16 7.343476e-16 1 4.338833e-16 7.343476e-16 0.5 -0.8660254 2.194267e-16 0.5 -0.8660254 2.194267e-16 0.5 -0.8660254 2.194267e-16 -0.5 -0.8660254 -5.149209e-16 -0.5 -0.8660254 -5.149209e-16 -0.5 -0.8660254 -5.149209e-16 -1 -5.830465e-17 -7.343476e-16 -1 -5.830465e-17 -7.343476e-16 -1 -5.830465e-17 -7.343476e-16 -0.5 0.8660254 -2.194267e-16 -0.5 0.8660254 -2.194267e-16 -0.5 0.8660254 -2.194267e-16 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 -7.343476e-16 -1.706036e-16 1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 0 1 2 1 4 2 3 2 2 2 5 3 6 3 7 3 8 4 9 4 7 4 10 5 5 5 7 5 6 6 8 6 7 6 11 7 12 7 13 7 14 8 11 8 13 8 11 9 15 9 16 9 17 10 18 10 16 10 15 11 19 11 16 11 19 12 17 12 16 12 9 13 20 13 21 13 10 14 7 14 21 14 7 15 9 15 21 15 17 16 10 16 21 16 11 17 16 17 22 17 16 18 18 18 22 18 18 19 23 19 22 19 12 20 11 20 22 20 20 21 24 21 25 21 17 22 21 22 25 22 21 23 20 23 25 23 18 24 17 24 25 24 22 25 23 25 26 25 12 26 22 26 26 26 27 27 12 27 26 27 23 28 28 28 26 28 25 29 24 29 29 29 18 30 25 30 29 30 23 31 18 31 29 31 24 32 30 32 29 32 27 33 26 33 31 33 26 34 28 34 31 34 32 35 27 35 31 35 28 36 33 36 31 36 23 37 29 37 34 37 29 38 30 38 34 38 30 39 35 39 34 39 28 40 23 40 34 40 36 41 32 41 37 41 32 42 31 42 37 42 31 43 33 43 37 43 33 44 38 44 37 44 34 45 35 45 39 45 28 46 34 46 39 46 35 47 40 47 39 47 33 48 28 48 39 48 37 49 38 49 41 49 36 50 37 50 41 50 38 51 42 51 41 51 43 52 36 52 41 52 40 53 44 53 45 53 39 54 40 54 45 54 33 55 39 55 45 55 38 56 33 56 45 56 41 57 42 57 46 57 43 58 41 58 46 58 47 59 43 59 46 59 42 60 48 60 46 60 49 61 50 61 51 61 38 62 45 62 52 62 42 63 38 63 52 63 45 64 44 64 52 64 44 65 53 65 52 65 48 66 54 66 55 66 47 67 46 67 55 67 46 68 48 68 55 68 49 69 47 69 55 69 51 70 50 70 56 70 53 71 57 71 58 71 42 72 52 72 58 72 52 73 53 73 58 73 48 74 42 74 58 74 50 75 59 75 60 75 56 76 50 76 60 76 61 77 56 77 60 77 61 78 60 78 62 78 60 79 59 79 62 79 54 80 63 80 64 80 49 81 55 81 64 81 55 82 54 82 64 82 50 83 49 83 64 83 59 84 65 84 66 84 62 85 59 85 66 85 54 86 48 86 67 86 48 87 58 87 67 87 57 88 68 88 67 88 58 89 57 89 67 89 66 90 65 90 69 90 59 91 50 91 70 91 63 92 71 92 70 92 64 93 63 93 70 93 50 94 64 94 70 94 65 95 72 95 73 95 69 96 65 96 73 96 63 97 54 97 74 97 68 98 75 98 74 98 67 99 68 99 74 99 54 100 67 100 74 100 73 101 72 101 76 101 59 102 70 102 77 102 71 103 78 103 77 103 65 104 59 104 77 104 70 105 71 105 77 105 72 106 79 106 80 106 76 107 72 107 80 107 63 108 74 108 81 108 71 109 63 109 81 109 75 110 82 110 81 110 74 111 75 111 81 111 80 112 79 112 83 112 72 113 65 113 84 113 78 114 85 114 84 114 77 115 78 115 84 115 65 116 77 116 84 116 71 117 81 117 86 117 81 118 82 118 86 118 78 119 71 119 86 119 82 120 87 120 86 120 84 121 85 121 88 121 79 122 72 122 88 122 72 123 84 123 88 123 85 124 89 124 88 124 83 125 79 125 90 125 90 126 91 126 92 126 91 127 83 127 90 127 78 128 86 128 93 128 86 129 87 129 93 129 85 130 78 130 93 130 87 131 94 131 93 131 85 132 93 132 95 132 93 133 94 133 95 133 89 134 85 134 95 134 94 135 96 135 95 135 89 136 95 136 97 136 95 137 96 137 97 137 98 138 0 138 99 138 97 139 96 139 99 139 0 140 97 140 99 140 100 141 101 141 102 141 92 142 100 142 102 142 102 143 101 143 103 143 92 144 102 144 103 144 92 145 103 145 104 145 103 146 101 146 104 146 101 147 105 147 104 147 92 148 104 148 106 148 104 149 105 149 106 149 106 150 105 150 107 150 92 151 106 151 107 151 105 152 108 152 107 152 92 153 107 153 109 153 107 154 108 154 109 154 109 155 108 155 110 155 111 156 112 156 110 156 108 157 111 157 110 157 92 158 0 158 113 158 114 159 92 159 113 159 115 160 114 160 113 160 0 161 3 161 113 161 3 162 4 162 113 162 6 163 115 163 113 163 4 164 6 164 113 164 14 165 13 165 116 165 2 166 1 166 117 166 1 167 118 167 117 167 118 168 119 168 117 168 119 169 120 169 117 169 12 170 27 170 121 170 116 171 13 171 121 171 122 172 116 172 121 172 13 173 12 173 121 173 122 174 121 174 123 174 27 175 32 175 124 175 32 176 123 176 124 176 123 177 121 177 124 177 121 178 27 178 124 178 32 179 36 179 125 179 123 180 32 180 125 180 126 181 125 181 127 181 125 182 36 182 128 182 36 183 43 183 128 183 127 184 125 184 128 184 126 185 127 185 129 185 128 186 43 186 129 186 130 187 131 187 8 187 127 188 128 188 129 188 43 189 47 189 132 189 129 190 43 190 132 190 47 191 49 191 133 191 132 192 47 192 133 192 66 193 69 193 134 193 69 194 73 194 134 194 73 195 76 195 134 195 134 196 76 196 135 196 92 197 134 197 135 197 135 198 76 198 136 198 76 199 80 199 136 199 92 200 135 200 136 200 136 201 80 201 137 201 92 202 136 202 137 202 137 203 80 203 138 203 80 204 83 204 138 204 92 205 137 205 138 205 138 206 83 206 139 206 140 207 141 207 9 207 92 208 138 208 139 208 139 209 83 209 142 209 91 210 92 210 142 210 8 211 131 211 9 211 92 212 139 212 142 212 131 213 140 213 9 213 83 214 91 214 142 214 92 215 90 215 143 215 79 216 88 216 143 216 88 217 89 217 143 217 89 218 97 218 143 218 90 219 79 219 143 219 97 220 0 220 143 220 0 221 92 221 143 221 144 222 145 222 146 222 145 223 147 223 146 223 147 224 98 224 146 224 98 225 99 225 146 225 110 226 112 226 148 226 92 227 109 227 148 227 109 228 110 228 148 228 112 229 149 229 148 229 148 230 149 230 150 230 151 231 152 231 150 231 149 232 151 232 150 232 148 233 150 233 153 233 150 234 152 234 153 234 141 235 154 235 20 235 154 236 155 236 20 236 14 237 116 237 153 237 155 238 156 238 20 238 152 239 14 239 153 239 2 240 117 240 157 240 4 241 2 241 157 241 130 242 8 242 157 242 9 243 141 243 20 243 8 244 4 244 157 244 120 245 158 245 157 245 158 246 130 246 157 246 117 247 120 247 157 247 123 248 125 248 159 248 125 249 126 249 159 249 129 250 132 250 160 250 132 251 133 251 160 251 161 252 160 252 162 252 51 253 161 253 162 253 133 254 49 254 162 254 49 255 51 255 162 255 160 256 133 256 162 256 161 257 51 257 163 257 20 258 156 258 24 258 56 259 61 259 163 259 51 260 56 260 163 260 92 261 161 261 164 261 156 262 165 262 24 262 161 263 163 263 164 263 165 264 166 264 24 264 163 265 61 265 164 265 166 266 167 266 24 266 134 267 92 267 164 267 61 268 62 268 164 268 62 269 66 269 164 269 66 270 134 270 164 270 168 271 169 271 170 271 169 272 144 272 170 272 94 273 168 273 170 273 144 274 146 274 170 274 146 275 99 275 170 275 99 276 96 276 170 276 96 277 94 277 170 277 148 278 153 278 171 278 153 279 116 279 171 279 161 280 92 280 171 280 92 281 148 281 171 281 116 282 122 282 171 282 161 283 171 283 172 283 171 284 122 284 172 284 122 285 123 285 172 285 123 286 159 286 172 286 172 287 159 287 173 287 159 288 126 288 173 288 161 289 172 289 174 289 160 290 161 290 174 290 175 291 176 291 30 291 129 292 160 292 174 292 173 293 126 293 174 293 126 294 129 294 174 294 172 295 173 295 174 295 167 296 175 296 30 296 24 297 167 297 30 297 30 298 176 298 35 298 176 299 177 299 35 299 177 300 178 300 35 300 178 301 179 301 35 301 179 302 180 302 40 302 180 303 181 303 40 303 181 304 182 304 40 304 35 305 179 305 40 305 40 306 182 306 44 306 183 307 184 307 44 307 182 308 183 308 44 308 184 309 185 309 53 309 185 310 186 310 53 310 186 311 187 311 53 311 44 312 184 312 53 312 187 313 188 313 57 313 188 314 189 314 57 314 189 315 190 315 57 315 53 316 187 316 57 316 57 317 190 317 68 317 191 318 192 318 68 318 190 319 191 319 68 319 192 320 193 320 75 320 193 321 194 321 75 321 194 322 195 322 75 322 68 323 192 323 75 323 195 324 196 324 82 324 196 325 197 325 82 325 197 326 198 326 82 326 75 327 195 327 82 327 199 328 200 328 87 328 198 329 199 329 87 329 82 330 198 330 87 330 200 331 168 331 94 331 87 332 200 332 94 332 201 333 101 333 114 333 101 334 100 334 114 334 114 335 92 335 100 335 101 336 201 336 105 336 201 337 202 337 105 337 105 338 202 338 108 338 202 339 203 339 111 339 108 340 202 340 111 340 111 341 203 341 112 341 115 342 5 342 204 342 201 343 114 343 204 343 114 344 115 344 204 344 202 345 201 345 204 345 112 346 203 346 149 346 203 347 15 347 149 347 149 348 15 348 151 348 204 349 5 349 205 349 203 350 202 350 205 350 202 351 204 351 205 351 5 352 10 352 205 352 152 353 151 353 206 353 15 354 11 354 206 354 151 355 15 355 206 355 5 356 115 356 6 356 4 357 8 357 6 357 10 358 17 358 19 358 203 359 205 359 19 359 205 360 10 360 19 360 15 361 203 361 19 361 152 362 206 362 14 362 206 363 11 363 14 363 207 364 208 364 209 364 207 365 210 365 208 365 211 366 212 366 213 366 207 367 209 367 214 367 211 368 215 368 212 368 216 369 217 369 218 369 211 370 213 370 219 370 216 371 220 371 217 371 216 372 218 372 221 372 222 373 221 373 223 373 224 374 225 374 226 374 224 375 227 375 225 375 222 376 223 376 228 376 229 377 207 377 214 377 230 378 231 378 232 378 233 379 214 379 234 379 235 380 219 380 231 380 233 381 234 381 236 381 235 382 211 382 219 382 237 383 238 383 239 383 240 384 222 384 228 384 237 385 239 385 241 385 237 386 242 386 227 386 237 387 241 387 242 387 240 388 228 388 243 388 244 389 210 389 207 389 244 390 243 390 210 390 245 391 226 391 215 391 245 392 224 392 226 392 246 393 221 393 222 393 246 394 220 394 216 394 247 395 215 395 211 395 247 396 211 396 235 396 246 397 216 397 221 397 248 398 236 398 249 398 250 399 232 399 251 399 248 400 249 400 252 400 250 401 230 401 232 401 253 402 244 402 207 402 254 403 227 403 224 403 254 404 237 404 227 404 255 405 235 405 231 405 253 406 207 406 229 406 256 407 214 407 233 407 255 408 231 408 230 408 256 409 229 409 214 409 257 410 246 410 222 410 258 411 247 411 235 411 257 412 220 412 246 412 257 413 259 413 220 413 257 414 222 414 240 414 260 415 243 415 244 415 261 416 224 416 245 416 260 417 240 417 243 417 261 418 254 418 224 418 262 419 215 419 247 419 262 420 245 420 215 420 263 421 250 421 251 421 264 422 236 422 248 422 264 423 233 423 236 423 265 424 244 424 253 424 265 425 260 425 244 425 266 426 230 426 250 426 266 427 255 427 230 427 267 428 253 428 229 428 268 429 254 429 261 429 268 430 269 430 238 430 267 431 229 431 256 431 268 432 238 432 237 432 268 433 237 433 254 433 270 434 240 434 260 434 270 435 259 435 257 435 271 436 235 436 255 436 270 437 257 437 240 437 271 438 258 438 235 438 270 439 260 439 265 439 272 440 247 440 258 440 273 441 252 441 274 441 273 442 264 442 248 442 272 443 262 443 247 443 273 444 248 444 252 444 275 445 269 445 268 445 276 446 233 446 264 446 275 447 268 447 261 447 276 448 256 448 233 448 277 449 263 449 251 449 277 450 251 450 278 450 279 451 280 451 259 451 279 452 259 452 270 452 279 453 270 453 265 453 281 454 245 454 262 454 282 455 265 455 253 455 282 456 253 456 267 456 281 457 261 457 245 457 283 458 250 458 263 458 284 459 276 459 264 459 283 460 266 460 250 460 284 461 264 461 273 461 285 462 255 462 266 462 286 463 256 463 276 463 285 464 271 464 255 464 286 465 267 465 256 465 287 466 265 466 282 466 288 467 258 467 271 467 287 468 280 468 279 468 288 469 272 469 258 469 287 470 279 470 265 470 289 471 277 471 278 471 290 472 274 472 291 472 290 473 273 473 274 473 292 474 262 474 272 474 290 475 284 475 273 475 293 476 276 476 284 476 292 477 281 477 262 477 294 478 295 478 269 478 293 479 286 479 276 479 294 480 269 480 275 480 294 481 275 481 261 481 294 482 261 482 281 482 296 483 287 483 282 483 296 484 282 484 267 484 294 485 281 485 292 485 296 486 267 486 286 486 297 487 283 487 263 487 297 488 263 488 277 488 298 489 284 489 290 489 299 490 296 490 286 490 300 491 266 491 283 491 300 492 285 492 266 492 299 493 286 493 293 493 301 494 271 494 285 494 301 495 288 495 271 495 302 496 291 496 303 496 302 497 290 497 291 497 304 498 272 498 288 498 305 499 306 499 280 499 304 500 292 500 272 500 305 501 287 501 296 501 305 502 280 502 287 502 307 503 294 503 292 503 308 504 284 504 298 504 307 505 295 505 294 505 309 506 297 506 277 506 309 507 277 507 289 507 308 508 293 508 284 508 310 509 296 509 299 509 311 510 289 510 278 510 310 511 305 511 296 511 311 512 278 512 312 512 313 513 290 513 302 513 314 514 283 514 297 514 313 515 298 515 290 515 314 516 300 516 283 516 314 517 297 517 309 517 315 518 293 518 308 518 316 519 285 519 300 519 315 520 299 520 293 520 316 521 301 521 285 521 317 522 302 522 303 522 317 523 303 523 318 523 319 524 311 524 312 524 317 525 313 525 302 525 320 526 305 526 310 526 320 527 321 527 306 527 322 528 288 528 301 528 320 529 306 529 305 529 322 530 304 530 288 530 323 531 298 531 313 531 324 532 325 532 295 532 323 533 308 533 298 533 324 534 295 534 307 534 324 535 292 535 304 535 324 536 307 536 292 536 326 537 310 537 299 537 326 538 299 538 315 538 327 539 314 539 309 539 328 540 289 540 311 540 329 541 313 541 317 541 328 542 309 542 289 542 329 543 323 543 313 543 330 544 315 544 308 544 331 545 300 545 314 545 330 546 308 546 323 546 331 547 316 547 300 547 330 548 326 548 315 548 332 549 301 549 316 549 332 550 322 550 301 550 333 551 318 551 334 551 333 552 317 552 318 552 335 553 310 553 326 553 336 554 328 554 311 554 335 555 320 555 310 555 336 556 311 556 319 556 335 557 321 557 320 557 335 558 337 558 321 558 338 559 325 559 324 559 339 560 330 560 323 560 338 561 304 561 322 561 339 562 323 562 329 562 338 563 324 563 304 563 340 564 312 564 341 564 342 565 335 565 326 565 340 566 319 566 312 566 342 567 326 567 330 567 343 568 331 568 314 568 344 569 329 569 317 569 343 570 314 570 327 570 344 571 317 571 333 571 345 572 330 572 339 572 346 573 327 573 309 573 346 574 309 574 328 574 347 575 316 575 331 575 348 576 334 576 349 576 347 577 332 577 316 577 348 578 333 578 334 578 350 579 338 579 322 579 350 580 351 580 325 580 350 581 325 581 338 581 352 582 335 582 342 582 352 583 353 583 337 583 350 584 322 584 332 584 352 585 337 585 335 585 354 586 329 586 344 586 355 587 346 587 328 587 354 588 339 588 329 588 355 589 328 589 336 589 356 590 319 590 340 590 357 591 349 591 358 591 357 592 348 592 349 592 356 593 336 593 319 593 359 594 342 594 330 594 360 595 347 595 331 595 359 596 330 596 345 596 360 597 331 597 343 597 361 598 343 598 327 598 362 599 348 599 357 599 362 600 344 600 333 600 361 601 327 601 346 601 363 602 332 602 347 602 362 603 333 603 348 603 363 604 350 604 332 604 363 605 347 605 360 605 363 606 351 606 350 606 364 607 345 607 339 607 364 608 339 608 354 608 365 609 340 609 341 609 364 610 359 610 345 610 365 611 341 611 366 611 367 612 362 612 357 612 368 613 361 613 346 613 368 614 346 614 355 614 369 615 357 615 358 615 370 616 371 616 353 616 372 617 336 617 356 617 370 618 352 618 342 618 370 619 342 619 359 619 370 620 353 620 352 620 372 621 355 621 336 621 373 622 374 622 351 622 373 623 363 623 360 623 375 624 344 624 362 624 373 625 351 625 363 625 375 626 354 626 344 626 376 627 343 627 361 627 376 628 360 628 343 628 375 629 362 629 367 629 377 630 358 630 378 630 379 631 340 631 365 631 379 632 356 632 340 632 377 633 369 633 358 633 380 634 359 634 364 634 380 635 370 635 359 635 381 636 376 636 361 636 381 637 361 637 368 637 382 638 375 638 367 638 383 639 368 639 355 639 383 640 355 640 372 640 384 641 367 641 357 641 384 642 357 642 369 642 385 643 374 643 373 643 385 644 373 644 360 644 386 645 375 645 382 645 385 646 360 646 376 646 386 647 364 647 354 647 386 648 354 648 375 648 387 649 365 649 366 649 386 650 380 650 364 650 387 651 366 651 388 651 389 652 377 652 378 652 390 653 384 653 369 653 391 654 356 654 379 654 391 655 372 655 356 655 392 656 376 656 381 656 392 657 393 657 374 657 390 658 369 658 377 658 392 659 385 659 376 659 394 660 395 660 371 660 392 661 374 661 385 661 394 662 371 662 370 662 396 663 368 663 383 663 394 664 370 664 380 664 396 665 381 665 368 665 397 666 386 666 382 666 398 667 382 667 367 667 398 668 384 668 390 668 399 669 365 669 387 669 398 670 367 670 384 670 399 671 379 671 365 671 400 672 389 672 378 672 400 673 378 673 401 673 402 674 383 674 372 674 402 675 372 675 391 675 403 676 380 676 386 676 404 677 392 677 381 677 403 678 386 678 397 678 404 679 393 679 392 679 404 680 381 680 396 680 403 681 394 681 380 681 405 682 390 682 377 682 406 683 388 683 407 683 405 684 377 684 389 684 406 685 387 685 388 685 405 686 389 686 400 686 408 687 391 687 379 687 409 688 390 688 405 688 409 689 398 689 390 689 408 690 379 690 399 690 410 691 403 691 397 691 411 692 396 692 383 692 411 693 383 693 402 693 411 694 404 694 396 694 412 695 397 695 382 695 412 696 382 696 398 696 413 697 400 697 401 697 414 698 399 698 387 698 414 699 387 699 406 699 415 700 402 700 391 700 416 701 400 701 413 701 416 702 405 702 400 702 415 703 391 703 408 703 417 704 403 704 410 704 418 705 406 705 407 705 417 706 394 706 403 706 417 707 419 707 395 707 417 708 395 708 394 708 420 709 409 709 405 709 418 710 407 710 421 710 420 711 405 711 416 711 422 712 423 712 393 712 422 713 393 713 404 713 422 714 404 714 411 714 424 715 412 715 398 715 424 716 398 716 409 716 425 717 408 717 399 717 426 718 417 718 410 718 425 719 399 719 414 719 426 720 419 720 417 720 427 721 401 721 428 721 429 722 411 722 402 722 427 723 413 723 401 723 429 724 402 724 415 724 429 725 422 725 411 725 430 726 425 726 414 726 431 727 397 727 412 727 430 728 406 728 418 728 430 729 414 729 406 729 431 730 410 730 397 730 432 731 416 731 413 731 433 732 408 732 425 732 433 733 415 733 408 733 434 734 416 734 432 734 434 735 420 735 416 735 435 736 424 736 409 736 435 737 409 737 420 737 436 738 421 738 437 738 436 739 418 739 421 739 438 740 422 740 429 740 438 741 439 741 423 741 435 742 420 742 434 742 438 743 423 743 422 743 440 744 427 744 428 744 441 745 425 745 430 745 442 746 412 746 424 746 443 747 429 747 415 747 442 748 431 748 412 748 444 749 445 749 419 749 443 750 415 750 433 750 444 751 426 751 410 751 444 752 419 752 426 752 446 753 430 753 418 753 444 754 410 754 431 754 444 755 431 755 442 755 447 756 413 756 427 756 446 757 418 757 436 757 447 758 432 758 413 758 448 759 425 759 441 759 449 760 434 760 432 760 448 761 433 761 425 761 450 762 436 762 437 762 449 763 432 763 447 763 451 764 435 764 434 764 450 765 437 765 452 765 451 766 434 766 449 766 453 767 454 767 439 767 455 768 442 768 424 768 453 769 439 769 438 769 455 770 424 770 435 770 453 771 429 771 443 771 453 772 438 772 429 772 455 773 435 773 451 773 456 774 442 774 455 774 456 775 445 775 444 775 457 776 430 776 446 776 456 777 444 777 442 777 457 778 441 778 430 778 458 779 443 779 433 779 458 780 433 780 448 780 459 781 427 781 440 781 459 782 447 782 427 782 460 783 428 783 461 783 462 784 436 784 450 784 460 785 440 785 428 785 460 786 459 786 440 786 462 787 446 787 436 787 463 788 449 788 447 788 464 789 458 789 448 789 464 790 448 790 441 790 464 791 441 791 457 791 465 792 451 792 449 792 466 793 450 793 452 793 466 794 452 794 467 794 468 795 469 795 454 795 470 796 460 796 461 796 471 797 451 797 465 797 468 798 443 798 458 798 468 799 454 799 453 799 468 800 453 800 443 800 471 801 455 801 451 801 472 802 455 802 471 802 472 803 473 803 445 803 472 804 456 804 455 804 472 805 445 805 456 805 474 806 467 806 475 806 474 807 466 807 467 807 476 808 463 808 447 808 476 809 447 809 459 809 477 810 457 810 446 810 478 811 459 811 460 811 477 812 446 812 462 812 478 813 476 813 459 813 479 814 458 814 464 814 478 815 460 815 470 815 480 816 465 816 449 816 479 817 468 817 458 817 480 818 449 818 463 818 481 819 450 819 466 819 481 820 462 820 450 820 482 821 471 821 465 821 483 822 481 822 466 822 484 823 478 823 470 823 483 824 466 824 474 824 485 825 471 825 482 825 485 826 472 826 471 826 486 827 464 827 457 827 485 828 473 828 472 828 487 829 470 829 461 829 486 830 457 830 477 830 487 831 461 831 488 831 489 832 463 832 476 832 490 833 474 833 475 833 491 834 492 834 469 834 491 835 468 835 479 835 491 836 469 836 468 836 489 837 480 837 463 837 493 838 476 838 478 838 493 839 489 839 476 839 493 840 478 840 484 840 494 841 481 841 483 841 494 842 477 842 462 842 495 843 465 843 480 843 494 844 462 844 481 844 495 845 482 845 465 845 496 846 485 846 482 846 496 847 473 847 485 847 497 848 475 848 498 848 496 849 499 849 473 849 496 850 482 850 495 850 497 851 490 851 475 851 500 852 493 852 484 852 501 853 494 853 483 853 502 854 479 854 464 854 503 855 470 855 487 855 502 856 464 856 486 856 503 857 484 857 470 857 504 858 495 858 480 858 504 859 480 859 489 859 505 860 483 860 474 860 505 861 474 861 490 861 506 862 489 862 493 862 506 863 493 863 500 863 507 864 502 864 486 864 506 865 504 865 489 865 507 866 486 866 477 866 507 867 477 867 494 867 508 868 499 868 496 868 508 869 496 869 495 869 509 870 488 870 510 870 511 871 497 871 498 871 509 872 487 872 488 872 512 873 505 873 490 873 512 874 497 874 511 874 512 875 490 875 497 875 513 876 506 876 500 876 514 877 515 877 492 877 514 878 479 878 502 878 514 879 492 879 491 879 516 880 500 880 484 880 514 881 491 881 479 881 516 882 484 882 503 882 517 883 494 883 501 883 518 884 495 884 504 884 518 885 519 885 499 885 517 886 507 886 494 886 518 887 508 887 495 887 518 888 499 888 508 888 520 889 517 889 501 889 521 890 518 890 504 890 520 891 501 891 483 891 520 892 483 892 505 892 521 893 504 893 506 893 521 894 506 894 513 894 522 895 487 895 509 895 522 896 503 896 487 896 523 897 498 897 524 897 523 898 511 898 498 898 525 899 514 899 502 899 525 900 502 900 507 900 526 901 512 901 511 901 527 902 521 902 513 902 528 903 513 903 500 903 528 904 500 904 516 904 529 905 520 905 505 905 528 906 527 906 513 906 529 907 505 907 512 907 530 908 518 908 521 908 529 909 512 909 526 909 530 910 519 910 518 910 531 911 525 911 507 911 530 912 521 912 527 912 531 913 507 913 517 913 532 914 510 914 533 914 532 915 509 915 510 915 534 916 503 916 522 916 535 917 517 917 520 917 536 918 523 918 524 918 534 919 516 919 503 919 537 920 538 920 519 920 539 921 511 921 523 921 537 922 519 922 530 922 537 923 530 923 527 923 539 924 526 924 511 924 540 925 527 925 528 925 541 926 542 926 515 926 541 927 515 927 514 927 543 928 509 928 532 928 541 929 514 929 525 929 541 930 525 930 531 930 544 931 529 931 526 931 543 932 522 932 509 932 544 933 526 933 539 933 545 934 529 934 544 934 545 935 535 935 520 935 545 936 520 936 529 936 546 937 528 937 516 937 546 938 516 938 534 938 547 939 542 939 541 939 548 940 537 940 527 940 548 941 538 941 537 941 547 942 541 942 531 942 548 943 527 943 540 943 549 944 536 944 524 944 550 945 533 945 551 945 550 946 532 946 533 946 549 947 524 947 552 947 553 948 517 948 535 948 554 949 522 949 543 949 553 950 531 950 517 950 555 951 523 951 536 951 555 952 539 952 523 952 554 953 534 953 522 953 555 954 536 954 549 954 556 955 540 955 528 955 557 956 544 956 539 956 556 957 528 957 546 957 557 958 539 958 555 958 558 959 532 959 550 959 559 960 545 960 544 960 558 961 543 961 532 961 560 962 534 962 554 962 561 963 553 963 535 963 561 964 535 964 545 964 561 965 545 965 559 965 560 966 546 966 534 966 562 967 549 967 552 967 563 968 551 968 564 968 563 969 558 969 550 969 563 970 550 970 551 970 565 971 555 971 549 971 566 972 538 972 548 972 566 973 548 973 540 973 565 974 549 974 562 974 567 975 568 975 569 975 570 976 571 976 542 976 566 977 572 977 538 977 570 978 542 978 547 978 566 979 540 979 556 979 570 980 547 980 531 980 570 981 531 981 553 981 573 982 543 982 558 982 574 983 557 983 555 983 573 984 554 984 543 984 574 985 555 985 565 985 575 986 546 986 560 986 575 987 556 987 546 987 576 988 544 988 557 988 576 989 559 989 544 989 577 990 571 990 570 990 578 991 573 991 558 991 577 992 553 992 561 992 577 993 570 993 553 993 578 994 558 994 563 994 579 995 561 995 559 995 580 996 560 996 554 996 579 997 577 997 561 997 580 998 554 998 573 998 581 999 552 999 582 999 581 1000 562 1000 552 1000 583 1001 584 1001 585 1001 583 1002 564 1002 584 1002 583 1003 563 1003 564 1003 586 1004 565 1004 562 1004 587 1005 556 1005 575 1005 587 1006 566 1006 556 1006 587 1007 572 1007 566 1007 588 1008 574 1008 565 1008 587 1009 589 1009 572 1009 590 1010 567 1010 569 1010 591 1011 573 1011 578 1011 588 1012 565 1012 586 1012 590 1013 592 1013 593 1013 594 1014 557 1014 574 1014 590 1015 569 1015 592 1015 594 1016 576 1016 557 1016 591 1017 580 1017 573 1017 595 1018 575 1018 560 1018 595 1019 560 1019 580 1019 595 1020 587 1020 575 1020 596 1021 597 1021 567 1021 598 1022 581 1022 582 1022 596 1023 567 1023 590 1023 599 1024 578 1024 563 1024 600 1025 559 1025 576 1025 601 1026 596 1026 590 1026 600 1027 579 1027 559 1027 601 1028 590 1028 593 1028 599 1029 563 1029 583 1029 602 1030 579 1030 600 1030 602 1031 603 1031 571 1031 604 1032 580 1032 591 1032 602 1033 571 1033 577 1033 605 1034 597 1034 596 1034 602 1035 577 1035 579 1035 605 1036 606 1036 597 1036 607 1037 599 1037 583 1037 608 1038 562 1038 581 1038 607 1039 583 1039 585 1039 609 1040 596 1040 601 1040 608 1041 586 1041 562 1041 609 1042 605 1042 596 1042 610 1043 587 1043 595 1043 611 1044 586 1044 608 1044 610 1045 612 1045 589 1045 610 1046 589 1046 587 1046 611 1047 588 1047 586 1047 613 1048 591 1048 578 1048 613 1049 578 1049 599 1049 614 1050 615 1050 606 1050 616 1051 588 1051 611 1051 614 1052 606 1052 605 1052 617 1053 601 1053 593 1053 616 1054 574 1054 588 1054 616 1055 594 1055 574 1055 618 1056 595 1056 580 1056 618 1057 580 1057 604 1057 618 1058 610 1058 595 1058 617 1059 619 1059 620 1059 621 1060 600 1060 576 1060 617 1061 593 1061 619 1061 621 1062 576 1062 594 1062 622 1063 600 1063 621 1063 623 1064 614 1064 605 1064 623 1065 605 1065 609 1065 622 1066 603 1066 602 1066 622 1067 602 1067 600 1067 624 1068 613 1068 599 1068 624 1069 599 1069 607 1069 625 1070 581 1070 598 1070 626 1071 627 1071 615 1071 628 1072 618 1072 604 1072 626 1073 629 1073 627 1073 625 1074 608 1074 581 1074 628 1075 604 1075 591 1075 628 1076 591 1076 613 1076 626 1077 615 1077 614 1077 630 1078 598 1078 582 1078 631 1079 609 1079 601 1079 630 1080 582 1080 632 1080 633 1081 585 1081 634 1081 633 1082 607 1082 585 1082 631 1083 601 1083 617 1083 635 1084 611 1084 608 1084 636 1085 637 1085 612 1085 638 1086 626 1086 614 1086 638 1087 614 1087 623 1087 636 1088 610 1088 618 1088 636 1089 612 1089 610 1089 639 1090 634 1090 640 1090 641 1091 617 1091 620 1091 642 1092 616 1092 611 1092 639 1093 633 1093 634 1093 641 1094 631 1094 617 1094 643 1095 630 1095 632 1095 644 1096 629 1096 626 1096 644 1097 645 1097 629 1097 644 1098 646 1098 645 1098 647 1099 613 1099 624 1099 647 1100 628 1100 613 1100 648 1101 621 1101 594 1101 648 1102 616 1102 642 1102 649 1103 623 1103 609 1103 650 1104 618 1104 628 1104 648 1105 594 1105 616 1105 651 1106 622 1106 621 1106 651 1107 621 1107 648 1107 650 1108 636 1108 618 1108 649 1109 609 1109 631 1109 651 1110 603 1110 622 1110 652 1111 641 1111 620 1111 651 1112 653 1112 603 1112 654 1113 624 1113 607 1113 654 1114 607 1114 633 1114 652 1115 620 1115 655 1115 656 1116 635 1116 608 1116 657 1117 644 1117 626 1117 656 1118 608 1118 625 1118 658 1119 625 1119 598 1119 657 1120 626 1120 638 1120 658 1121 598 1121 630 1121 659 1122 631 1122 641 1122 660 1123 654 1123 633 1123 659 1124 649 1124 631 1124 658 1125 630 1125 643 1125 659 1126 641 1126 652 1126 658 1127 656 1127 625 1127 660 1128 633 1128 639 1128 661 1129 638 1129 623 1129 662 1130 611 1130 635 1130 663 1131 628 1131 647 1131 662 1132 642 1132 611 1132 663 1133 650 1133 628 1133 661 1134 623 1134 649 1134 664 1135 660 1135 639 1135 665 1136 648 1136 642 1136 666 1137 659 1137 652 1137 664 1138 639 1138 640 1138 667 1139 668 1139 637 1139 667 1140 637 1140 636 1140 669 1141 652 1141 655 1141 667 1142 636 1142 650 1142 670 1143 658 1143 643 1143 671 1144 651 1144 648 1144 672 1145 624 1145 654 1145 669 1146 666 1146 652 1146 671 1147 653 1147 651 1147 672 1148 647 1148 624 1148 673 1149 646 1149 644 1149 671 1150 648 1150 665 1150 673 1151 674 1151 646 1151 673 1152 644 1152 657 1152 675 1153 664 1153 640 1153 676 1154 632 1154 677 1154 675 1155 640 1155 678 1155 679 1156 659 1156 666 1156 676 1157 643 1157 632 1157 679 1158 649 1158 659 1158 679 1159 661 1159 649 1159 680 1160 635 1160 656 1160 681 1161 672 1161 654 1161 682 1162 669 1162 655 1162 680 1163 662 1163 635 1163 682 1164 655 1164 683 1164 681 1165 654 1165 660 1165 684 1166 657 1166 638 1166 685 1167 667 1167 650 1167 686 1168 656 1168 658 1168 684 1169 638 1169 661 1169 686 1170 658 1170 670 1170 687 1171 688 1171 653 1171 685 1172 650 1172 663 1172 687 1173 653 1173 671 1173 687 1174 671 1174 665 1174 689 1175 681 1175 660 1175 690 1176 679 1176 666 1176 691 1177 642 1177 662 1177 691 1178 665 1178 642 1178 689 1179 660 1179 664 1179 692 1180 647 1180 672 1180 692 1181 663 1181 647 1181 693 1182 666 1182 669 1182 693 1183 690 1183 666 1183 692 1184 685 1184 663 1184 693 1185 669 1185 682 1185 694 1186 686 1186 670 1186 695 1187 684 1187 661 1187 696 1188 670 1188 643 1188 696 1189 643 1189 676 1189 695 1190 661 1190 679 1190 697 1191 675 1191 678 1191 698 1192 664 1192 675 1192 698 1193 689 1193 664 1193 698 1194 675 1194 697 1194 699 1195 682 1195 683 1195 700 1196 662 1196 680 1196 701 1197 693 1197 682 1197 700 1198 691 1198 662 1198 702 1199 703 1199 668 1199 704 1200 680 1200 656 1200 702 1201 667 1201 685 1201 702 1202 668 1202 667 1202 705 1203 672 1203 681 1203 704 1204 656 1204 686 1204 706 1205 673 1205 657 1205 704 1206 686 1206 694 1206 706 1207 674 1207 673 1207 706 1208 707 1208 674 1208 708 1209 688 1209 687 1209 706 1210 657 1210 684 1210 708 1211 687 1211 665 1211 705 1212 692 1212 672 1212 708 1213 665 1213 691 1213 709 1214 681 1214 689 1214 709 1215 705 1215 681 1215 710 1216 695 1216 679 1216 709 1217 689 1217 698 1217 710 1218 679 1218 690 1218 711 1219 677 1219 712 1219 713 1220 697 1220 678 1220 714 1221 710 1221 690 1221 711 1222 676 1222 677 1222 713 1223 678 1223 715 1223 714 1224 693 1224 701 1224 714 1225 690 1225 693 1225 716 1226 702 1226 685 1226 716 1227 685 1227 692 1227 717 1228 704 1228 694 1228 718 1229 683 1229 719 1229 718 1230 699 1230 683 1230 720 1231 670 1231 696 1231 720 1232 694 1232 670 1232 721 1233 698 1233 697 1233 722 1234 684 1234 695 1234 722 1235 706 1235 684 1235 723 1236 724 1236 688 1236 723 1237 688 1237 708 1237 723 1238 691 1238 700 1238 725 1239 698 1239 721 1239 726 1240 701 1240 682 1240 723 1241 708 1241 691 1241 726 1242 682 1242 699 1242 725 1243 709 1243 698 1243 727 1244 680 1244 704 1244 727 1245 700 1245 680 1245 728 1246 716 1246 692 1246 728 1247 692 1247 705 1247 727 1248 704 1248 717 1248 729 1249 714 1249 701 1249 730 1250 705 1250 709 1250 731 1251 696 1251 676 1251 730 1252 728 1252 705 1252 732 1253 695 1253 710 1253 731 1254 676 1254 711 1254 732 1255 722 1255 695 1255 733 1256 727 1256 717 1256 734 1257 710 1257 714 1257 734 1258 732 1258 710 1258 734 1259 714 1259 729 1259 735 1260 713 1260 715 1260 736 1261 697 1261 713 1261 736 1262 721 1262 697 1262 737 1263 718 1263 719 1263 738 1264 717 1264 694 1264 736 1265 713 1265 735 1265 738 1266 694 1266 720 1266 739 1267 700 1267 727 1267 740 1268 702 1268 716 1268 741 1269 726 1269 699 1269 740 1270 703 1270 702 1270 741 1271 699 1271 718 1271 739 1272 727 1272 733 1272 739 1273 724 1273 723 1273 740 1274 742 1274 703 1274 739 1275 723 1275 700 1275 743 1276 721 1276 736 1276 743 1277 725 1277 721 1277 744 1278 707 1278 706 1278 744 1279 706 1279 722 1279 744 1280 722 1280 732 1280 745 1281 712 1281 746 1281 747 1282 709 1282 725 1282 744 1283 748 1283 707 1283 745 1284 711 1284 712 1284 747 1285 730 1285 709 1285 749 1286 729 1286 701 1286 749 1287 701 1287 726 1287 749 1288 726 1288 741 1288 750 1289 716 1289 728 1289 751 1290 696 1290 731 1290 752 1291 734 1291 729 1291 751 1292 720 1292 696 1292 750 1293 742 1293 740 1293 750 1294 740 1294 716 1294 753 1295 724 1295 739 1295 753 1296 739 1296 733 1296 754 1297 715 1297 755 1297 753 1298 756 1298 724 1298 757 1299 748 1299 744 1299 757 1300 744 1300 732 1300 758 1301 717 1301 738 1301 754 1302 735 1302 715 1302 758 1303 733 1303 717 1303 759 1304 750 1304 728 1304 760 1305 719 1305 761 1305 759 1306 728 1306 730 1306 760 1307 737 1307 719 1307 762 1308 731 1308 711 1308 763 1309 734 1309 752 1309 764 1310 736 1310 735 1310 763 1311 757 1311 732 1311 762 1312 711 1312 745 1312 764 1313 735 1313 754 1313 763 1314 732 1314 734 1314 765 1315 738 1315 720 1315 766 1316 718 1316 737 1316 767 1317 743 1317 736 1317 767 1318 736 1318 764 1318 766 1319 741 1319 718 1319 768 1320 725 1320 743 1320 765 1321 720 1321 751 1321 768 1322 747 1322 725 1322 769 1323 753 1323 733 1323 770 1324 749 1324 741 1324 769 1325 756 1325 753 1325 769 1326 733 1326 758 1326 771 1327 730 1327 747 1327 772 1328 745 1328 746 1328 771 1329 759 1329 730 1329 773 1330 729 1330 749 1330 773 1331 752 1331 729 1331 772 1332 746 1332 774 1332 775 1333 763 1333 752 1333 776 1334 754 1334 755 1334 777 1335 751 1335 731 1335 777 1336 731 1336 762 1336 778 1337 760 1337 761 1337 779 1338 764 1338 754 1338 779 1339 754 1339 776 1339 780 1340 757 1340 763 1340 781 1341 769 1341 758 1341 782 1342 783 1342 742 1342 780 1343 748 1343 757 1343 782 1344 742 1344 750 1344 780 1345 784 1345 748 1345 781 1346 738 1346 765 1346 782 1347 750 1347 759 1347 780 1348 763 1348 775 1348 781 1349 758 1349 738 1349 782 1350 759 1350 771 1350 785 1351 737 1351 760 1351 785 1352 766 1352 737 1352 786 1353 745 1353 772 1353 787 1354 764 1354 779 1354 786 1355 762 1355 745 1355 787 1356 767 1356 764 1356 788 1357 767 1357 787 1357 789 1358 770 1358 741 1358 788 1359 768 1359 743 1359 789 1360 766 1360 785 1360 788 1361 743 1361 767 1361 789 1362 741 1362 766 1362 790 1363 765 1363 751 1363 791 1364 782 1364 771 1364 792 1365 773 1365 749 1365 790 1366 751 1366 777 1366 791 1367 783 1367 782 1367 793 1368 791 1368 771 1368 792 1369 749 1369 770 1369 794 1370 772 1370 774 1370 794 1371 774 1371 795 1371 796 1372 780 1372 775 1372 793 1373 771 1373 747 1373 796 1374 784 1374 780 1374 793 1375 747 1375 768 1375 797 1376 775 1376 752 1376 798 1377 799 1377 756 1377 800 1378 755 1378 801 1378 797 1379 752 1379 773 1379 798 1380 756 1380 769 1380 798 1381 769 1381 781 1381 800 1382 776 1382 755 1382 802 1383 779 1383 776 1383 803 1384 777 1384 762 1384 803 1385 762 1385 786 1385 802 1386 776 1386 800 1386 804 1387 761 1387 805 1387 804 1388 778 1388 761 1388 806 1389 787 1389 779 1389 807 1390 765 1390 790 1390 807 1391 781 1391 765 1391 806 1392 779 1392 802 1392 808 1393 760 1393 778 1393 808 1394 785 1394 760 1394 807 1395 798 1395 781 1395 809 1396 785 1396 808 1396 809 1397 789 1397 785 1397 810 1398 772 1398 794 1398 811 1399 788 1399 787 1399 810 1400 786 1400 772 1400 812 1401 770 1401 789 1401 812 1402 792 1402 770 1402 813 1403 800 1403 801 1403 814 1404 777 1404 803 1404 815 1405 768 1405 788 1405 814 1406 790 1406 777 1406 815 1407 788 1407 811 1407 816 1408 804 1408 805 1408 815 1409 793 1409 768 1409 817 1410 818 1410 819 1410 817 1411 795 1411 818 1411 820 1412 783 1412 791 1412 820 1413 793 1413 815 1413 820 1414 821 1414 783 1414 817 1415 794 1415 795 1415 820 1416 791 1416 793 1416 822 1417 797 1417 773 1417 823 1418 802 1418 800 1418 822 1419 773 1419 792 1419 824 1420 825 1420 799 1420 824 1421 798 1421 807 1421 824 1422 799 1422 798 1422 826 1423 797 1423 822 1423 826 1424 775 1424 797 1424 826 1425 827 1425 784 1425 828 1426 803 1426 786 1426 826 1427 784 1427 796 1427 826 1428 796 1428 775 1428 828 1429 786 1429 810 1429 829 1430 778 1430 804 1430 830 1431 802 1431 823 1431 830 1432 806 1432 802 1432 831 1433 811 1433 787 1433 831 1434 787 1434 806 1434 829 1435 808 1435 778 1435 829 1436 804 1436 816 1436 832 1437 807 1437 790 1437 832 1438 824 1438 807 1438 832 1439 790 1439 814 1439 833 1440 815 1440 811 1440 834 1441 809 1441 808 1441 835 1442 810 1442 794 1442 836 1443 821 1443 820 1443 836 1444 820 1444 815 1444 837 1445 812 1445 789 1445 835 1446 794 1446 817 1446 836 1447 815 1447 833 1447 837 1448 789 1448 809 1448 838 1449 803 1449 828 1449 839 1450 823 1450 800 1450 838 1451 814 1451 803 1451 839 1452 800 1452 813 1452 840 1453 822 1453 792 1453 840 1454 792 1454 812 1454 841 1455 829 1455 816 1455 842 1456 801 1456 843 1456 844 1457 817 1457 819 1457 844 1458 835 1458 817 1458 842 1459 813 1459 801 1459 845 1460 846 1460 825 1460 847 1461 823 1461 839 1461 845 1462 824 1462 832 1462 847 1463 830 1463 823 1463 845 1464 825 1464 824 1464 848 1465 827 1465 826 1465 848 1466 826 1466 822 1466 849 1467 831 1467 806 1467 850 1468 828 1468 810 1468 850 1469 810 1469 835 1469 851 1470 805 1470 852 1470 851 1471 816 1471 805 1471 853 1472 834 1472 808 1472 853 1473 829 1473 841 1473 849 1474 806 1474 830 1474 853 1475 808 1475 829 1475 854 1476 832 1476 814 1476 854 1477 814 1477 838 1477 855 1478 842 1478 843 1478 856 1479 809 1479 834 1479 857 1480 811 1480 831 1480 856 1481 837 1481 809 1481 857 1482 833 1482 811 1482 858 1483 835 1483 844 1483 858 1484 850 1484 835 1484 859 1485 821 1485 836 1485 860 1486 838 1486 828 1486 859 1487 833 1487 857 1487 859 1488 836 1488 833 1488 860 1489 828 1489 850 1489 859 1490 861 1490 821 1490 862 1491 851 1491 852 1491 860 1492 854 1492 838 1492 863 1493 847 1493 839 1493 864 1494 812 1494 837 1494 864 1495 840 1495 812 1495 865 1496 819 1496 866 1496 865 1497 844 1497 819 1497 867 1498 822 1498 840 1498 868 1499 869 1499 846 1499 870 1500 839 1500 813 1500 867 1501 848 1501 822 1501 870 1502 813 1502 842 1502 867 1503 827 1503 848 1503 868 1504 832 1504 854 1504 867 1505 840 1505 864 1505 868 1506 845 1506 832 1506 867 1507 871 1507 827 1507 868 1508 846 1508 845 1508 872 1509 860 1509 850 1509 873 1510 853 1510 841 1510 874 1511 849 1511 830 1511 874 1512 830 1512 847 1512 872 1513 850 1513 858 1513 875 1514 816 1514 851 1514 876 1515 865 1515 866 1515 875 1516 841 1516 816 1516 877 1517 857 1517 831 1517 876 1518 866 1518 878 1518 877 1519 831 1519 849 1519 879 1520 854 1520 860 1520 879 1521 868 1521 854 1521 880 1522 856 1522 834 1522 881 1523 870 1523 842 1523 880 1524 834 1524 853 1524 880 1525 853 1525 873 1525 882 1526 858 1526 844 1526 881 1527 842 1527 855 1527 883 1528 837 1528 856 1528 883 1529 864 1529 837 1529 882 1530 844 1530 865 1530 884 1531 859 1531 857 1531 884 1532 861 1532 859 1532 884 1533 857 1533 877 1533 885 1534 875 1534 851 1534 886 1535 879 1535 860 1535 887 1536 843 1536 888 1536 885 1537 851 1537 862 1537 886 1538 860 1538 872 1538 889 1539 882 1539 865 1539 887 1540 855 1540 843 1540 890 1541 864 1541 883 1541 889 1542 865 1542 876 1542 891 1543 847 1543 863 1543 890 1544 867 1544 864 1544 890 1545 871 1545 867 1545 891 1546 874 1546 847 1546 892 1547 862 1547 852 1547 893 1548 870 1548 881 1548 892 1549 852 1549 894 1549 895 1550 876 1550 878 1550 893 1551 863 1551 839 1551 896 1552 880 1552 873 1552 897 1553 898 1553 869 1553 897 1554 869 1554 868 1554 893 1555 839 1555 870 1555 897 1556 868 1556 879 1556 899 1557 900 1557 861 1557 899 1558 861 1558 884 1558 901 1559 872 1559 858 1559 902 1560 875 1560 885 1560 901 1561 858 1561 882 1561 899 1562 884 1562 877 1562 902 1563 873 1563 841 1563 902 1564 841 1564 875 1564 903 1565 849 1565 874 1565 901 1566 882 1566 889 1566 903 1567 877 1567 849 1567 904 1568 895 1568 878 1568 905 1569 890 1569 883 1569 905 1570 871 1570 890 1570 904 1571 878 1571 906 1571 905 1572 907 1572 871 1572 908 1573 883 1573 856 1573 908 1574 856 1574 880 1574 909 1575 879 1575 886 1575 910 1576 893 1576 881 1576 908 1577 880 1577 896 1577 909 1578 897 1578 879 1578 911 1579 902 1579 885 1579 912 1580 881 1580 855 1580 912 1581 855 1581 887 1581 913 1582 901 1582 889 1582 914 1583 876 1583 895 1583 915 1584 903 1584 874 1584 916 1585 862 1585 892 1585 915 1586 874 1586 891 1586 916 1587 885 1587 862 1587 914 1588 889 1588 876 1588 917 1589 908 1589 896 1589 914 1590 895 1590 904 1590 918 1591 863 1591 893 1591 919 1592 872 1592 901 1592 918 1593 891 1593 863 1593 919 1594 886 1594 872 1594 920 1595 899 1595 877 1595 920 1596 903 1596 915 1596 921 1597 896 1597 873 1597 921 1598 873 1598 902 1598 920 1599 900 1599 899 1599 920 1600 877 1600 903 1600 922 1601 904 1601 906 1601 923 1602 888 1602 924 1602 925 1603 883 1603 908 1603 925 1604 908 1604 917 1604 923 1605 887 1605 888 1605 925 1606 905 1606 883 1606 925 1607 907 1607 905 1607 926 1608 916 1608 892 1608 927 1609 914 1609 904 1609 928 1610 918 1610 893 1610 929 1611 930 1611 898 1611 929 1612 898 1612 897 1612 926 1613 894 1613 931 1613 929 1614 897 1614 909 1614 928 1615 893 1615 910 1615 926 1616 892 1616 894 1616 932 1617 919 1617 901 1617 933 1618 910 1618 881 1618 934 1619 921 1619 902 1619 932 1620 901 1620 913 1620 934 1621 902 1621 911 1621 933 1622 881 1622 912 1622 935 1623 913 1623 889 1623 936 1624 920 1624 915 1624 935 1625 889 1625 914 1625 936 1626 900 1626 920 1626 935 1627 914 1627 927 1627 936 1628 937 1628 900 1628 938 1629 911 1629 885 1629 939 1630 891 1630 918 1630 938 1631 885 1631 916 1631 939 1632 936 1632 915 1632 940 1633 907 1633 925 1633 939 1634 915 1634 891 1634 940 1635 925 1635 917 1635 941 1636 906 1636 942 1636 940 1637 943 1637 907 1637 941 1638 922 1638 906 1638 944 1639 909 1639 886 1639 945 1640 887 1640 923 1640 946 1641 917 1641 896 1641 944 1642 886 1642 919 1642 945 1643 912 1643 887 1643 946 1644 896 1644 921 1644 947 1645 939 1645 918 1645 948 1646 938 1646 916 1646 948 1647 916 1647 926 1647 949 1648 922 1648 941 1648 949 1649 904 1649 922 1649 949 1650 927 1650 904 1650 947 1651 918 1651 928 1651 950 1652 946 1652 921 1652 950 1653 921 1653 934 1653 951 1654 928 1654 910 1654 952 1655 935 1655 927 1655 953 1656 919 1656 932 1656 951 1657 910 1657 933 1657 954 1658 911 1658 938 1658 955 1659 939 1659 947 1659 953 1660 944 1660 919 1660 955 1661 937 1661 936 1661 954 1662 934 1662 911 1662 955 1663 936 1663 939 1663 956 1664 913 1664 935 1664 957 1665 924 1665 568 1665 958 1666 946 1666 950 1666 957 1667 923 1667 924 1667 958 1668 943 1668 940 1668 958 1669 917 1669 946 1669 956 1670 932 1670 913 1670 958 1671 940 1671 917 1671 957 1672 568 1672 567 1672 959 1673 933 1673 912 1673 960 1674 926 1674 931 1674 959 1675 912 1675 945 1675 961 1676 941 1676 942 1676 960 1677 931 1677 962 1677 963 1678 955 1678 947 1678 964 1679 938 1679 948 1679 965 1680 949 1680 941 1680 963 1681 937 1681 955 1681 966 1682 967 1682 930 1682 963 1683 968 1683 937 1683 964 1684 954 1684 938 1684 966 1685 930 1685 929 1685 969 1686 928 1686 951 1686 966 1687 909 1687 944 1687 970 1688 958 1688 950 1688 966 1689 929 1689 909 1689 969 1690 947 1690 928 1690 970 1691 943 1691 958 1691 966 1692 944 1692 953 1692 970 1693 971 1693 943 1693 972 1694 927 1694 949 1694 973 1695 950 1695 934 1695 973 1696 934 1696 954 1696 974 1697 923 1697 957 1697 972 1698 952 1698 927 1698 974 1699 945 1699 923 1699 973 1700 970 1700 950 1700 974 1701 957 1701 567 1701 972 1702 949 1702 965 1702 974 1703 567 1703 597 1703 974 1704 597 1704 606 1704 975 1705 926 1705 960 1705 976 1706 956 1706 935 1706 976 1707 935 1707 952 1707 977 1708 933 1708 959 1708 977 1709 951 1709 933 1709 975 1710 948 1710 926 1710 978 1711 967 1711 966 1711 978 1712 966 1712 953 1712 979 1713 973 1713 954 1713 980 1714 942 1714 981 1714 982 1715 947 1715 969 1715 982 1716 963 1716 947 1716 979 1717 954 1717 964 1717 982 1718 968 1718 963 1718 980 1719 961 1719 942 1719 983 1720 971 1720 970 1720 984 1721 959 1721 945 1721 983 1722 970 1722 973 1722 984 1723 945 1723 974 1723 985 1724 953 1724 932 1724 984 1725 974 1725 606 1725 986 1726 975 1726 960 1726 986 1727 960 1727 962 1727 985 1728 932 1728 956 1728 987 1729 969 1729 951 1729 987 1730 951 1730 977 1730 986 1731 962 1731 988 1731 989 1732 941 1732 961 1732 989 1733 965 1733 941 1733 990 1734 965 1734 989 1734 991 1735 964 1735 948 1735 992 1736 977 1736 959 1736 991 1737 948 1737 975 1737 992 1738 959 1738 984 1738 990 1739 972 1739 965 1739 992 1740 984 1740 606 1740 993 1741 973 1741 979 1741 992 1742 606 1742 615 1742 994 1743 972 1743 990 1743 993 1744 983 1744 973 1744 995 1745 969 1745 987 1745 995 1746 982 1746 969 1746 994 1747 952 1747 972 1747 995 1748 996 1748 968 1748 994 1749 976 1749 952 1749 997 1750 975 1750 986 1750 998 1751 985 1751 956 1751 995 1752 968 1752 982 1752 999 1753 977 1753 992 1753 999 1754 987 1754 977 1754 998 1755 956 1755 976 1755 999 1756 992 1756 615 1756 999 1757 615 1757 627 1757 999 1758 627 1758 629 1758 1000 1759 979 1759 964 1759 1001 1760 987 1760 999 1760 1001 1761 999 1761 629 1761 1000 1762 964 1762 991 1762 1002 1763 980 1763 981 1763 1001 1764 1003 1764 996 1764 1001 1765 645 1765 1003 1765 1004 1766 967 1766 978 1766 1001 1767 995 1767 987 1767 1004 1768 978 1768 953 1768 1001 1769 996 1769 995 1769 1004 1770 985 1770 998 1770 1001 1771 629 1771 645 1771 1005 1772 986 1772 988 1772 1004 1773 1006 1773 967 1773 1004 1774 953 1774 985 1774 1007 1775 989 1775 961 1775 1005 1776 1008 1776 1009 1776 1007 1777 961 1777 980 1777 1005 1778 988 1778 1008 1778 1010 1779 971 1779 983 1779 1010 1780 983 1780 993 1780 1010 1781 1011 1781 971 1781 1012 1782 989 1782 1007 1782 1013 1783 991 1783 975 1783 1013 1784 975 1784 997 1784 1012 1785 990 1785 989 1785 1014 1786 979 1786 1000 1786 1014 1787 993 1787 979 1787 1015 1788 994 1788 990 1788 1014 1789 1010 1789 993 1789 1016 1790 1004 1790 998 1790 1016 1791 1006 1791 1004 1791 1017 1792 976 1792 994 1792 1017 1793 994 1793 1015 1793 1018 1794 997 1794 986 1794 1018 1795 986 1795 1005 1795 1017 1796 998 1796 976 1796 1019 1797 1002 1797 981 1797 1019 1798 981 1798 1020 1798 1021 1799 991 1799 1013 1799 1021 1800 1000 1800 991 1800 1022 1801 1007 1801 980 1801 1023 1802 1005 1802 1009 1802 1022 1803 980 1803 1002 1803 1024 1804 1012 1804 1007 1804 1023 1805 1018 1805 1005 1805 1025 1806 1026 1806 1011 1806 1025 1807 1011 1807 1010 1807 1025 1808 1010 1808 1014 1808 1024 1809 1007 1809 1022 1809 1027 1810 990 1810 1012 1810 1028 1811 997 1811 1018 1811 1028 1812 1013 1812 997 1812 1027 1813 1015 1813 990 1813 1029 1814 1014 1814 1000 1814 1029 1815 1000 1815 1021 1815 1030 1816 1019 1816 1020 1816 1031 1817 1017 1817 1015 1817 1032 1818 1016 1818 998 1818 1033 1819 1028 1819 1018 1819 1032 1820 1034 1820 1006 1820 1033 1821 1018 1821 1023 1821 1032 1822 1006 1822 1016 1822 1035 1823 1029 1823 1021 1823 1032 1824 998 1824 1017 1824 1032 1825 1017 1825 1031 1825 1036 1826 1002 1826 1019 1826 1035 1827 1021 1827 1013 1827 1035 1828 1013 1828 1028 1828 1036 1829 1022 1829 1002 1829 1037 1830 1038 1830 1039 1830 1037 1831 1009 1831 1038 1831 1040 1832 1024 1832 1022 1832 1037 1833 1023 1833 1009 1833 1041 1834 1042 1834 1026 1834 1040 1835 1022 1835 1036 1835 1041 1836 1026 1836 1025 1836 1041 1837 1014 1837 1029 1837 1043 1838 1027 1838 1012 1838 1041 1839 1025 1839 1014 1839 1043 1840 1012 1840 1024 1840 1044 1841 1028 1841 1033 1841 1044 1842 1035 1842 1028 1842 1045 1843 1031 1843 1015 1843 1045 1844 1015 1844 1027 1844 1046 1845 1041 1845 1029 1845 1046 1846 1029 1846 1035 1846 208 1847 1036 1847 1019 1847 208 1848 1019 1848 1030 1848 1047 1849 1023 1849 1037 1849 1048 1850 1034 1850 1032 1850 1047 1851 1033 1851 1023 1851 1048 1852 1032 1852 1031 1852 1048 1853 1031 1853 1045 1853 1049 1854 1035 1854 1044 1854 1050 1855 1020 1855 1051 1855 1049 1856 1046 1856 1035 1856 1050 1857 1030 1857 1020 1857 1052 1858 1037 1858 1039 1858 1052 1859 1047 1859 1037 1859 1053 1860 1040 1860 1036 1860 1054 1861 1055 1861 1042 1861 1054 1862 1042 1862 1041 1862 1054 1863 1041 1863 1046 1863 223 1864 1024 1864 1040 1864 223 1865 1043 1865 1024 1865 1056 1866 1044 1866 1033 1866 1056 1867 1033 1867 1047 1867 234 1868 1050 1868 1051 1868 213 1869 1052 1869 1039 1869 1057 1870 1027 1870 1043 1870 1057 1871 1045 1871 1027 1871 213 1872 1039 1872 1058 1872 242 1873 1046 1873 1049 1873 1059 1874 217 1874 1034 1874 1059 1875 1034 1875 1048 1875 242 1876 1054 1876 1046 1876 1059 1877 1048 1877 1045 1877 1059 1878 1045 1878 1057 1878 210 1879 1036 1879 208 1879 1060 1880 1056 1880 1047 1880 210 1881 1053 1881 1036 1881 1060 1882 1047 1882 1052 1882 225 1883 1044 1883 1056 1883 209 1884 208 1884 1030 1884 225 1885 1049 1885 1044 1885 209 1886 1030 1886 1050 1886 212 1887 1052 1887 213 1887 228 1888 223 1888 1040 1888 228 1889 1040 1889 1053 1889 212 1890 1060 1890 1052 1890 219 1891 213 1891 1058 1891 221 1892 1043 1892 223 1892 221 1893 1057 1893 1043 1893 241 1894 239 1894 1055 1894 214 1895 209 1895 1050 1895 241 1896 1054 1896 242 1896 241 1897 1055 1897 1054 1897 226 1898 1056 1898 1060 1898 214 1899 1050 1899 234 1899 218 1900 1057 1900 221 1900 226 1901 225 1901 1056 1901 226 1902 1060 1902 212 1902 218 1903 217 1903 1059 1903 218 1904 1059 1904 1057 1904 231 1905 219 1905 1058 1905 236 1906 1051 1906 249 1906 231 1907 1058 1907 232 1907 236 1908 234 1908 1051 1908 243 1909 228 1909 1053 1909 227 1910 242 1910 1049 1910 227 1911 1049 1911 225 1911 243 1912 1053 1912 210 1912 215 1913 226 1913 212 1913 1061 1914 1062 1914 1063 1914 1064 1915 1065 1915 1066 1915 1062 1916 1067 1916 1063 1916 1068 1917 1069 1917 1063 1917 1065 1918 1070 1918 1066 1918 1067 1919 1068 1919 1063 1919 1071 1920 1064 1920 1066 1920 1072 1921 1073 1921 1074 1921 1075 1922 1076 1922 1077 1922 1076 1923 1078 1923 1077 1923 1073 1924 1079 1924 1074 1924 1080 1925 1081 1925 1082 1925 1083 1926 1080 1926 1082 1926 1084 1927 1061 1927 1085 1927 1063 1928 1069 1928 1085 1928 1070 1929 1083 1929 1082 1929 1061 1930 1063 1930 1085 1930 1078 1931 1071 1931 1086 1931 1087 1932 1084 1932 1088 1932 1077 1933 1078 1933 1086 1933 1084 1934 1085 1934 1088 1934 1089 1935 1090 1935 1091 1935 1092 1936 1093 1936 1094 1936 1090 1937 1072 1937 1091 1937 1095 1938 1087 1938 1096 1938 1075 1939 1077 1939 1097 1939 1094 1940 1093 1940 1097 1940 1093 1941 1075 1941 1097 1941 1087 1942 1088 1942 1096 1942 1098 1943 1099 1943 1100 1943 1074 1944 1079 1944 1101 1944 1079 1945 1095 1945 1101 1945 1085 1946 1069 1946 1102 1946 1088 1947 1085 1947 1102 1947 1071 1948 1066 1948 1103 1948 1069 1949 1104 1949 1102 1949 1082 1950 1081 1950 1105 1950 1066 1951 1070 1951 1105 1951 1070 1952 1082 1952 1105 1952 1103 1953 1066 1953 1105 1953 1091 1954 1072 1954 1106 1954 1072 1955 1074 1955 1106 1955 1099 1956 1092 1956 1107 1956 1092 1957 1094 1957 1107 1957 1096 1958 1088 1958 1108 1958 1109 1959 1110 1959 1111 1959 1088 1960 1102 1960 1108 1960 1097 1961 1077 1961 1112 1961 1077 1962 1086 1962 1112 1962 1113 1963 1089 1963 1114 1963 1115 1964 1113 1964 1114 1964 1086 1965 1071 1965 1116 1965 1089 1966 1091 1966 1114 1966 1071 1967 1103 1967 1116 1967 1095 1968 1096 1968 1117 1968 1094 1969 1097 1969 1118 1969 1101 1970 1095 1970 1117 1970 1106 1971 1074 1971 1119 1971 1097 1972 1112 1972 1120 1972 1118 1973 1097 1973 1120 1973 1081 1974 1121 1974 1122 1974 1074 1975 1101 1975 1119 1975 1105 1976 1081 1976 1122 1976 1103 1977 1105 1977 1122 1977 1102 1978 1104 1978 1123 1978 1108 1979 1102 1979 1123 1979 1104 1980 1124 1980 1123 1980 1091 1981 1106 1981 1125 1981 1100 1982 1099 1982 1126 1982 1099 1983 1107 1983 1126 1983 1114 1984 1091 1984 1125 1984 1117 1985 1096 1985 1127 1985 1107 1986 1094 1986 1128 1986 1094 1987 1118 1987 1128 1987 1096 1988 1108 1988 1127 1988 1129 1989 1098 1989 1130 1989 1131 1990 1129 1990 1130 1990 1114 1991 1125 1991 1132 1991 1098 1992 1100 1992 1130 1992 1115 1993 1114 1993 1132 1993 1119 1994 1101 1994 1133 1994 1101 1995 1117 1995 1133 1995 1112 1996 1086 1996 1134 1996 1086 1997 1116 1997 1134 1997 1103 1998 1122 1998 1135 1998 1122 1999 1121 1999 1135 1999 1106 2000 1119 2000 1136 2000 1134 2001 1116 2001 1135 2001 1116 2002 1103 2002 1135 2002 1128 2003 1118 2003 1137 2003 1125 2004 1106 2004 1136 2004 1118 2005 1120 2005 1137 2005 1127 2006 1108 2006 1138 2006 1108 2007 1123 2007 1138 2007 1123 2008 1124 2008 1138 2008 1112 2009 1134 2009 1139 2009 1137 2010 1120 2010 1139 2010 1124 2011 1140 2011 1138 2011 1120 2012 1112 2012 1139 2012 1125 2013 1136 2013 1141 2013 1126 2014 1107 2014 1142 2014 1132 2015 1125 2015 1141 2015 1107 2016 1128 2016 1142 2016 1117 2017 1127 2017 1143 2017 1128 2018 1137 2018 1144 2018 1133 2019 1117 2019 1143 2019 1142 2020 1128 2020 1144 2020 1121 2021 1145 2021 1146 2021 1115 2022 1132 2022 1147 2022 1135 2023 1121 2023 1146 2023 1148 2024 1115 2024 1147 2024 1134 2025 1135 2025 1146 2025 1100 2026 1126 2026 1149 2026 1119 2027 1133 2027 1150 2027 1130 2028 1100 2028 1149 2028 1136 2029 1119 2029 1150 2029 1139 2030 1134 2030 1151 2030 1134 2031 1146 2031 1151 2031 1146 2032 1145 2032 1151 2032 1141 2033 1136 2033 1152 2033 1136 2034 1150 2034 1152 2034 1139 2035 1151 2035 1153 2035 1137 2036 1139 2036 1153 2036 1131 2037 1130 2037 1154 2037 1143 2038 1127 2038 1155 2038 1127 2039 1138 2039 1155 2039 1138 2040 1140 2040 1155 2040 1130 2041 1149 2041 1154 2041 1140 2042 1156 2042 1155 2042 1147 2043 1132 2043 1157 2043 1142 2044 1144 2044 1158 2044 1132 2045 1141 2045 1157 2045 1144 2046 1137 2046 1159 2046 1137 2047 1153 2047 1159 2047 1150 2048 1133 2048 1160 2048 1133 2049 1143 2049 1160 2049 1149 2050 1126 2050 1161 2050 1126 2051 1142 2051 1161 2051 1162 2052 1148 2052 1163 2052 1145 2053 1164 2053 1165 2053 1151 2054 1145 2054 1165 2054 1153 2055 1151 2055 1165 2055 1148 2056 1147 2056 1163 2056 1152 2057 1150 2057 1166 2057 1150 2058 1160 2058 1166 2058 1154 2059 1149 2059 1167 2059 1149 2060 1161 2060 1167 2060 1165 2061 1164 2061 1168 2061 1157 2062 1141 2062 1169 2062 1159 2063 1153 2063 1168 2063 1153 2064 1165 2064 1168 2064 1141 2065 1152 2065 1169 2065 1158 2066 1144 2066 1170 2066 1144 2067 1159 2067 1170 2067 1143 2068 1155 2068 1171 2068 1156 2069 1172 2069 1171 2069 1160 2070 1143 2070 1171 2070 1173 2071 1131 2071 1174 2071 1155 2072 1156 2072 1171 2072 1131 2073 1154 2073 1174 2073 1147 2074 1157 2074 1175 2074 1163 2075 1147 2075 1175 2075 1142 2076 1158 2076 1176 2076 1166 2077 1160 2077 1177 2077 1161 2078 1142 2078 1176 2078 1160 2079 1171 2079 1177 2079 1162 2080 1163 2080 1178 2080 1179 2081 1162 2081 1178 2081 1167 2082 1161 2082 1180 2082 1181 2083 1179 2083 1178 2083 1182 2084 1181 2084 1178 2084 1161 2085 1176 2085 1180 2085 1164 2086 1183 2086 1184 2086 1168 2087 1164 2087 1184 2087 1159 2088 1168 2088 1184 2088 1170 2089 1159 2089 1184 2089 1152 2090 1166 2090 1185 2090 1169 2091 1152 2091 1185 2091 1154 2092 1167 2092 1186 2092 1174 2093 1154 2093 1186 2093 1187 2094 1173 2094 1188 2094 1175 2095 1157 2095 1189 2095 1190 2096 1187 2096 1188 2096 1157 2097 1169 2097 1189 2097 1173 2098 1174 2098 1188 2098 1172 2099 1191 2099 1192 2099 1177 2100 1171 2100 1192 2100 1171 2101 1172 2101 1192 2101 1163 2102 1175 2102 1193 2102 1176 2103 1158 2103 1194 2103 1182 2104 1178 2104 1193 2104 1158 2105 1170 2105 1194 2105 1195 2106 1182 2106 1193 2106 1178 2107 1163 2107 1193 2107 1166 2108 1177 2108 1196 2108 1176 2109 1194 2109 1197 2109 1180 2110 1176 2110 1197 2110 1185 2111 1166 2111 1196 2111 1189 2112 1169 2112 1198 2112 1169 2113 1185 2113 1198 2113 1167 2114 1180 2114 1199 2114 1186 2115 1167 2115 1199 2115 1175 2116 1189 2116 1200 2116 1183 2117 1201 2117 1202 2117 1195 2118 1193 2118 1200 2118 1184 2119 1183 2119 1202 2119 1203 2120 1195 2120 1200 2120 1170 2121 1184 2121 1202 2121 1204 2122 1203 2122 1200 2122 1194 2123 1170 2123 1202 2123 1193 2124 1175 2124 1200 2124 1177 2125 1192 2125 1205 2125 1191 2126 1206 2126 1205 2126 1174 2127 1186 2127 1207 2127 1192 2128 1191 2128 1205 2128 1188 2129 1174 2129 1207 2129 1196 2130 1177 2130 1205 2130 1198 2131 1185 2131 1208 2131 1185 2132 1196 2132 1208 2132 1190 2133 1188 2133 1209 2133 1188 2134 1207 2134 1209 2134 1198 2135 1208 2135 1210 2135 1200 2136 1189 2136 1210 2136 1197 2137 1194 2137 1211 2137 1204 2138 1200 2138 1210 2138 1189 2139 1198 2139 1210 2139 1194 2140 1202 2140 1211 2140 1205 2141 1206 2141 1212 2141 1196 2142 1205 2142 1212 2142 1206 2143 1213 2143 1212 2143 1180 2144 1197 2144 1214 2144 1208 2145 1196 2145 1212 2145 1199 2146 1180 2146 1214 2146 1210 2147 1208 2147 1215 2147 1208 2148 1212 2148 1215 2148 1204 2149 1210 2149 1215 2149 1216 2150 1204 2150 1215 2150 1109 2151 1216 2151 1215 2151 1217 2152 1109 2152 1218 2152 1109 2153 1215 2153 1218 2153 1186 2154 1199 2154 1219 2154 1212 2155 1213 2155 1218 2155 1207 2156 1186 2156 1219 2156 1215 2157 1212 2157 1218 2157 1213 2158 1217 2158 1218 2158 1211 2159 1202 2159 1220 2159 1201 2160 1221 2160 1220 2160 1202 2161 1201 2161 1220 2161 1209 2162 1207 2162 1222 2162 1207 2163 1219 2163 1222 2163 1223 2164 1190 2164 1224 2164 1190 2165 1209 2165 1224 2165 1197 2166 1211 2166 1225 2166 1214 2167 1197 2167 1225 2167 1199 2168 1214 2168 1226 2168 1219 2169 1199 2169 1226 2169 1222 2170 1219 2170 1227 2170 1219 2171 1226 2171 1227 2171 1221 2172 1228 2172 1229 2172 1211 2173 1220 2173 1229 2173 1220 2174 1221 2174 1229 2174 1225 2175 1211 2175 1229 2175 1209 2176 1222 2176 1230 2176 1224 2177 1209 2177 1230 2177 1214 2178 1225 2178 1231 2178 1226 2179 1214 2179 1231 2179 1232 2180 1223 2180 1233 2180 1223 2181 1224 2181 1233 2181 1226 2182 1231 2182 1234 2182 1227 2183 1226 2183 1234 2183 1222 2184 1227 2184 1235 2184 1230 2185 1222 2185 1235 2185 1228 2186 1236 2186 1237 2186 1225 2187 1229 2187 1237 2187 1231 2188 1225 2188 1237 2188 1229 2189 1228 2189 1237 2189 1224 2190 1230 2190 1238 2190 1233 2191 1224 2191 1238 2191 1234 2192 1231 2192 1239 2192 1231 2193 1237 2193 1239 2193 1240 2194 1232 2194 1241 2194 1232 2195 1233 2195 1241 2195 1227 2196 1234 2196 1242 2196 1235 2197 1227 2197 1242 2197 1230 2198 1235 2198 1243 2198 1238 2199 1230 2199 1243 2199 1236 2200 1244 2200 1245 2200 1239 2201 1237 2201 1245 2201 1237 2202 1236 2202 1245 2202 1233 2203 1238 2203 1246 2203 1241 2204 1233 2204 1246 2204 1234 2205 1239 2205 1247 2205 1242 2206 1234 2206 1247 2206 1248 2207 1240 2207 1249 2207 1240 2208 1241 2208 1249 2208 1235 2209 1242 2209 1250 2209 1243 2210 1235 2210 1250 2210 1246 2211 1238 2211 1251 2211 1238 2212 1243 2212 1251 2212 1243 2213 1250 2213 1251 2213 1244 2214 1252 2214 1253 2214 1245 2215 1244 2215 1253 2215 1239 2216 1245 2216 1253 2216 1247 2217 1239 2217 1253 2217 1241 2218 1246 2218 1254 2218 1249 2219 1241 2219 1254 2219 1255 2220 1248 2220 1256 2220 1248 2221 1249 2221 1256 2221 1250 2222 1242 2222 1257 2222 1242 2223 1247 2223 1257 2223 1251 2224 1250 2224 1258 2224 1254 2225 1246 2225 1259 2225 1246 2226 1251 2226 1259 2226 1252 2227 1260 2227 1261 2227 1253 2228 1252 2228 1261 2228 1247 2229 1253 2229 1261 2229 1257 2230 1247 2230 1261 2230 1249 2231 1254 2231 1262 2231 1256 2232 1249 2232 1262 2232 1263 2233 1255 2233 1264 2233 1255 2234 1256 2234 1264 2234 1250 2235 1257 2235 1265 2235 1258 2236 1250 2236 1265 2236 1251 2237 1258 2237 1266 2237 1259 2238 1251 2238 1266 2238 1254 2239 1259 2239 1267 2239 1262 2240 1254 2240 1267 2240 1257 2241 1261 2241 1268 2241 1261 2242 1260 2242 1268 2242 1265 2243 1257 2243 1268 2243 1260 2244 1269 2244 1268 2244 1264 2245 1256 2245 1270 2245 1256 2246 1262 2246 1270 2246 1271 2247 1263 2247 1272 2247 1263 2248 1264 2248 1272 2248 1258 2249 1265 2249 1273 2249 1266 2250 1258 2250 1273 2250 1267 2251 1259 2251 1274 2251 1259 2252 1266 2252 1274 2252 1262 2253 1267 2253 1275 2253 1270 2254 1262 2254 1275 2254 1273 2255 1265 2255 1276 2255 1265 2256 1268 2256 1276 2256 1268 2257 1269 2257 1276 2257 1269 2258 1277 2258 1276 2258 1272 2259 1264 2259 1278 2259 1264 2260 1270 2260 1278 2260 1271 2261 1272 2261 1279 2261 1280 2262 1271 2262 1279 2262 1266 2263 1273 2263 1281 2263 1274 2264 1266 2264 1281 2264 1275 2265 1267 2265 1282 2265 1267 2266 1274 2266 1282 2266 1270 2267 1275 2267 1283 2267 1278 2268 1270 2268 1283 2268 1273 2269 1276 2269 1284 2269 1281 2270 1273 2270 1284 2270 1276 2271 1277 2271 1284 2271 1277 2272 1285 2272 1284 2272 1279 2273 1272 2273 1286 2273 1272 2274 1278 2274 1286 2274 1280 2275 1279 2275 1287 2275 1288 2276 1280 2276 1287 2276 1274 2277 1281 2277 1289 2277 1282 2278 1274 2278 1289 2278 1283 2279 1275 2279 1290 2279 1275 2280 1282 2280 1290 2280 1278 2281 1283 2281 1291 2281 1286 2282 1278 2282 1291 2282 1281 2283 1284 2283 1292 2283 1289 2284 1281 2284 1292 2284 1284 2285 1285 2285 1292 2285 1285 2286 1293 2286 1292 2286 1279 2287 1286 2287 1294 2287 1287 2288 1279 2288 1294 2288 1288 2289 1287 2289 1295 2289 1296 2290 1288 2290 1295 2290 1287 2291 1294 2291 1295 2291 1282 2292 1289 2292 1297 2292 1290 2293 1282 2293 1297 2293 1283 2294 1290 2294 1298 2294 1291 2295 1283 2295 1298 2295 1294 2296 1286 2296 1299 2296 1286 2297 1291 2297 1299 2297 1289 2298 1292 2298 1300 2298 1297 2299 1289 2299 1300 2299 1292 2300 1293 2300 1300 2300 1293 2301 1301 2301 1300 2301 1294 2302 1299 2302 1302 2302 1295 2303 1294 2303 1302 2303 1296 2304 1295 2304 1303 2304 1304 2305 1296 2305 1303 2305 1109 2306 1217 2306 1110 2306 1290 2307 1297 2307 1305 2307 1298 2308 1290 2308 1305 2308 1306 2309 1181 2309 1307 2309 1181 2310 1182 2310 1307 2310 1299 2311 1291 2311 1308 2311 1291 2312 1298 2312 1308 2312 1182 2313 1195 2313 1309 2313 1299 2314 1308 2314 1310 2314 1302 2315 1299 2315 1310 2315 1307 2316 1182 2316 1309 2316 1311 2317 1306 2317 1312 2317 1297 2318 1300 2318 1313 2318 1305 2319 1297 2319 1313 2319 1306 2320 1307 2320 1312 2320 1300 2321 1301 2321 1313 2321 1301 2322 1314 2322 1313 2322 1309 2323 1195 2323 1315 2323 1195 2324 1203 2324 1315 2324 1303 2325 1295 2325 1316 2325 1295 2326 1302 2326 1316 2326 1307 2327 1309 2327 1317 2327 1304 2328 1303 2328 1318 2328 1312 2329 1307 2329 1317 2329 1319 2330 1304 2330 1318 2330 1320 2331 1311 2331 1321 2331 1308 2332 1298 2332 1322 2332 1298 2333 1305 2333 1322 2333 1311 2334 1312 2334 1321 2334 1310 2335 1308 2335 1323 2335 1203 2336 1204 2336 1324 2336 1308 2337 1322 2337 1323 2337 1315 2338 1203 2338 1324 2338 1316 2339 1302 2339 1325 2339 1302 2340 1310 2340 1325 2340 1309 2341 1315 2341 1326 2341 1317 2342 1309 2342 1326 2342 1305 2343 1313 2343 1327 2343 1313 2344 1314 2344 1327 2344 1312 2345 1317 2345 1328 2345 1321 2346 1312 2346 1328 2346 1322 2347 1305 2347 1327 2347 1314 2348 1329 2348 1327 2348 1303 2349 1316 2349 1330 2349 1331 2350 1320 2350 1332 2350 1320 2351 1321 2351 1332 2351 1318 2352 1303 2352 1330 2352 1319 2353 1318 2353 1333 2353 1334 2354 1319 2354 1333 2354 1204 2355 1216 2355 1335 2355 1324 2356 1204 2356 1335 2356 1323 2357 1322 2357 1336 2357 1322 2358 1327 2358 1336 2358 1326 2359 1315 2359 1337 2359 1310 2360 1323 2360 1338 2360 1315 2361 1324 2361 1337 2361 1325 2362 1310 2362 1338 2362 1317 2363 1326 2363 1339 2363 1316 2364 1325 2364 1340 2364 1328 2365 1317 2365 1339 2365 1335 2366 1216 2366 1341 2366 1330 2367 1316 2367 1340 2367 1216 2368 1109 2368 1341 2368 1109 2369 1111 2369 1341 2369 1327 2370 1329 2370 1342 2370 1336 2371 1327 2371 1342 2371 1332 2372 1321 2372 1343 2372 1329 2373 1344 2373 1342 2373 1318 2374 1330 2374 1345 2374 1321 2375 1328 2375 1343 2375 1333 2376 1318 2376 1345 2376 1346 2377 1331 2377 1347 2377 1331 2378 1332 2378 1347 2378 1332 2379 1343 2379 1347 2379 1334 2380 1333 2380 1348 2380 1324 2381 1335 2381 1349 2381 1350 2382 1334 2382 1348 2382 1338 2383 1323 2383 1351 2383 1323 2384 1336 2384 1351 2384 1337 2385 1324 2385 1349 2385 1339 2386 1326 2386 1352 2386 1325 2387 1338 2387 1353 2387 1326 2388 1337 2388 1352 2388 1340 2389 1325 2389 1353 2389 1328 2390 1339 2390 1354 2390 1343 2391 1328 2391 1354 2391 1341 2392 1111 2392 1355 2392 1350 2393 1348 2393 1356 2393 1111 2394 1357 2394 1355 2394 1335 2395 1341 2395 1355 2395 1349 2396 1335 2396 1355 2396 1345 2397 1330 2397 1358 2397 1330 2398 1340 2398 1358 2398 1347 2399 1343 2399 1359 2399 1343 2400 1354 2400 1359 2400 1351 2401 1336 2401 1360 2401 1361 2402 1346 2402 1362 2402 1336 2403 1342 2403 1360 2403 1342 2404 1344 2404 1360 2404 1344 2405 1363 2405 1360 2405 1346 2406 1347 2406 1362 2406 1333 2407 1345 2407 1364 2407 1348 2408 1333 2408 1364 2408 1337 2409 1349 2409 1365 2409 1352 2410 1337 2410 1365 2410 1349 2411 1355 2411 1365 2411 1366 2412 1350 2412 1367 2412 1350 2413 1356 2413 1367 2413 1354 2414 1339 2414 1368 2414 1353 2415 1338 2415 1369 2415 1339 2416 1352 2416 1368 2416 1338 2417 1351 2417 1369 2417 1354 2418 1368 2418 1370 2418 1348 2419 1364 2419 1371 2419 1359 2420 1354 2420 1370 2420 1356 2421 1348 2421 1371 2421 1357 2422 1372 2422 1373 2422 1365 2423 1355 2423 1373 2423 1367 2424 1356 2424 1371 2424 1355 2425 1357 2425 1373 2425 1358 2426 1340 2426 1374 2426 1362 2427 1347 2427 1375 2427 1340 2428 1353 2428 1374 2428 1347 2429 1359 2429 1375 2429 1376 2430 1361 2430 1377 2430 1366 2431 1367 2431 1378 2431 1361 2432 1362 2432 1377 2432 1362 2433 1375 2433 1377 2433 1345 2434 1358 2434 1379 2434 1364 2435 1345 2435 1379 2435 1368 2436 1352 2436 1380 2436 1352 2437 1365 2437 1380 2437 1351 2438 1360 2438 1381 2438 1369 2439 1351 2439 1381 2439 1360 2440 1363 2440 1381 2440 1368 2441 1380 2441 1382 2441 1370 2442 1368 2442 1382 2442 1363 2443 1383 2443 1381 2443 1367 2444 1371 2444 1384 2444 1378 2445 1367 2445 1384 2445 1375 2446 1359 2446 1385 2446 1359 2447 1370 2447 1385 2447 1371 2448 1364 2448 1386 2448 1364 2449 1379 2449 1386 2449 1372 2450 1387 2450 1388 2450 1380 2451 1365 2451 1388 2451 1384 2452 1371 2452 1386 2452 1373 2453 1372 2453 1388 2453 1365 2454 1373 2454 1388 2454 1389 2455 1366 2455 1390 2455 1377 2456 1375 2456 1391 2456 1366 2457 1378 2457 1390 2457 1375 2458 1385 2458 1391 2458 1376 2459 1377 2459 1392 2459 1393 2460 1376 2460 1392 2460 1374 2461 1353 2461 1394 2461 1353 2462 1369 2462 1394 2462 1380 2463 1388 2463 1395 2463 1378 2464 1384 2464 1396 2464 1382 2465 1380 2465 1395 2465 1385 2466 1370 2466 1397 2466 1358 2467 1374 2467 1398 2467 1379 2468 1358 2468 1398 2468 1370 2469 1382 2469 1397 2469 1386 2470 1379 2470 1398 2470 1389 2471 1390 2471 1399 2471 1385 2472 1397 2472 1400 2472 1391 2473 1385 2473 1400 2473 1387 2474 1401 2474 1402 2474 1396 2475 1384 2475 1403 2475 1388 2476 1387 2476 1402 2476 1395 2477 1388 2477 1402 2477 1392 2478 1377 2478 1404 2478 1384 2479 1386 2479 1403 2479 1386 2480 1398 2480 1405 2480 1377 2481 1391 2481 1404 2481 1403 2482 1386 2482 1405 2482 1406 2483 1393 2483 1407 2483 1369 2484 1381 2484 1408 2484 1392 2485 1404 2485 1407 2485 1394 2486 1369 2486 1408 2486 1393 2487 1392 2487 1407 2487 1383 2488 1409 2488 1408 2488 1381 2489 1383 2489 1408 2489 1378 2490 1396 2490 1410 2490 1382 2491 1395 2491 1411 2491 1399 2492 1390 2492 1410 2492 1397 2493 1382 2493 1411 2493 1390 2494 1378 2494 1410 2494 1397 2495 1411 2495 1412 2495 1396 2496 1403 2496 1413 2496 1400 2497 1397 2497 1412 2497 1391 2498 1400 2498 1414 2498 1415 2499 1389 2499 1416 2499 1404 2500 1391 2500 1414 2500 1389 2501 1399 2501 1416 2501 1411 2502 1395 2502 1417 2502 1398 2503 1374 2503 1418 2503 1401 2504 1419 2504 1417 2504 1374 2505 1394 2505 1418 2505 1402 2506 1401 2506 1417 2506 1395 2507 1402 2507 1417 2507 1416 2508 1399 2508 1420 2508 1399 2509 1410 2509 1420 2509 1404 2510 1414 2510 1421 2510 1407 2511 1404 2511 1421 2511 1422 2512 1406 2512 1423 2512 1413 2513 1403 2513 1424 2513 1403 2514 1405 2514 1424 2514 1406 2515 1407 2515 1423 2515 1424 2516 1405 2516 1425 2516 1398 2517 1418 2517 1425 2517 1412 2518 1411 2518 1426 2518 1405 2519 1398 2519 1425 2519 1415 2520 1416 2520 1427 2520 1411 2521 1417 2521 1426 2521 1410 2522 1396 2522 1428 2522 1414 2523 1400 2523 1429 2523 1396 2524 1413 2524 1428 2524 1400 2525 1412 2525 1429 2525 1420 2526 1410 2526 1428 2526 1422 2527 1423 2527 1430 2527 1413 2528 1424 2528 1431 2528 1414 2529 1429 2529 1432 2529 1418 2530 1394 2530 1433 2530 1394 2531 1408 2531 1433 2531 1408 2532 1409 2532 1433 2532 1421 2533 1414 2533 1432 2533 1419 2534 1434 2534 1435 2534 1409 2535 1436 2535 1433 2535 1426 2536 1417 2536 1435 2536 1417 2537 1419 2537 1435 2537 1430 2538 1423 2538 1437 2538 1423 2539 1407 2539 1437 2539 1416 2540 1420 2540 1438 2540 1407 2541 1421 2541 1437 2541 1420 2542 1428 2542 1439 2542 1438 2543 1420 2543 1439 2543 1440 2544 1422 2544 1441 2544 1415 2545 1427 2545 1442 2545 1422 2546 1430 2546 1441 2546 1443 2547 1415 2547 1442 2547 1412 2548 1426 2548 1444 2548 1418 2549 1433 2549 1445 2549 1425 2550 1418 2550 1445 2550 1433 2551 1436 2551 1445 2551 1429 2552 1412 2552 1444 2552 1436 2553 1446 2553 1445 2553 1424 2554 1425 2554 1447 2554 1425 2555 1445 2555 1447 2555 1430 2556 1437 2556 1448 2556 1427 2557 1416 2557 1449 2557 1416 2558 1438 2558 1449 2558 1429 2559 1444 2559 1450 2559 1442 2560 1427 2560 1449 2560 1432 2561 1429 2561 1450 2561 1428 2562 1413 2562 1451 2562 1439 2563 1428 2563 1451 2563 1413 2564 1431 2564 1451 2564 1440 2565 1441 2565 1452 2565 1431 2566 1424 2566 1453 2566 1421 2567 1432 2567 1454 2567 1424 2568 1447 2568 1453 2568 1448 2569 1437 2569 1454 2569 1437 2570 1421 2570 1454 2570 1435 2571 1434 2571 1455 2571 1443 2572 1442 2572 1456 2572 1434 2573 1457 2573 1455 2573 1444 2574 1426 2574 1455 2574 1438 2575 1439 2575 1458 2575 1426 2576 1435 2576 1455 2576 1441 2577 1430 2577 1459 2577 1430 2578 1448 2578 1459 2578 1439 2579 1451 2579 1460 2579 1452 2580 1441 2580 1459 2580 1458 2581 1439 2581 1460 2581 1453 2582 1447 2582 1461 2582 1448 2583 1454 2583 1462 2583 1445 2584 1446 2584 1461 2584 1447 2585 1445 2585 1461 2585 1463 2586 1440 2586 1464 2586 1440 2587 1452 2587 1464 2587 1442 2588 1449 2588 1465 2588 1456 2589 1442 2589 1465 2589 1450 2590 1444 2590 1466 2590 1465 2591 1449 2591 1467 2591 1449 2592 1438 2592 1467 2592 1444 2593 1455 2593 1466 2593 1438 2594 1458 2594 1467 2594 1443 2595 1456 2595 1468 2595 1452 2596 1459 2596 1469 2596 1470 2597 1443 2597 1468 2597 1432 2598 1450 2598 1471 2598 1451 2599 1431 2599 1472 2599 1462 2600 1454 2600 1471 2600 1431 2601 1453 2601 1472 2601 1460 2602 1451 2602 1472 2602 1454 2603 1432 2603 1471 2603 1463 2604 1464 2604 1473 2604 1453 2605 1461 2605 1474 2605 1461 2606 1446 2606 1474 2606 1446 2607 1475 2607 1474 2607 1456 2608 1465 2608 1476 2608 1459 2609 1448 2609 1477 2609 1448 2610 1462 2610 1477 2610 1469 2611 1459 2611 1477 2611 1458 2612 1460 2612 1478 2612 1462 2613 1471 2613 1479 2613 1457 2614 1480 2614 1481 2614 1478 2615 1460 2615 1482 2615 1455 2616 1457 2616 1481 2616 1460 2617 1472 2617 1482 2617 1466 2618 1455 2618 1481 2618 1473 2619 1464 2619 1483 2619 1464 2620 1452 2620 1483 2620 1470 2621 1468 2621 1484 2621 1452 2622 1469 2622 1483 2622 1476 2623 1465 2623 1485 2623 1465 2624 1467 2624 1485 2624 1469 2625 1477 2625 1486 2625 1453 2626 1474 2626 1487 2626 1482 2627 1472 2627 1487 2627 1488 2628 1463 2628 1489 2628 1472 2629 1453 2629 1487 2629 1474 2630 1475 2630 1487 2630 1463 2631 1473 2631 1489 2631 1485 2632 1467 2632 1490 2632 1467 2633 1458 2633 1490 2633 1450 2634 1466 2634 1491 2634 1458 2635 1478 2635 1490 2635 1471 2636 1450 2636 1491 2636 1468 2637 1456 2637 1492 2637 1473 2638 1483 2638 1493 2638 1456 2639 1476 2639 1492 2639 1470 2640 1484 2640 1494 2640 1477 2641 1462 2641 1495 2641 1496 2642 1470 2642 1494 2642 1462 2643 1479 2643 1495 2643 1486 2644 1477 2644 1495 2644 1479 2645 1471 2645 1497 2645 1471 2646 1491 2646 1497 2646 1476 2647 1485 2647 1498 2647 1488 2648 1489 2648 1499 2648 1478 2649 1482 2649 1500 2649 1500 2650 1482 2650 1501 2650 1482 2651 1487 2651 1501 2651 1487 2652 1475 2652 1501 2652 1475 2653 1502 2653 1501 2653 1493 2654 1483 2654 1503 2654 1468 2655 1492 2655 1504 2655 1483 2656 1469 2656 1503 2656 1484 2657 1468 2657 1504 2657 1469 2658 1486 2658 1503 2658 1485 2659 1490 2659 1505 2659 1486 2660 1495 2660 1506 2660 1480 2661 1507 2661 1508 2661 1491 2662 1466 2662 1508 2662 1466 2663 1481 2663 1508 2663 1498 2664 1485 2664 1505 2664 1481 2665 1480 2665 1508 2665 1490 2666 1478 2666 1509 2666 1497 2667 1491 2667 1508 2667 1505 2668 1490 2668 1509 2668 1478 2669 1500 2669 1509 2669 1499 2670 1489 2670 1510 2670 1489 2671 1473 2671 1510 2671 1496 2672 1494 2672 1511 2672 1473 2673 1493 2673 1510 2673 1493 2674 1503 2674 1512 2674 1492 2675 1476 2675 1513 2675 1476 2676 1498 2676 1513 2676 1488 2677 1499 2677 1514 2677 1515 2678 1488 2678 1514 2678 1500 2679 1501 2679 1516 2679 1501 2680 1502 2680 1516 2680 1497 2681 1508 2681 1517 2681 1507 2682 1518 2682 1517 2682 1508 2683 1507 2683 1517 2683 1484 2684 1504 2684 1519 2684 1494 2685 1484 2685 1519 2685 1495 2686 1479 2686 1520 2686 1479 2687 1497 2687 1520 2687 1511 2688 1494 2688 1519 2688 1506 2689 1495 2689 1520 2689 1513 2690 1498 2690 1521 2690 1499 2691 1510 2691 1522 2691 1498 2692 1505 2692 1521 2692 1496 2693 1511 2693 1523 2693 1486 2694 1506 2694 1524 2694 1525 2695 1496 2695 1523 2695 1512 2696 1503 2696 1524 2696 1492 2697 1513 2697 1526 2697 1503 2698 1486 2698 1524 2698 1504 2699 1492 2699 1526 2699 1506 2700 1520 2700 1527 2700 1515 2701 1514 2701 1528 2701 1505 2702 1509 2702 1529 2702 1500 2703 1516 2703 1530 2703 1493 2704 1512 2704 1531 2704 1509 2705 1500 2705 1530 2705 1522 2706 1510 2706 1531 2706 1516 2707 1502 2707 1530 2707 1529 2708 1509 2708 1530 2708 1502 2709 1532 2709 1530 2709 1523 2710 1511 2710 1533 2710 1510 2711 1493 2711 1531 2711 1511 2712 1519 2712 1533 2712 1512 2713 1524 2713 1534 2713 1526 2714 1513 2714 1535 2714 1531 2715 1512 2715 1534 2715 1513 2716 1521 2716 1535 2716 1497 2717 1517 2717 1536 2717 1517 2718 1518 2718 1536 2718 1527 2719 1520 2719 1536 2719 1520 2720 1497 2720 1536 2720 1504 2721 1526 2721 1537 2721 1519 2722 1504 2722 1537 2722 1528 2723 1514 2723 1538 2723 1533 2724 1519 2724 1537 2724 1499 2725 1522 2725 1538 2725 1514 2726 1499 2726 1538 2726 1505 2727 1529 2727 1539 2727 1521 2728 1505 2728 1539 2728 1522 2729 1531 2729 1540 2729 1541 2730 1515 2730 1542 2730 1525 2731 1523 2731 1543 2731 1515 2732 1528 2732 1542 2732 1524 2733 1506 2733 1544 2733 1529 2734 1530 2734 1545 2734 1530 2735 1532 2735 1545 2735 1506 2736 1527 2736 1544 2736 1534 2737 1524 2737 1544 2737 1523 2738 1533 2738 1546 2738 1518 2739 1547 2739 1548 2739 1527 2740 1536 2740 1548 2740 1536 2741 1518 2741 1548 2741 1526 2742 1535 2742 1549 2742 1528 2743 1538 2743 1550 2743 1551 2744 1525 2744 1552 2744 1525 2745 1543 2745 1552 2745 1531 2746 1534 2746 1553 2746 1540 2747 1531 2747 1553 2747 1533 2748 1537 2748 1554 2748 1546 2749 1533 2749 1554 2749 1534 2750 1544 2750 1555 2750 1535 2751 1521 2751 1556 2751 1521 2752 1539 2752 1556 2752 1541 2753 1542 2753 1557 2753 1529 2754 1545 2754 1558 2754 1539 2755 1529 2755 1558 2755 1532 2756 1559 2756 1558 2756 1550 2757 1538 2757 1560 2757 1545 2758 1532 2758 1558 2758 1538 2759 1522 2759 1560 2759 1522 2760 1540 2760 1560 2760 1537 2761 1526 2761 1561 2761 1544 2762 1527 2762 1562 2762 1548 2763 1547 2763 1562 2763 1526 2764 1549 2764 1561 2764 1527 2765 1548 2765 1562 2765 1554 2766 1537 2766 1561 2766 1555 2767 1544 2767 1562 2767 1540 2768 1553 2768 1563 2768 1523 2769 1546 2769 1564 2769 1543 2770 1523 2770 1564 2770 1552 2771 1543 2771 1564 2771 1557 2772 1542 2772 1565 2772 1546 2773 1554 2773 1566 2773 1542 2774 1528 2774 1565 2774 1528 2775 1550 2775 1565 2775 1567 2776 1541 2776 1568 2776 1549 2777 1535 2777 1569 2777 1541 2778 1557 2778 1568 2778 1535 2779 1556 2779 1569 2779 1551 2780 1552 2780 1570 2780 1550 2781 1560 2781 1571 2781 1556 2782 1539 2782 1572 2782 1563 2783 1553 2783 1573 2783 1553 2784 1534 2784 1573 2784 1539 2785 1558 2785 1572 2785 1558 2786 1559 2786 1572 2786 1534 2787 1555 2787 1573 2787 1547 2788 1574 2788 1575 2788 1562 2789 1547 2789 1575 2789 1555 2790 1562 2790 1575 2790 1552 2791 1564 2791 1576 2791 1554 2792 1561 2792 1577 2792 1557 2793 1565 2793 1578 2793 1566 2794 1554 2794 1577 2794 1579 2795 1551 2795 1580 2795 1560 2796 1540 2796 1581 2796 1540 2797 1563 2797 1581 2797 1551 2798 1570 2798 1580 2798 1571 2799 1560 2799 1581 2799 1577 2800 1561 2800 1582 2800 1549 2801 1569 2801 1582 2801 1561 2802 1549 2802 1582 2802 1564 2803 1546 2803 1583 2803 1563 2804 1573 2804 1584 2804 1576 2805 1564 2805 1583 2805 1567 2806 1568 2806 1585 2806 1546 2807 1566 2807 1583 2807 1556 2808 1572 2808 1586 2808 1572 2809 1559 2809 1586 2809 1559 2810 1587 2810 1586 2810 1569 2811 1556 2811 1586 2811 1578 2812 1565 2812 1588 2812 1565 2813 1550 2813 1588 2813 1550 2814 1571 2814 1588 2814 1566 2815 1577 2815 1589 2815 1583 2816 1566 2816 1589 2816 1575 2817 1574 2817 1590 2817 1584 2818 1573 2818 1590 2818 1573 2819 1555 2819 1590 2819 1552 2820 1576 2820 1591 2820 1555 2821 1575 2821 1590 2821 1570 2822 1552 2822 1591 2822 1568 2823 1557 2823 1592 2823 1557 2824 1578 2824 1592 2824 1576 2825 1583 2825 1593 2825 1571 2826 1581 2826 1594 2826 1577 2827 1582 2827 1595 2827 1596 2828 1567 2828 1597 2828 1567 2829 1585 2829 1597 2829 1579 2830 1580 2830 1598 2830 1578 2831 1588 2831 1599 2831 1582 2832 1569 2832 1600 2832 1595 2833 1582 2833 1600 2833 1594 2834 1581 2834 1601 2834 1569 2835 1586 2835 1600 2835 1586 2836 1587 2836 1600 2836 1581 2837 1563 2837 1601 2837 1580 2838 1570 2838 1602 2838 1563 2839 1584 2839 1601 2839 1598 2840 1580 2840 1602 2840 1584 2841 1590 2841 1603 2841 1570 2842 1591 2842 1602 2842 1590 2843 1574 2843 1603 2843 1574 2844 1604 2844 1603 2844 1585 2845 1568 2845 1605 2845 1583 2846 1589 2846 1606 2846 1593 2847 1583 2847 1606 2847 1568 2848 1592 2848 1605 2848 1579 2849 1598 2849 1607 2849 1608 2850 1579 2850 1607 2850 1588 2851 1571 2851 1609 2851 1599 2852 1588 2852 1609 2852 1589 2853 1577 2853 1610 2853 1571 2854 1594 2854 1609 2854 1592 2855 1578 2855 1611 2855 1577 2856 1595 2856 1610 2856 1591 2857 1576 2857 1612 2857 1576 2858 1593 2858 1612 2858 1578 2859 1599 2859 1611 2859 1594 2860 1601 2860 1613 2860 1595 2861 1600 2861 1614 2861 1600 2862 1587 2862 1614 2862 1587 2863 1615 2863 1614 2863 1596 2864 1597 2864 1616 2864 1612 2865 1593 2865 1617 2865 1593 2866 1606 2866 1617 2866 1601 2867 1584 2867 1618 2867 1598 2868 1602 2868 1619 2868 1603 2869 1604 2869 1618 2869 1607 2870 1598 2870 1619 2870 1613 2871 1601 2871 1618 2871 1584 2872 1603 2872 1618 2872 1597 2873 1585 2873 1620 2873 1616 2874 1597 2874 1620 2874 1602 2875 1591 2875 1621 2875 1591 2876 1612 2876 1621 2876 1619 2877 1602 2877 1621 2877 1585 2878 1605 2878 1620 2878 1599 2879 1609 2879 1622 2879 1611 2880 1599 2880 1622 2880 1606 2881 1589 2881 1623 2881 1589 2882 1610 2882 1623 2882 1624 2883 1596 2883 1625 2883 1617 2884 1606 2884 1623 2884 1596 2885 1616 2885 1625 2885 1608 2886 1607 2886 1626 2886 1605 2887 1592 2887 1627 2887 1595 2888 1614 2888 1628 2888 1592 2889 1611 2889 1627 2889 1610 2890 1595 2890 1628 2890 1622 2891 1609 2891 1629 2891 1614 2892 1615 2892 1628 2892 1594 2893 1613 2893 1629 2893 1609 2894 1594 2894 1629 2894 1607 2895 1619 2895 1630 2895 1604 2896 1631 2896 1632 2896 1618 2897 1604 2897 1632 2897 1613 2898 1618 2898 1632 2898 1612 2899 1617 2899 1633 2899 1611 2900 1622 2900 1634 2900 1627 2901 1611 2901 1634 2901 1635 2902 1608 2902 1636 2902 1608 2903 1626 2903 1636 2903 1616 2904 1620 2904 1637 2904 1605 2905 1627 2905 1638 2905 1617 2906 1623 2906 1639 2906 1620 2907 1605 2907 1638 2907 1637 2908 1620 2908 1638 2908 1619 2909 1621 2909 1640 2909 1630 2910 1619 2910 1640 2910 1639 2911 1623 2911 1641 2911 1623 2912 1610 2912 1641 2912 1622 2913 1629 2913 1642 2913 1610 2914 1628 2914 1641 2914 1615 2915 1643 2915 1641 2915 1628 2916 1615 2916 1641 2916 1640 2917 1621 2917 1644 2917 1624 2918 1625 2918 1645 2918 1621 2919 1612 2919 1644 2919 1612 2920 1633 2920 1644 2920 1632 2921 1631 2921 1646 2921 1613 2922 1632 2922 1646 2922 1642 2923 1629 2923 1646 2923 1629 2924 1613 2924 1646 2924 1626 2925 1607 2925 1647 2925 1625 2926 1616 2926 1648 2926 1607 2927 1630 2927 1647 2927 1616 2928 1637 2928 1648 2928 1630 2929 1640 2929 1649 2929 1645 2930 1625 2930 1648 2930 1638 2931 1627 2931 1650 2931 1627 2932 1634 2932 1650 2932 1617 2933 1639 2933 1651 2933 1652 2934 1624 2934 1653 2934 1633 2935 1617 2935 1651 2935 1624 2936 1645 2936 1653 2936 1654 2937 1635 2937 1655 2937 1634 2938 1622 2938 1656 2938 1635 2939 1636 2939 1655 2939 1622 2940 1642 2940 1656 2940 1651 2941 1639 2941 1657 2941 1639 2942 1641 2942 1657 2942 1641 2943 1643 2943 1657 2943 1637 2944 1638 2944 1658 2944 1626 2945 1647 2945 1659 2945 1636 2946 1626 2946 1659 2946 1631 2947 1660 2947 1661 2947 1646 2948 1631 2948 1661 2948 1655 2949 1636 2949 1659 2949 1642 2950 1646 2950 1661 2950 1656 2951 1642 2951 1661 2951 1649 2952 1640 2952 1662 2952 1638 2953 1650 2953 1663 2953 1640 2954 1644 2954 1662 2954 1644 2955 1633 2955 1664 2955 1658 2956 1638 2956 1663 2956 1633 2957 1651 2957 1664 2957 1645 2958 1648 2958 1665 2958 1647 2959 1630 2959 1666 2959 1665 2960 1648 2960 1667 2960 1630 2961 1649 2961 1666 2961 1648 2962 1637 2962 1667 2962 1637 2963 1658 2963 1667 2963 1649 2964 1662 2964 1668 2964 1651 2965 1657 2965 1669 2965 1657 2966 1643 2966 1669 2966 1650 2967 1634 2967 1670 2967 1643 2968 1671 2968 1669 2968 1634 2969 1656 2969 1670 2969 1655 2970 1659 2970 1672 2970 1652 2971 1653 2971 1673 2971 1647 2972 1666 2972 1674 2972 1661 2973 1660 2973 1675 2973 1659 2974 1647 2974 1674 2974 1656 2975 1661 2975 1675 2975 1645 2976 1665 2976 1076 2976 1672 2977 1659 2977 1674 2977 1644 2978 1664 2978 1676 2978 1653 2979 1645 2979 1076 2979 1662 2980 1644 2980 1676 2980 1668 2981 1662 2981 1676 2981 1658 2982 1663 2982 1065 2982 1652 2983 1673 2983 1677 2983 1655 2984 1672 2984 1073 2984 1654 2985 1655 2985 1073 2985 1678 2986 1652 2986 1677 2986 1651 2987 1669 2987 1679 2987 1650 2988 1670 2988 1680 2988 1669 2989 1671 2989 1679 2989 1663 2990 1650 2990 1680 2990 1065 2991 1663 2991 1680 2991 1664 2992 1651 2992 1679 2992 1665 2993 1667 2993 1681 2993 1666 2994 1649 2994 1682 2994 1649 2995 1668 2995 1682 2995 1668 2996 1676 2996 1062 2996 1670 2997 1656 2997 1683 2997 1680 2998 1670 2998 1683 2998 1660 2999 1080 2999 1683 2999 1675 3000 1660 3000 1683 3000 1672 3001 1674 3001 1684 3001 1656 3002 1675 3002 1683 3002 1658 3003 1065 3003 1064 3003 1667 3004 1658 3004 1064 3004 1666 3005 1682 3005 1685 3005 1674 3006 1666 3006 1685 3006 1681 3007 1667 3007 1064 3007 1684 3008 1674 3008 1685 3008 1653 3009 1076 3009 1075 3009 1676 3010 1664 3010 1686 3010 1664 3011 1679 3011 1686 3011 1679 3012 1671 3012 1686 3012 1062 3013 1676 3013 1686 3013 1673 3014 1653 3014 1075 3014 1671 3015 1068 3015 1686 3015 1672 3016 1684 3016 1079 3016 1073 3017 1672 3017 1079 3017 1665 3018 1681 3018 1078 3018 1076 3019 1665 3019 1078 3019 1062 3020 1686 3020 1067 3020 1686 3021 1068 3021 1067 3021 1065 3022 1680 3022 1070 3022 1682 3023 1668 3023 1061 3023 1668 3024 1062 3024 1061 3024 1678 3025 1677 3025 1092 3025 1090 3026 1654 3026 1072 3026 1654 3027 1073 3027 1072 3027 1683 3028 1080 3028 1083 3028 1070 3029 1680 3029 1083 3029 1680 3030 1683 3030 1083 3030 1673 3031 1075 3031 1093 3031 1677 3032 1673 3032 1093 3032 1684 3033 1685 3033 1087 3033 1092 3034 1677 3034 1093 3034 1685 3035 1682 3035 1084 3035 1087 3036 1685 3036 1084 3036 1681 3037 1064 3037 1071 3037 1682 3038 1061 3038 1084 3038 1078 3039 1681 3039 1071 3039 1079 3040 1684 3040 1095 3040 1098 3041 1678 3041 1099 3041 1684 3042 1087 3042 1095 3042 1678 3043 1092 3043 1099 3043 592 3044 1687 3044 1688 3044 592 3045 569 3045 1687 3045 593 3046 1688 3046 1689 3046 593 3047 592 3047 1688 3047 619 3048 1689 3048 1690 3048 619 3049 593 3049 1689 3049 620 3050 1690 3050 1691 3050 620 3051 619 3051 1690 3051 655 3052 1691 3052 1692 3052 655 3053 620 3053 1691 3053 683 3054 1692 3054 1693 3054 683 3055 655 3055 1692 3055 719 3056 1693 3056 1694 3056 719 3057 683 3057 1693 3057 761 3058 1694 3058 1695 3058 761 3059 719 3059 1694 3059 805 3060 761 3060 1695 3060 805 3061 1695 3061 1696 3061 852 3062 1696 3062 1697 3062 852 3063 805 3063 1696 3063 894 3064 1697 3064 1698 3064 894 3065 852 3065 1697 3065 931 3066 1698 3066 1699 3066 931 3067 894 3067 1698 3067 962 3068 1699 3068 1700 3068 962 3069 931 3069 1699 3069 988 3070 1700 3070 1701 3070 988 3071 962 3071 1700 3071 1008 3072 1701 3072 1702 3072 1008 3073 988 3073 1701 3073 1009 3074 1702 3074 1703 3074 1009 3075 1008 3075 1702 3075 1038 3076 1703 3076 1704 3076 1038 3077 1009 3077 1703 3077 1039 3078 1704 3078 1705 3078 1039 3079 1038 3079 1704 3079 1058 3080 1705 3080 1706 3080 1058 3081 1039 3081 1705 3081 232 3082 1706 3082 1707 3082 232 3083 1058 3083 1706 3083 251 3084 1707 3084 1708 3084 251 3085 232 3085 1707 3085 278 3086 1708 3086 1709 3086 278 3087 251 3087 1708 3087 312 3088 1709 3088 1710 3088 312 3089 278 3089 1709 3089 341 3090 1710 3090 1711 3090 341 3091 1711 3091 1712 3091 341 3092 312 3092 1710 3092 366 3093 1712 3093 1713 3093 366 3094 341 3094 1712 3094 388 3095 1713 3095 1714 3095 388 3096 366 3096 1713 3096 407 3097 1714 3097 1715 3097 407 3098 388 3098 1714 3098 421 3099 1715 3099 1716 3099 421 3100 407 3100 1715 3100 437 3101 1716 3101 1717 3101 437 3102 421 3102 1716 3102 452 3103 1717 3103 1718 3103 452 3104 437 3104 1717 3104 467 3105 1718 3105 1719 3105 467 3106 452 3106 1718 3106 475 3107 1719 3107 1720 3107 475 3108 467 3108 1719 3108 498 3109 475 3109 1720 3109 498 3110 1720 3110 1721 3110 524 3111 498 3111 1721 3111 524 3112 1721 3112 1722 3112 552 3113 524 3113 1722 3113 552 3114 1722 3114 1723 3114 582 3115 552 3115 1723 3115 582 3116 1723 3116 1724 3116 632 3117 582 3117 1724 3117 632 3118 1724 3118 1725 3118 677 3119 632 3119 1725 3119 677 3120 1725 3120 1726 3120 712 3121 677 3121 1726 3121 712 3122 1726 3122 1727 3122 746 3123 712 3123 1727 3123 746 3124 1727 3124 1728 3124 774 3125 746 3125 1728 3125 774 3126 1728 3126 1729 3126 795 3127 774 3127 1729 3127 795 3128 1729 3128 1730 3128 818 3129 795 3129 1730 3129 818 3130 1730 3130 1731 3130 819 3131 1731 3131 1732 3131 819 3132 818 3132 1731 3132 866 3133 819 3133 1732 3133 866 3134 1732 3134 1733 3134 878 3135 1733 3135 1734 3135 878 3136 866 3136 1733 3136 906 3137 1734 3137 1735 3137 906 3138 878 3138 1734 3138 942 3139 1735 3139 1736 3139 942 3140 906 3140 1735 3140 981 3141 1736 3141 1737 3141 981 3142 942 3142 1736 3142 1020 3143 1737 3143 1738 3143 1020 3144 981 3144 1737 3144 1051 3145 1738 3145 1739 3145 1051 3146 1020 3146 1738 3146 249 3147 1739 3147 1740 3147 249 3148 1051 3148 1739 3148 252 3149 1740 3149 1741 3149 252 3150 249 3150 1740 3150 274 3151 1741 3151 1742 3151 274 3152 252 3152 1741 3152 291 3153 1742 3153 1743 3153 291 3154 274 3154 1742 3154 303 3155 1743 3155 1744 3155 303 3156 291 3156 1743 3156 318 3157 1744 3157 1745 3157 318 3158 303 3158 1744 3158 334 3159 1745 3159 1746 3159 334 3160 318 3160 1745 3160 349 3161 334 3161 1746 3161 358 3162 349 3162 1746 3162 358 3163 1746 3163 1747 3163 378 3164 358 3164 1747 3164 378 3165 1747 3165 1748 3165 401 3166 378 3166 1748 3166 401 3167 1748 3167 1749 3167 428 3168 401 3168 1749 3168 428 3169 1749 3169 1750 3169 461 3170 428 3170 1750 3170 461 3171 1750 3171 1751 3171 488 3172 461 3172 1751 3172 488 3173 1751 3173 1752 3173 510 3174 488 3174 1752 3174 510 3175 1752 3175 1753 3175 533 3176 510 3176 1753 3176 533 3177 1753 3177 1754 3177 551 3178 533 3178 1754 3178 551 3179 1754 3179 1755 3179 564 3180 551 3180 1755 3180 564 3181 1755 3181 1756 3181 584 3182 564 3182 1756 3182 584 3183 1756 3183 1757 3183 585 3184 584 3184 1757 3184 585 3185 1757 3185 1758 3185 634 3186 585 3186 1758 3186 634 3187 1758 3187 1759 3187 640 3188 634 3188 1759 3188 640 3189 1759 3189 1760 3189 678 3190 640 3190 1760 3190 678 3191 1760 3191 1761 3191 715 3192 678 3192 1761 3192 715 3193 1761 3193 1762 3193 755 3194 715 3194 1762 3194 755 3195 1762 3195 1763 3195 801 3196 755 3196 1763 3196 801 3197 1763 3197 1764 3197 843 3198 1764 3198 1765 3198 843 3199 801 3199 1764 3199 888 3200 1765 3200 1766 3200 888 3201 843 3201 1765 3201 924 3202 1766 3202 1767 3202 924 3203 888 3203 1766 3203 568 3204 1767 3204 1768 3204 568 3205 924 3205 1767 3205 569 3206 1768 3206 1687 3206 569 3207 568 3207 1768 3207 1240 3208 1769 3208 1770 3208 1240 3209 1248 3209 1769 3209 1232 3210 1770 3210 1771 3210 1232 3211 1240 3211 1770 3211 1223 3212 1771 3212 1772 3212 1223 3213 1232 3213 1771 3213 1190 3214 1772 3214 1773 3214 1190 3215 1223 3215 1772 3215 1187 3216 1773 3216 1774 3216 1187 3217 1190 3217 1773 3217 1173 3218 1774 3218 1775 3218 1173 3219 1187 3219 1774 3219 1131 3220 1775 3220 1776 3220 1131 3221 1173 3221 1775 3221 1129 3222 1776 3222 1777 3222 1129 3223 1131 3223 1776 3223 1098 3224 1777 3224 1778 3224 1098 3225 1129 3225 1777 3225 1678 3226 1778 3226 1779 3226 1678 3227 1098 3227 1778 3227 1652 3228 1779 3228 1780 3228 1652 3229 1678 3229 1779 3229 1624 3230 1780 3230 1781 3230 1624 3231 1652 3231 1780 3231 1596 3232 1781 3232 1782 3232 1596 3233 1624 3233 1781 3233 1567 3234 1782 3234 1783 3234 1567 3235 1596 3235 1782 3235 1541 3236 1783 3236 1784 3236 1541 3237 1567 3237 1783 3237 1515 3238 1784 3238 1785 3238 1515 3239 1541 3239 1784 3239 1488 3240 1785 3240 1786 3240 1488 3241 1515 3241 1785 3241 1463 3242 1786 3242 1787 3242 1463 3243 1488 3243 1786 3243 1440 3244 1787 3244 1788 3244 1440 3245 1463 3245 1787 3245 1422 3246 1440 3246 1788 3246 1422 3247 1788 3247 1789 3247 1406 3248 1422 3248 1789 3248 1406 3249 1789 3249 1790 3249 1393 3250 1406 3250 1790 3250 1393 3251 1790 3251 1791 3251 1376 3252 1393 3252 1791 3252 1376 3253 1791 3253 1792 3253 1361 3254 1376 3254 1792 3254 1361 3255 1792 3255 1793 3255 1346 3256 1793 3256 1794 3256 1346 3257 1361 3257 1793 3257 1331 3258 1794 3258 1795 3258 1331 3259 1346 3259 1794 3259 1320 3260 1795 3260 1796 3260 1320 3261 1331 3261 1795 3261 1311 3262 1796 3262 1797 3262 1311 3263 1320 3263 1796 3263 1306 3264 1797 3264 1798 3264 1306 3265 1311 3265 1797 3265 1181 3266 1798 3266 1799 3266 1181 3267 1306 3267 1798 3267 1179 3268 1799 3268 1800 3268 1179 3269 1181 3269 1799 3269 1162 3270 1800 3270 1801 3270 1162 3271 1179 3271 1800 3271 1148 3272 1801 3272 1802 3272 1148 3273 1162 3273 1801 3273 1115 3274 1802 3274 1803 3274 1115 3275 1148 3275 1802 3275 1113 3276 1803 3276 1804 3276 1113 3277 1115 3277 1803 3277 1089 3278 1804 3278 1805 3278 1089 3279 1113 3279 1804 3279 1090 3280 1805 3280 1806 3280 1090 3281 1089 3281 1805 3281 1654 3282 1806 3282 1807 3282 1654 3283 1090 3283 1806 3283 1635 3284 1807 3284 1808 3284 1635 3285 1654 3285 1807 3285 1608 3286 1808 3286 1809 3286 1608 3287 1635 3287 1808 3287 1579 3288 1809 3288 1810 3288 1579 3289 1608 3289 1809 3289 1551 3290 1810 3290 1811 3290 1551 3291 1579 3291 1810 3291 1525 3292 1811 3292 1812 3292 1525 3293 1551 3293 1811 3293 1496 3294 1812 3294 1813 3294 1496 3295 1525 3295 1812 3295 1470 3296 1496 3296 1813 3296 1470 3297 1813 3297 1814 3297 1443 3298 1470 3298 1814 3298 1443 3299 1814 3299 1815 3299 1415 3300 1443 3300 1815 3300 1415 3301 1815 3301 1816 3301 1389 3302 1415 3302 1816 3302 1389 3303 1816 3303 1817 3303 1366 3304 1389 3304 1817 3304 1366 3305 1817 3305 1818 3305 1350 3306 1366 3306 1818 3306 1350 3307 1818 3307 1819 3307 1334 3308 1350 3308 1819 3308 1334 3309 1819 3309 1820 3309 1319 3310 1334 3310 1820 3310 1319 3311 1820 3311 1821 3311 1304 3312 1319 3312 1821 3312 1304 3313 1821 3313 1822 3313 1296 3314 1304 3314 1822 3314 1296 3315 1822 3315 1823 3315 1288 3316 1296 3316 1823 3316 1288 3317 1823 3317 1824 3317 1280 3318 1288 3318 1824 3318 1280 3319 1824 3319 1825 3319 1271 3320 1280 3320 1825 3320 1271 3321 1825 3321 1826 3321 1263 3322 1826 3322 1827 3322 1263 3323 1271 3323 1826 3323 1255 3324 1827 3324 1828 3324 1255 3325 1263 3325 1827 3325 1248 3326 1828 3326 1769 3326 1248 3327 1255 3327 1828 3327 1770 3328 1829 3328 1830 3328 1770 3329 1769 3329 1829 3329 1771 3330 1830 3330 1831 3330 1771 3331 1770 3331 1830 3331 1772 3332 1831 3332 1832 3332 1772 3333 1771 3333 1831 3333 1773 3334 1832 3334 1833 3334 1773 3335 1772 3335 1832 3335 1774 3336 1833 3336 1834 3336 1774 3337 1773 3337 1833 3337 1775 3338 1834 3338 1835 3338 1775 3339 1774 3339 1834 3339 1776 3340 1835 3340 1836 3340 1776 3341 1775 3341 1835 3341 1777 3342 1836 3342 1837 3342 1777 3343 1776 3343 1836 3343 1778 3344 1837 3344 1838 3344 1778 3345 1777 3345 1837 3345 1779 3346 1778 3346 1838 3346 1780 3347 1838 3347 1839 3347 1780 3348 1779 3348 1838 3348 1781 3349 1839 3349 1840 3349 1781 3350 1780 3350 1839 3350 1782 3351 1840 3351 1841 3351 1782 3352 1781 3352 1840 3352 1783 3353 1841 3353 1842 3353 1783 3354 1782 3354 1841 3354 1784 3355 1842 3355 1843 3355 1784 3356 1783 3356 1842 3356 1785 3357 1843 3357 1844 3357 1785 3358 1784 3358 1843 3358 1786 3359 1844 3359 1845 3359 1786 3360 1785 3360 1844 3360 1787 3361 1845 3361 1846 3361 1787 3362 1786 3362 1845 3362 1788 3363 1846 3363 1847 3363 1788 3364 1787 3364 1846 3364 1789 3365 1788 3365 1847 3365 1790 3366 1789 3366 1847 3366 1790 3367 1847 3367 1848 3367 1791 3368 1848 3368 1849 3368 1791 3369 1790 3369 1848 3369 1792 3370 1791 3370 1849 3370 1792 3371 1849 3371 1850 3371 1793 3372 1792 3372 1850 3372 1793 3373 1850 3373 1851 3373 1794 3374 1793 3374 1851 3374 1794 3375 1851 3375 1852 3375 1795 3376 1794 3376 1852 3376 1795 3377 1852 3377 1853 3377 1796 3378 1795 3378 1853 3378 1796 3379 1853 3379 1854 3379 1797 3380 1854 3380 1855 3380 1797 3381 1796 3381 1854 3381 1798 3382 1855 3382 1856 3382 1798 3383 1797 3383 1855 3383 1799 3384 1798 3384 1856 3384 1800 3385 1856 3385 1857 3385 1800 3386 1799 3386 1856 3386 1801 3387 1857 3387 1858 3387 1801 3388 1800 3388 1857 3388 1802 3389 1858 3389 1859 3389 1802 3390 1801 3390 1858 3390 1803 3391 1859 3391 1860 3391 1803 3392 1802 3392 1859 3392 1804 3393 1860 3393 1861 3393 1804 3394 1803 3394 1860 3394 1805 3395 1861 3395 1862 3395 1805 3396 1804 3396 1861 3396 1806 3397 1862 3397 1863 3397 1806 3398 1805 3398 1862 3398 1807 3399 1863 3399 1864 3399 1807 3400 1806 3400 1863 3400 1808 3401 1864 3401 1865 3401 1808 3402 1807 3402 1864 3402 1809 3403 1808 3403 1865 3403 1810 3404 1865 3404 1866 3404 1810 3405 1809 3405 1865 3405 1811 3406 1866 3406 1867 3406 1811 3407 1810 3407 1866 3407 1812 3408 1867 3408 1868 3408 1812 3409 1811 3409 1867 3409 1813 3410 1868 3410 1869 3410 1813 3411 1812 3411 1868 3411 1814 3412 1869 3412 1870 3412 1814 3413 1813 3413 1869 3413 1815 3414 1870 3414 1871 3414 1815 3415 1814 3415 1870 3415 1816 3416 1871 3416 1872 3416 1816 3417 1815 3417 1871 3417 1817 3418 1816 3418 1872 3418 1817 3419 1872 3419 1873 3419 1818 3420 1817 3420 1873 3420 1818 3421 1873 3421 1874 3421 1819 3422 1818 3422 1874 3422 1820 3423 1819 3423 1874 3423 1820 3424 1874 3424 1875 3424 1821 3425 1820 3425 1875 3425 1821 3426 1875 3426 1876 3426 1822 3427 1821 3427 1876 3427 1822 3428 1876 3428 1877 3428 1823 3429 1822 3429 1877 3429 1823 3430 1877 3430 1878 3430 1824 3431 1823 3431 1878 3431 1824 3432 1878 3432 1879 3432 1825 3433 1824 3433 1879 3433 1825 3434 1879 3434 1880 3434 1826 3435 1825 3435 1880 3435 1826 3436 1880 3436 1881 3436 1827 3437 1826 3437 1881 3437 1827 3438 1881 3438 1882 3438 1828 3439 1827 3439 1882 3439 1828 3440 1882 3440 1829 3440 1769 3441 1828 3441 1829 3441 1883 3442 395 3442 419 3442 239 3443 238 3443 1884 3443 1883 3444 419 3444 445 3444 1883 3445 445 3445 473 3445 1883 3446 473 3446 499 3446 1883 3447 499 3447 519 3447 784 3448 1885 3448 748 3448 1883 3449 519 3449 538 3449 1883 3450 538 3450 572 3450 1883 3451 572 3451 589 3451 1883 3452 1886 3452 337 3452 612 3453 1883 3453 589 3453 1055 3454 239 3454 1884 3454 1042 3455 1055 3455 1884 3455 1042 3456 1884 3456 1885 3456 827 3457 1885 3457 784 3457 1026 3458 1042 3458 1885 3458 871 3459 1885 3459 827 3459 1011 3460 1026 3460 1885 3460 1887 3461 846 3461 1886 3461 1887 3462 571 3462 603 3462 1887 3463 603 3463 653 3463 907 3464 1885 3464 871 3464 1887 3465 653 3465 688 3465 1887 3466 688 3466 724 3466 1887 3467 724 3467 756 3467 971 3468 1011 3468 1885 3468 1887 3469 756 3469 799 3469 1887 3470 799 3470 825 3470 1887 3471 825 3471 846 3471 943 3472 971 3472 1885 3472 943 3473 1885 3473 907 3473 542 3474 571 3474 1887 3474 515 3475 542 3475 1887 3475 1888 3476 1883 3476 612 3476 1888 3477 612 3477 637 3477 1888 3478 637 3478 668 3478 1888 3479 668 3479 703 3479 1888 3480 703 3480 742 3480 783 3481 1888 3481 742 3481 492 3482 515 3482 1887 3482 821 3483 1888 3483 783 3483 469 3484 492 3484 1887 3484 861 3485 1888 3485 821 3485 454 3486 469 3486 1887 3486 1884 3487 454 3487 1887 3487 900 3488 1888 3488 861 3488 439 3489 454 3489 1884 3489 937 3490 1888 3490 900 3490 423 3491 439 3491 1884 3491 968 3492 1888 3492 937 3492 393 3493 423 3493 1884 3493 996 3494 1888 3494 968 3494 374 3495 393 3495 1884 3495 1003 3496 1888 3496 996 3496 351 3497 374 3497 1884 3497 325 3498 351 3498 1884 3498 1886 3499 846 3499 869 3499 1886 3500 869 3500 898 3500 1886 3501 898 3501 930 3501 1886 3502 930 3502 967 3502 1886 3503 967 3503 1006 3503 645 3504 1885 3504 1888 3504 1886 3505 1006 3505 1034 3505 1886 3506 1034 3506 217 3506 645 3507 1888 3507 1003 3507 1886 3508 217 3508 220 3508 646 3509 1885 3509 645 3509 1886 3510 220 3510 259 3510 1886 3511 259 3511 280 3511 1886 3512 280 3512 306 3512 1886 3513 306 3513 321 3513 1886 3514 321 3514 337 3514 295 3515 325 3515 1884 3515 674 3516 1885 3516 646 3516 269 3517 295 3517 1884 3517 707 3518 1885 3518 674 3518 238 3519 269 3519 1884 3519 748 3520 1885 3520 707 3520 1883 3521 337 3521 353 3521 1883 3522 353 3522 371 3522 1883 3523 371 3523 395 3523 1858 3524 1861 3524 1860 3524 1841 3525 1834 3525 1829 3525 1841 3526 1835 3526 1834 3526 1841 3527 1839 3527 1838 3527 1841 3528 1840 3528 1839 3528 1841 3529 1838 3529 1835 3529 1875 3530 1877 3530 1876 3530 1841 3531 1829 3531 1868 3531 1857 3532 1868 3532 1861 3532 1857 3533 1861 3533 1858 3533 1879 3534 1878 3534 1877 3534 1855 3535 1857 3535 1856 3535 1873 3536 1875 3536 1874 3536 1873 3537 1877 3537 1875 3537 1844 3538 1842 3538 1841 3538 1844 3539 1843 3539 1842 3539 1880 3540 1879 3540 1877 3540 1853 3541 1855 3541 1854 3541 1852 3542 1868 3542 1857 3542 1852 3543 1857 3543 1855 3543 1852 3544 1855 3544 1853 3544 1870 3545 1872 3545 1871 3545 1870 3546 1873 3546 1872 3546 1847 3547 1845 3547 1844 3547 1847 3548 1846 3548 1845 3548 1847 3549 1841 3549 1868 3549 1847 3550 1844 3550 1841 3550 1829 3551 1881 3551 1880 3551 1829 3552 1882 3552 1881 3552 1851 3553 1868 3553 1852 3553 1829 3554 1877 3554 1873 3554 1829 3555 1880 3555 1877 3555 1850 3556 1868 3556 1851 3556 1849 3557 1848 3557 1847 3557 1849 3558 1847 3558 1868 3558 1849 3559 1868 3559 1850 3559 1868 3560 1870 3560 1869 3560 1868 3561 1873 3561 1870 3561 1868 3562 1829 3562 1873 3562 1831 3563 1830 3563 1829 3563 1866 3564 1868 3564 1867 3564 1833 3565 1832 3565 1831 3565 1833 3566 1831 3566 1829 3566 1834 3567 1833 3567 1829 3567 1864 3568 1866 3568 1865 3568 1864 3569 1868 3569 1866 3569 1862 3570 1868 3570 1864 3570 1862 3571 1864 3571 1863 3571 1837 3572 1836 3572 1835 3572 1861 3573 1868 3573 1862 3573 1838 3574 1837 3574 1835 3574 1858 3575 1860 3575 1859 3575 1712 3576 1711 3576 1547 3576 1723 3577 1372 3577 1724 3577 1723 3578 1387 3578 1372 3578 1713 3579 1712 3579 1547 3579 1713 3580 1547 3580 1518 3580 1722 3581 1387 3581 1723 3581 1722 3582 1401 3582 1387 3582 1714 3583 1518 3583 1507 3583 1714 3584 1713 3584 1518 3584 1721 3585 1401 3585 1722 3585 1721 3586 1419 3586 1401 3586 1715 3587 1714 3587 1507 3587 1715 3588 1507 3588 1480 3588 1720 3589 1419 3589 1721 3589 1716 3590 1715 3590 1480 3590 1719 3591 1419 3591 1720 3591 1719 3592 1434 3592 1419 3592 1717 3593 1716 3593 1480 3593 1717 3594 1480 3594 1457 3594 1718 3595 1434 3595 1719 3595 1718 3596 1717 3596 1457 3596 1718 3597 1457 3597 1434 3597 1383 3598 1759 3598 1758 3598 1363 3599 1760 3599 1759 3599 1363 3600 1759 3600 1383 3600 1409 3601 1757 3601 1756 3601 1409 3602 1758 3602 1757 3602 1409 3603 1383 3603 1758 3603 1344 3604 1761 3604 1760 3604 1344 3605 1762 3605 1761 3605 1344 3606 1760 3606 1363 3606 1436 3607 1756 3607 1755 3607 1436 3608 1409 3608 1756 3608 1329 3609 1762 3609 1344 3609 1329 3610 1763 3610 1762 3610 1446 3611 1755 3611 1754 3611 1446 3612 1436 3612 1755 3612 1314 3613 1763 3613 1329 3613 1314 3614 1764 3614 1763 3614 1475 3615 1446 3615 1754 3615 1475 3616 1753 3616 1752 3616 1475 3617 1754 3617 1753 3617 1301 3618 1764 3618 1314 3618 1301 3619 1765 3619 1764 3619 1301 3620 1766 3620 1765 3620 1502 3621 1475 3621 1752 3621 1502 3622 1752 3622 1751 3622 1293 3623 1766 3623 1301 3623 1293 3624 1767 3624 1766 3624 1532 3625 1502 3625 1751 3625 1532 3626 1751 3626 1750 3626 1285 3627 1767 3627 1293 3627 1285 3628 1768 3628 1767 3628 1559 3629 1532 3629 1750 3629 1559 3630 1750 3630 1749 3630 1277 3631 1688 3631 1687 3631 1277 3632 1768 3632 1285 3632 1277 3633 1687 3633 1768 3633 1587 3634 1559 3634 1749 3634 1587 3635 1748 3635 1747 3635 1587 3636 1749 3636 1748 3636 1269 3637 1689 3637 1688 3637 1269 3638 1688 3638 1277 3638 1615 3639 1587 3639 1747 3639 1615 3640 1747 3640 1746 3640 1260 3641 1690 3641 1689 3641 1260 3642 1689 3642 1269 3642 1643 3643 1615 3643 1746 3643 1643 3644 1746 3644 1745 3644 1252 3645 1691 3645 1690 3645 1252 3646 1692 3646 1691 3646 1252 3647 1690 3647 1260 3647 1671 3648 1643 3648 1745 3648 1671 3649 1744 3649 1743 3649 1671 3650 1745 3650 1744 3650 1244 3651 1693 3651 1692 3651 1244 3652 1692 3652 1252 3652 1068 3653 1743 3653 1742 3653 1068 3654 1671 3654 1743 3654 1236 3655 1694 3655 1693 3655 1236 3656 1693 3656 1244 3656 1069 3657 1742 3657 1741 3657 1069 3658 1068 3658 1742 3658 1228 3659 1695 3659 1694 3659 1228 3660 1694 3660 1236 3660 1696 3661 1695 3661 1228 3661 1104 3662 1741 3662 1740 3662 1104 3663 1069 3663 1741 3663 1739 3664 1104 3664 1740 3664 1221 3665 1696 3665 1228 3665 1697 3666 1696 3666 1221 3666 1124 3667 1104 3667 1739 3667 1201 3668 1697 3668 1221 3668 1738 3669 1124 3669 1739 3669 1140 3670 1124 3670 1738 3670 1698 3671 1697 3671 1201 3671 1183 3672 1698 3672 1201 3672 1737 3673 1140 3673 1738 3673 1156 3674 1140 3674 1737 3674 1699 3675 1698 3675 1183 3675 1736 3676 1156 3676 1737 3676 1700 3677 1183 3677 1164 3677 1700 3678 1699 3678 1183 3678 1735 3679 1156 3679 1736 3679 1735 3680 1172 3680 1156 3680 1701 3681 1700 3681 1164 3681 1701 3682 1164 3682 1145 3682 1734 3683 1172 3683 1735 3683 1734 3684 1191 3684 1172 3684 1702 3685 1145 3685 1121 3685 1702 3686 1701 3686 1145 3686 1733 3687 1191 3687 1734 3687 1733 3688 1206 3688 1191 3688 1703 3689 1702 3689 1121 3689 1732 3690 1206 3690 1733 3690 1704 3691 1121 3691 1081 3691 1704 3692 1703 3692 1121 3692 1731 3693 1206 3693 1732 3693 1731 3694 1213 3694 1206 3694 1705 3695 1081 3695 1080 3695 1705 3696 1704 3696 1081 3696 1730 3697 1213 3697 1731 3697 1730 3698 1217 3698 1213 3698 1706 3699 1080 3699 1660 3699 1706 3700 1705 3700 1080 3700 1729 3701 1110 3701 1217 3701 1729 3702 1217 3702 1730 3702 1707 3703 1660 3703 1631 3703 1707 3704 1706 3704 1660 3704 1728 3705 1110 3705 1729 3705 1708 3706 1707 3706 1631 3706 1727 3707 1111 3707 1110 3707 1727 3708 1110 3708 1728 3708 1709 3709 1631 3709 1604 3709 1709 3710 1708 3710 1631 3710 1726 3711 1357 3711 1111 3711 1726 3712 1111 3712 1727 3712 1710 3713 1604 3713 1574 3713 1710 3714 1709 3714 1604 3714 1725 3715 1372 3715 1357 3715 1725 3716 1357 3716 1726 3716 1711 3717 1574 3717 1547 3717 1711 3718 1710 3718 1574 3718 1724 3719 1372 3719 1725 3719 191 3720 1885 3720 1884 3720 191 3721 1889 3721 1885 3721 1890 3722 191 3722 1884 3722 1888 3723 1885 3723 183 3723 1885 3724 1889 3724 183 3724 1888 3725 183 3725 1891 3725 175 3726 1883 3726 1888 3726 175 3727 1892 3727 1883 3727 1891 3728 175 3728 1888 3728 140 3729 1886 3729 1883 3729 140 3730 1893 3730 1886 3730 1892 3731 140 3731 1883 3731 1887 3732 1886 3732 0 3732 1886 3733 1893 3733 0 3733 1887 3734 0 3734 1894 3734 1884 3735 1887 3735 199 3735 1887 3736 1894 3736 199 3736 1884 3737 199 3737 1890 3737 158 3738 120 3738 1893 3738 130 3739 158 3739 1893 3739 131 3740 130 3740 1893 3740 1893 3741 120 3741 119 3741 1893 3742 119 3742 118 3742 1893 3743 118 3743 1 3743 1 3744 0 3744 1893 3744 131 3745 1893 3745 140 3745 167 3746 166 3746 1892 3746 1892 3747 166 3747 165 3747 1892 3748 165 3748 156 3748 1892 3749 156 3749 155 3749 1892 3750 155 3750 154 3750 1892 3751 154 3751 141 3751 141 3752 140 3752 1892 3752 167 3753 1892 3753 175 3753 1891 3754 177 3754 176 3754 177 3755 1891 3755 178 3755 178 3756 1891 3756 179 3756 179 3757 1891 3757 180 3757 180 3758 1891 3758 181 3758 181 3759 1891 3759 182 3759 176 3760 175 3760 1891 3760 182 3761 1891 3761 183 3761 185 3762 184 3762 1889 3762 186 3763 185 3763 1889 3763 186 3764 1889 3764 187 3764 187 3765 1889 3765 188 3765 188 3766 1889 3766 189 3766 184 3767 183 3767 1889 3767 190 3768 1889 3768 191 3768 189 3769 1889 3769 190 3769 193 3770 192 3770 1890 3770 194 3771 193 3771 1890 3771 195 3772 194 3772 1890 3772 196 3773 195 3773 1890 3773 196 3774 1890 3774 197 3774 197 3775 1890 3775 198 3775 192 3776 191 3776 1890 3776 198 3777 1890 3777 199 3777 169 3778 168 3778 1894 3778 144 3779 169 3779 1894 3779 145 3780 144 3780 1894 3780 147 3781 145 3781 1894 3781 98 3782 147 3782 1894 3782 200 3783 199 3783 1894 3783 168 3784 200 3784 1894 3784 98 3785 1894 3785 0 3785

+
+
+
+ + + + -6 11.625 87.99482 -5.990309 11.66638 88.01887 -6.028941 11.66413 88.01887 -6.043412 11.7462 88.06699 -5 11.5 88.5 -5.008555 11.63053 88.5 -5.138293 11.65194 88.42783 -5.261394 11.63024 88.35566 -5.295231 11.75652 88.35566 -5.75 11.93301 88.21132 -5.616978 11.82139 88.21132 -5.598258 11.97878 88.28349 -5.458734 11.8125 88.28349 -5.425467 11.98209 88.35566 -5.625 12.14952 88.35566 -6.125 11.71651 88.06699 -6.066013 11.65304 88.01887 -5.913176 11.9924 88.21132 -6.086824 11.9924 88.21132 -6 11.875 88.13916 -5.871742 11.85238 88.13916 -5.956588 11.7462 88.06699 -5.786237 12.08731 88.28349 -5.869764 12.23861 88.35566 -6.128258 11.85238 88.13916 -6.25 11.93301 88.21132 -6 12.125 88.28349 -6.130236 12.23861 88.35566 -6.241045 11.78727 88.13916 -6.383022 11.82139 88.21132 -6.191511 11.6607 88.06699 -6.213763 12.08731 88.28349 -6.375 12.14952 88.35566 -6.32476 11.6875 88.13916 -6.234923 11.58551 88.06699 -6.469846 11.67101 88.21132 -6.401742 11.97878 88.28349 -6.574533 11.98209 88.35566 -6.5 11.5 88.21132 -6.369303 11.56512 88.13916 -6.25 11.5 88.06699 -6.541266 11.8125 88.28349 -6.704769 11.75652 88.35566 -6.469846 11.32899 88.21132 -6.369303 11.43488 88.13916 -6.234923 11.41449 88.06699 -6.615505 11.60853 88.28349 -6.75 11.5 88.35566 -6.32476 11.3125 88.13916 -6.191511 11.3393 88.06699 -6.383022 11.17861 88.21132 -6.125 11.28349 88.06699 -6.043412 11.2538 88.06699 -6.066013 11.34696 88.01887 -6.615505 11.39147 88.28349 -6.704769 11.24348 88.35566 -6.25 11.06699 88.21132 -6.241045 11.21273 88.13916 -6.028941 11.33587 88.01887 -6.574533 11.01791 88.35566 -6.541266 11.1875 88.28349 -5.956588 11.2538 88.06699 -5.990309 11.33362 88.01887 -6 11.375 87.99482 -5.978294 11.3769 87.99482 -6.086824 11.0076 88.21132 -6.128258 11.14762 88.13916 -5.875 11.28349 88.06699 -5.957247 11.38254 87.99482 -6.401742 11.02122 88.28349 -6.375 10.85048 88.35566 -5.9375 11.39175 87.99482 -6 11.125 88.13916 -5.913176 11.0076 88.21132 -5.808489 11.3393 88.06699 -5.919652 11.40424 87.99482 -6.130236 10.76139 88.35566 -6.213763 10.91269 88.28349 -5.904244 11.41965 87.99482 -5.75 11.06699 88.21132 -5.871742 11.14762 88.13916 -5.765077 11.41449 88.06699 -5.891747 11.4375 87.99482 -6 10.875 88.28349 -5.869764 10.76139 88.35566 -5.882538 11.45725 87.99482 -5.616978 11.17861 88.21132 -5.758955 11.21273 88.13916 -5.786237 10.91269 88.28349 -5.625 10.85048 88.35566 -5.67524 11.3125 88.13916 -5.530154 11.32899 88.21132 -5.753798 11.45659 88.06699 -5.876899 11.47829 87.99482 -6 11.5 87.92265 -5.598258 11.02122 88.28349 -5.425467 11.01791 88.35566 -5.458734 11.1875 88.28349 -5.295231 11.24348 88.35566 -5.008555 11.36947 88.5 -5.138293 11.34806 88.42783 -5.261394 11.36976 88.35566 -5.876899 11.52171 87.99482 -5.882538 11.54275 87.99482 -5.93963 11.51618 87.95873 -5.941269 11.52138 87.95873 -5.943356 11.52641 87.95873 -5.891747 11.5625 87.99482 -5.945873 11.53125 87.95873 -5.948803 11.53585 87.95873 -5.904244 11.58035 87.99482 -5.952122 11.54017 87.95873 -5.955806 11.54419 87.95873 -5.919652 11.59576 87.99482 -5.9375 11.60825 87.99482 -5.626427 11.53268 88.13916 -5.753798 11.54341 88.06699 -5.765077 11.58551 88.06699 -5.67524 11.6875 88.13916 -5.530154 11.67101 88.21132 -6.041667 11.57217 87.97076 -5.034074 11.75882 88.5 -5.119038 11.82064 88.46392 -5.07612 11.88268 88.5 -5.133975 12 88.5 -6.151536 11.64297 88.04293 -6.044194 11.54419 87.95873 -6.132309 11.57639 88.01086 -6.17406 11.61448 88.04293 -6.142821 11.52949 88.00685 -6.125 11.5 87.99482 -6.166667 11.5 88.01887 -6.194444 11.5 88.03491 -6.128573 11.44747 88.00284 -5.292893 12.20711 88.5 -5.391239 12.29335 88.5 -6.17406 11.38552 88.04293 -6.151536 11.35703 88.04293 -5.955806 11.45581 87.95873 -5.952122 11.45983 87.95873 -5.948803 11.46415 87.95873 -5.945873 11.46875 87.95873 -5.943356 11.47359 87.95873 -5.5 12.36603 88.5 -5.617317 12.42388 88.5 -5.941269 11.47862 87.95873 -5.93963 11.48382 87.95873 -5.377378 11.44553 88.28349 -5.119038 11.17936 88.46392 -5.133975 11 88.5 -5.07612 11.11732 88.5 -5.034074 11.24118 88.5 -5.988041 11.52887 87.94069 -5.957247 11.61746 87.99482 -5.990482 11.57229 87.96475 -5.978294 11.6231 87.99482 -6 11.5625 87.95873 -5.741181 12.46593 88.5 -5.869474 12.49144 88.5 -6 12.5 88.5 -5.269291 11.92187 88.40979 -5.206647 12.10876 88.5 -6.098712 11.51988 87.98079 -6.044194 11.45581 87.95873 -6.011959 11.47113 87.94069 -6.07357 11.39047 87.99883 -6.019884 11.40129 87.98079 -6.130526 12.49144 88.5 -6.258819 12.46593 88.5 -6.382683 12.42388 88.5 -6 11.45833 87.94671 -5.292893 10.79289 88.5 -5.206647 10.89124 88.5 -5.269291 11.07812 88.40979 -6.008681 11.51299 87.93167 -6.028871 11.51196 87.94069 -6.0625 11.5 87.95873 -6.045974 11.49086 87.94971 -6.5 12.36603 88.5 -6.608761 12.29335 88.5 -6.707107 12.20711 88.5 -6.793353 12.10876 88.5 -6.866025 12 88.5 -6.92388 11.88268 88.5 -6.965926 11.75882 88.5 -6.991445 11.63053 88.5 -7 11.5 88.5 -6.991445 11.36947 88.5 -6.965926 11.24118 88.5 -6.92388 11.11732 88.5 -6.866025 11 88.5 -6.793353 10.89124 88.5 -6.707107 10.79289 88.5 -6.608761 10.70665 88.5 -6.5 10.63397 88.5 -6.382683 10.57612 88.5 -6.258819 10.53407 88.5 -6.130526 10.50856 88.5 -6 10.5 88.5 -5.869474 10.50856 88.5 -5.741181 10.53407 88.5 -5.617317 10.57612 88.5 -5.5 10.63397 88.5 -5.391239 10.70665 88.5 -5.808489 11.6607 88.06699 -5.875 11.71651 88.06699 -5.758955 11.78727 88.13916 -4.14285 13.5174 89.76854 -4.018566 13.40694 89.7 -4.170354 13.55302 89.7 -6.441291 8.855488 89.89132 -6.510453 8.867963 89.89132 -6.44748 8.818401 89.83346 -4.024283 13.40144 89.76854 -3.970016 13.17412 89.93905 -3.923571 13.11615 89.93905 -3.884253 13.14675 89.89132 -6.311787 8.799259 89.83346 -6.451329 8.795334 89.76854 -6.314469 8.776027 89.76854 -6.226438 8.767301 89.76854 -3.931577 13.20582 89.89132 -6.500967 8.916877 89.93905 -6.68149 9.020094 89.97414 -6.697233 8.962805 89.93905 -4.027467 13.31584 89.89132 -3.902569 13.22974 89.83346 -3.999803 13.34131 89.83346 -3.945135 12.94536 89.99346 -3.846942 12.90666 89.97414 -3.896417 12.97963 89.97414 -6.105029 8.759948 89.76854 -6.105333 8.752018 89.7 -3.948942 12.84002 90 -3.896806 12.87409 89.99346 -4.066606 13.00482 90 -3.970457 13.07966 89.97414 -3.847821 13.01381 89.93905 -6.224507 8.790607 89.83346 -6.665707 9.077529 89.99346 -6.601439 9.124969 90 -6.795514 9.182748 90 -6.849192 9.135596 89.99346 -4.068225 13.35915 89.89132 -6.869325 9.079538 89.97414 -4.041134 13.38522 89.83346 -4.158689 13.5002 89.83346 -6.43309 8.904633 89.93905 -6.307475 8.836611 89.89132 -4.015853 13.13631 89.97414 -6 8.757935 89.76854 -5.894667 8.752018 89.7 -4.064124 13.2821 89.93905 -4.017461 13.04307 89.99346 -6.489655 8.975203 89.97414 -6.104133 8.783317 89.83346 -4.315789 13.66387 89.76854 -4.33288 13.68706 89.7 -4.104125 13.3246 89.93905 -6.221402 8.828079 89.89132 -6.423311 8.963237 89.97414 -4.184155 13.47253 89.89132 -6.301761 8.886107 89.93905 -4.061806 13.09842 89.99346 -4.197476 13.15934 90 -5.894971 8.759948 89.76854 -4.107836 13.24186 89.97414 -6 8.781322 89.83346 -4.330153 13.64542 89.83346 -6.478315 9.033677 89.99346 -6.403257 9.083415 90 -6.102693 8.820889 89.89132 -4.146934 13.2834 89.97414 -6.217287 8.877734 89.93905 -4.217901 13.43588 89.93905 -6.413507 9.021988 89.99346 -4.151658 13.20152 89.99346 -5.773562 8.767301 89.76854 -5.684621 8.768144 89.7 -4.500233 13.79556 89.76854 -4.505189 13.80825 89.7 -6.294947 8.945129 89.97414 -4.353248 13.61575 89.89132 -5.895867 8.783317 89.83346 -4.18985 13.24209 89.99346 -4.34066 13.30252 90 -6 8.818922 89.89132 -4.25814 13.39216 89.97414 -6.100784 8.870677 89.93905 -4.513024 13.77599 89.83346 -5.685531 8.776027 89.76854 -4.383851 13.57643 89.93905 -6.212381 8.936944 89.97414 -4.298481 13.34834 89.99346 -6.288116 9.004299 89.99346 -6.202319 9.058368 90 -4.690061 13.90894 89.76854 -4.68627 13.91591 89.7 -5.775493 8.790607 89.83346 -5.897307 8.820889 89.89132 -4.533589 13.74451 89.89132 -4.420343 13.52954 89.97414 -6 8.868747 89.93905 -4.701234 13.88839 89.83346 -6.098508 8.930047 89.97414 -4.560841 13.7028 89.93905 -6.207462 8.996304 89.99346 -5.688213 8.799259 89.83346 -4.878307 14.00214 89.76854 -4.875061 14.00938 89.7 -5.070454 14.08814 89.7 -4.456928 13.48254 89.99346 -4.495179 13.43339 90 -5.548671 8.795334 89.76854 -5.476424 8.800302 89.7 -4.719196 13.85536 89.89132 -5.778598 8.828079 89.89132 -5.899216 8.870677 89.93905 -4.593337 13.65306 89.97414 -4.887874 13.9808 89.83346 -5.477935 8.808092 89.76854 -4.742998 13.81159 89.93905 -6 8.92816 89.97414 -6.096227 8.989567 89.99346 -6 9.05 90 -5.692525 8.836611 89.89132 -5.073136 14.08067 89.76854 -4.625915 13.60319 89.99346 -4.659977 13.55106 90 -4.903255 13.94649 89.89132 -5.55252 8.818401 89.83346 -5.782713 8.877734 89.93905 -4.771381 13.75939 89.97414 -5.081041 14.05866 89.83346 -5.901492 8.930047 89.97414 -5.482388 8.831051 89.83346 -4.923637 13.90103 89.93905 -6 8.987723 89.99346 -5.273404 14.14405 89.76854 -5.271301 14.1517 89.7 -5.326863 8.841842 89.76854 -5.271301 8.848303 89.7 -4.799836 13.70707 89.99346 -4.833929 13.65471 90 -5.698239 8.886107 89.93905 -5.09375 14.02327 89.89132 -4.947941 13.84681 89.97414 -5.558709 8.855488 89.89132 -5.787619 8.936944 89.97414 -5.903773 8.989567 89.99346 -5.797681 9.058368 90 -5.279601 14.1215 89.83346 -5.110592 13.97638 89.93905 -5.489547 8.867963 89.89132 -5.477935 14.19191 89.76854 -5.476424 14.1997 89.7 -5.332604 8.864513 89.83346 -4.972306 13.79246 89.99346 -5.015846 13.74364 90 -5.705053 8.945129 89.97414 -5.289564 14.08524 89.89132 -5.56691 8.904633 89.93905 -5.548671 14.20467 89.76854 -5.684621 14.23186 89.7 -5.792538 8.996304 89.99346 -5.130675 13.92046 89.97414 -5.109653 8.906508 89.76854 -5.070454 8.911865 89.7 -5.482388 14.16895 89.83346 -5.499033 8.916877 89.93905 -5.302767 14.0372 89.93905 -5.341834 8.900962 89.89132 -5.711884 9.004299 89.99346 -5.596743 9.083415 90 -5.55252 14.1816 89.83346 -5.576689 8.963237 89.97414 -5.685531 14.22397 89.76854 -5.150808 13.8644 89.99346 -5.204486 13.81725 90 -5.117247 8.928627 89.83346 -5.489547 14.13204 89.89132 -5.510345 8.975203 89.97414 -5.773562 14.2327 89.76854 -5.894667 14.24798 89.7 -5.354065 8.949262 89.93905 -5.31851 13.97991 89.97414 -5.586493 9.021988 89.99346 -5.558709 14.14451 89.89132 -4.898525 8.98889 89.76854 -4.875061 8.990615 89.7 -5.688213 14.20074 89.83346 -5.129455 8.96419 89.89132 -5.499033 14.08312 89.93905 -5.521685 9.033677 89.99346 -5.398561 9.124969 90 -5.894971 14.24005 89.76854 -5.368651 9.006858 89.97414 -5.775493 14.20939 89.83346 -4.907919 9.010307 89.83346 -5.334293 13.92247 89.99346 -5.398561 13.87503 90 -5.145633 9.011315 89.93905 -5.56691 14.09537 89.93905 -5.692525 14.16339 89.89132 -5.383273 9.064598 89.99346 -6 14.24206 89.76854 -6.105333 14.24798 89.7 -4.694921 9.088426 89.76854 -4.68627 9.084091 89.7 -5.510345 14.0248 89.97414 -4.923023 9.04474 89.89132 -5.895867 14.21668 89.83346 -5.164925 9.067509 89.97414 -5.778598 14.17192 89.89132 -4.706052 9.108994 89.83346 -5.576689 14.03676 89.97414 -5.698239 14.11389 89.93905 -4.943038 9.090368 89.93905 -6.105029 14.24005 89.76854 -4.509503 9.198406 89.76854 -4.505189 9.191745 89.7 -6 14.21868 89.83346 -5.184265 9.123845 89.99346 -5.204486 9.182748 90 -5.521685 13.96632 89.99346 -4.723948 9.142062 89.89132 -5.596743 13.91659 90 -5.897307 14.17911 89.89132 -5.782713 14.12227 89.93905 -4.966904 9.144778 89.97414 -4.522215 9.218035 89.83346 -5.586493 13.97801 89.99346 -6.226438 14.2327 89.76854 -6.315379 14.23186 89.7 -4.747662 9.185882 89.93905 -5.705053 14.05487 89.97414 -4.337691 9.319256 89.76854 -6.104133 14.21668 89.83346 -4.33288 9.312945 89.7 -4.99083 9.199324 89.99346 -5.015846 9.256355 90 -6 14.18108 89.89132 -5.899216 14.12932 89.93905 -4.542653 9.249596 89.89132 -4.775939 9.238134 89.97414 -6.314469 14.22397 89.76854 -4.351868 9.337855 89.83346 -5.787619 14.06306 89.97414 -4.569736 9.291417 89.93905 -5.711884 13.9957 89.99346 -5.797681 13.94163 90 -4.175634 9.452903 89.76854 -6.224507 14.20939 89.83346 -4.170354 9.446979 89.7 -4.804289 9.290519 89.99346 -4.833929 9.345289 90 -6.102693 14.17911 89.89132 -4.374662 9.367758 89.89132 -6 14.13125 89.93905 -5.901492 14.06995 89.97414 -4.602031 9.341286 89.97414 -5.792538 14.0037 89.99346 -4.191193 9.470362 89.83346 -6.311787 14.20074 89.83346 -6.451329 14.20467 89.76854 -6.523576 14.1997 89.7 -4.404867 9.407383 89.93905 -6.221402 14.17192 89.89132 -4.024283 9.598563 89.76854 -4.018566 9.593061 89.7 -4.634408 9.391282 89.99346 -4.659977 9.448942 90 -6.100784 14.12932 89.93905 -3.982597 9.64285 89.76854 -3.878405 9.750333 89.7 -6.522065 14.19191 89.76854 -4.21621 9.498432 89.89132 -6 14.07184 89.97414 -5.903773 14.01043 89.99346 -6 13.95 90 -4.440885 9.454634 89.97414 -4.041134 9.61478 89.83346 -6.307475 14.16339 89.89132 -6.44748 14.1816 89.83346 -3.999803 9.658689 89.83346 -6.217287 14.12227 89.93905 -4.249359 9.535629 89.93905 -6.098508 14.06995 89.97414 -6.517612 14.16895 89.83346 -3.884527 9.755382 89.76854 -4.476994 9.502004 89.99346 -4.495179 9.566606 90 -6 14.01228 89.99346 -6.673137 14.15816 89.76854 -4.068225 9.640853 89.89132 -6.728699 14.1517 89.7 -6.301761 14.11389 89.93905 -3.836126 9.815789 89.76854 -3.750694 9.917874 89.7 -6.441291 14.14451 89.89132 -4.027467 9.684155 89.89132 -6.212381 14.06306 89.97414 -4.288889 9.579985 89.97414 -6.096227 14.01043 89.99346 -6.202319 13.94163 90 -6.510453 14.13204 89.89132 -3.902569 9.770261 89.83346 -6.667396 14.13549 89.83346 -4.104125 9.675403 89.93905 -6.294947 14.05487 89.97414 -3.757185 9.922439 89.76854 -6.43309 14.09537 89.93905 -3.854581 9.830153 89.83346 -6.207462 14.0037 89.99346 -4.328518 9.624452 89.99346 -4.34066 9.697476 90 -6.890347 14.09349 89.76854 -6.929546 14.08814 89.7 -4.064124 9.717901 89.93905 -6.500967 14.08312 89.93905 -3.931577 9.794184 89.89132 -6.658166 14.09904 89.89132 -3.704435 10.00023 89.76854 -3.636184 10.0947 89.7 -6.288116 13.9957 89.99346 -6.403257 13.91659 90 -4.146934 9.716603 89.97414 -6.423311 14.03676 89.97414 -6.882753 14.07137 89.83346 -3.776313 9.935894 89.83346 -3.884253 9.853248 89.89132 -6.489655 14.0248 89.97414 -4.107836 9.75814 89.97414 -6.645935 14.05074 89.93905 -3.970016 9.825885 89.93905 -6.413507 13.97801 89.99346 -3.643005 10.09875 89.76854 -7.101475 14.01111 89.76854 -7.124939 14.00938 89.7 -3.724014 10.01302 89.83346 -6.870545 14.03581 89.89132 -4.18985 9.757906 89.99346 -4.197476 9.84066 90 -6.478315 13.96632 89.99346 -6.601439 13.87503 90 -3.807067 9.957526 89.89132 -3.923571 9.883851 89.93905 -6.631349 13.99314 89.97414 -7.092081 13.98969 89.83346 -4.151658 9.798481 89.99346 -3.588426 10.19492 89.76854 -3.535545 10.27977 89.7 -6.854367 13.98868 89.93905 -6.616727 13.9354 89.99346 -4.015853 9.863686 89.97414 -7.305079 13.91157 89.76854 -7.31373 13.91591 89.7 -3.663107 10.1107 89.83346 -3.755491 10.03359 89.89132 -7.076977 13.95526 89.89132 -3.847821 9.986191 89.93905 -6.835075 13.93249 89.97414 -3.970457 9.920343 89.97414 -7.293948 13.89101 89.83346 -8.742065 11.5 89.76854 -8.741931 11.71051 89.7 -8.75 11.5 89.7 -3.542656 10.28329 89.76854 -3.608994 10.20605 89.83346 -7.056962 13.90963 89.93905 -4.061806 9.901583 89.99346 -4.066606 9.995179 90 -7.490497 13.80159 89.76854 -7.494811 13.80825 89.7 -3.695427 10.12992 89.89132 -6.815735 13.87615 89.99346 -6.795514 13.81725 90 -7.276052 13.85794 89.89132 -3.797203 10.06084 89.93905 -4.017461 9.956928 89.99346 -7.033096 13.85522 89.97414 -3.896417 10.02037 89.97414 -7.477785 13.78196 89.83346 -3.48889 10.39853 89.76854 -3.449368 10.472 89.7 -8.734019 11.2901 89.76854 -7.252338 13.81412 89.93905 -8.718678 11.5 89.83346 -3.563614 10.29367 89.83346 -8.741931 11.28949 89.7 -8.717771 11.08021 89.7 -3.642062 10.22395 89.89132 -7.662309 13.68074 89.76854 -7.66712 13.68706 89.7 -7.829646 13.55302 89.7 -8.710701 11.29189 89.83346 -3.738255 10.15538 89.93905 -7.00917 13.80068 89.99346 -8.709929 11.08143 89.76854 -6.984154 13.74364 90 -7.457347 13.7504 89.89132 -8.673211 11.29477 89.89132 -8.681078 11.5 89.89132 -3.456728 10.47497 89.76854 -3.846942 10.09334 89.97414 -7.224061 13.76187 89.97414 -8.686817 11.085 89.83346 -3.945135 10.05464 89.99346 -3.948942 10.15998 90 -7.648132 13.66215 89.83346 -3.510307 10.40792 89.83346 -8.623533 11.29858 89.93905 -8.631254 11.5 89.93905 -8.57184 11.5 89.97414 -8.669936 10.87521 89.76854 -7.430264 13.70858 89.93905 -3.59731 10.31035 89.89132 -8.677662 10.8734 89.7 -8.62184 10.67027 89.7 -7.824366 13.5471 89.76854 -3.685882 10.24766 89.93905 -8.649657 11.09074 89.89132 -7.195711 13.70948 89.99346 -3.789325 10.18574 89.97414 -7.166071 13.65471 90 -8.564294 11.30313 89.97414 -7.625338 13.63224 89.89132 -3.896806 10.12591 89.99346 -8.647165 10.88054 89.83346 -3.478419 10.48371 89.83346 -7.397969 13.65871 89.97414 -8.600416 11.09834 89.93905 -3.406508 10.60965 89.76854 -3.37816 10.67027 89.7 -8.614275 10.67266 89.76854 -7.808807 13.52964 89.83346 -3.54474 10.42302 89.89132 -8.504905 11.30769 89.99346 -7.595133 13.59262 89.93905 -8.512276 11.5 89.99347 -8.45 11.5 90 -8.441632 11.29768 90 -7.975717 13.40144 89.76854 -7.981434 13.40694 89.7 -8.610554 10.88911 89.89132 -3.641961 10.33246 89.93905 -7.365592 13.60872 89.99346 -3.385725 10.67266 89.76854 -7.340023 13.55106 90 -8.593492 10.60965 89.76854 -8.550632 10.472 89.7 -8.017403 13.35715 89.76854 -8.121595 13.24967 89.7 -8.541699 11.10741 89.97414 -3.738134 10.27594 89.97414 -3.840523 10.21618 89.99346 -3.845289 10.33393 90 -8.591978 10.67972 89.83346 -7.78379 13.50157 89.89132 -3.513293 10.49777 89.89132 -7.559115 13.54537 89.97414 -3.428627 10.61725 89.83346 -8.562039 10.90046 89.93905 -8.571373 10.61725 89.83346 -7.958866 13.38522 89.83346 -3.590368 10.44304 89.93905 -8.543272 10.47497 89.76854 -8.000197 13.34131 89.83346 -8.482834 11.1165 89.99346 -3.695206 10.35882 89.97414 -8.416585 11.09674 90 -8.55613 10.69106 89.89132 -7.750641 13.46437 89.93905 -3.408022 10.67972 89.83346 -3.790519 10.30429 89.99346 -8.115473 13.24462 89.76854 -8.51111 10.39853 89.76854 -8.464455 10.27977 89.7 -7.523006 13.498 89.99346 -7.504821 13.43339 90 -3.341842 10.82686 89.76854 -8.504189 10.914 89.97414 -3.322338 10.8734 89.7 -7.931775 13.35915 89.89132 -3.559506 10.51639 89.93905 -8.163874 13.18421 89.76854 -8.53581 10.62946 89.89132 -8.249306 13.08213 89.7 -3.46419 10.62946 89.89132 -8.521581 10.48371 89.83346 -7.972533 13.31584 89.89132 -3.748584 10.38525 89.99346 -3.756355 10.51585 90 -8.508628 10.7061 89.93905 -3.644778 10.4669 89.97414 -7.711111 13.42002 89.97414 -8.097431 13.22974 89.83346 -8.457344 10.28329 89.76854 -8.489693 10.40792 89.83346 -3.44387 10.69106 89.89132 -3.364513 10.8326 89.83346 -7.895875 13.3246 89.93905 -8.446192 10.92757 89.99346 -8.375031 10.89856 90 -8.488685 10.64563 89.93905 -3.614612 10.5386 89.97414 -8.242815 13.07756 89.76854 -3.511315 10.64563 89.93905 -8.145419 13.16985 89.83346 -8.486707 10.49777 89.89132 -3.699324 10.49083 89.99346 -7.671482 13.37555 89.99346 -7.65934 13.30252 90 -8.411574 10.19492 89.76854 -7.935876 13.2821 89.93905 -8.363816 10.0947 89.7 -3.295334 11.04867 89.76854 -3.282229 11.08021 89.7 -8.451983 10.72402 89.97414 -8.068423 13.20582 89.89132 -8.436386 10.29367 89.83346 -3.491372 10.7061 89.93905 -8.295565 12.99977 89.76854 -8.363816 12.9053 89.7 -3.400962 10.84183 89.89132 -7.853066 13.2834 89.97414 -8.45526 10.42302 89.89132 -3.669857 10.56087 89.99346 -3.682748 10.70449 90 -8.432491 10.66492 89.97414 -8.223687 13.06411 89.83346 -3.567509 10.66492 89.97414 -8.440494 10.51639 89.93905 -8.115747 13.14675 89.89132 -3.318401 11.05252 89.83346 -8.356995 10.09875 89.76854 -7.892164 13.24186 89.97414 -8.391006 10.20605 89.83346 -3.548017 10.72402 89.97414 -8.029984 13.17412 89.93905 -8.395195 10.74199 89.99346 -8.317252 10.70449 90 -3.449262 10.85407 89.93905 -8.40269 10.31035 89.89132 -3.623845 10.68427 89.99346 -8.356995 12.90125 89.76854 -8.275986 12.98698 89.83346 -8.409632 10.44304 89.93905 -3.267301 11.27356 89.76854 -3.258069 11.28949 89.7 -7.81015 13.24209 89.99346 -8.376155 10.68427 89.99346 -7.802524 13.15934 90 -3.355488 11.05871 89.89132 -8.192933 13.04247 89.89132 -8.295565 10.00023 89.76854 -8.249306 9.917874 89.7 -3.604805 10.74199 89.99346 -8.076429 13.11615 89.93905 -8.385388 10.5386 89.97414 -3.624969 10.89856 90 -3.506858 10.86865 89.97414 -7.848342 13.20152 89.99346 -8.336893 10.1107 89.83346 -3.290607 11.27549 89.83346 -8.411574 12.80508 89.76854 -8.464455 12.72023 89.7 -8.357938 10.22395 89.89132 -3.404633 11.06691 89.93905 -7.984147 13.13631 89.97414 -8.358039 10.33246 89.93905 -8.336893 12.8893 89.83346 -3.564598 10.88327 89.99346 -8.355222 10.4669 89.97414 -8.244509 12.96641 89.89132 -8.242815 9.922439 89.76854 -8.152179 13.01381 89.93905 -3.257935 11.5 89.76854 -3.25 11.5 89.7 -8.330143 10.56087 89.99346 -8.243645 10.51585 90 -3.328079 11.2786 89.89132 -8.029543 13.07966 89.97414 -8.275986 10.01302 89.83346 -8.304573 10.12992 89.89132 -8.457344 12.71671 89.76854 -3.463237 11.07669 89.97414 -3.281322 11.5 89.83346 -8.391006 12.79395 89.83346 -8.314118 10.24766 89.93905 -7.938194 13.09842 89.99346 -7.933394 13.00482 90 -8.300676 10.49083 89.99346 -3.377734 11.28271 89.93905 -8.304573 12.87008 89.89132 -8.304794 10.35882 89.97414 -3.265981 11.7099 89.76854 -8.202797 12.93916 89.93905 -8.163874 9.815789 89.76854 -3.258069 11.71051 89.7 -8.121595 9.750333 89.7 -3.521988 11.08649 89.99346 -7.982539 13.04307 89.99346 -3.583415 11.09674 90 -8.223687 9.935894 89.83346 -3.318922 11.5 89.89132 -8.103583 12.97963 89.97414 -8.244509 10.03359 89.89132 -8.51111 12.60147 89.76854 -8.550632 12.528 89.7 -3.436944 11.28762 89.97414 -8.261745 10.15538 89.93905 -8.436386 12.70633 89.83346 -3.289299 11.70811 89.83346 -8.115473 9.755382 89.76854 -8.357938 12.77605 89.89132 -8.261866 10.27594 89.97414 -8.261745 12.84462 89.93905 -3.368747 11.5 89.93905 -8.251416 10.38525 89.99346 -3.290071 11.91857 89.76854 -3.282229 11.91979 89.7 -3.322338 12.1266 89.7 -8.154711 10.33393 90 -8.145419 9.830153 89.83346 -8.543272 12.52503 89.76854 -3.496304 11.29254 89.99346 -8.153058 12.90666 89.97414 -3.558368 11.29768 90 -8.054865 12.94536 89.99346 -8.192933 9.957526 89.89132 -3.326789 11.70523 89.89132 -8.051058 12.84002 90 -8.489693 12.59208 89.83346 -8.202797 10.06084 89.93905 -3.42816 11.5 89.97414 -8.210675 10.18574 89.97414 -8.40269 12.68965 89.89132 -3.313183 11.915 89.83346 -8.097431 9.770261 89.83346 -8.314118 12.75234 89.93905 -3.376467 11.70142 89.93905 -8.209481 10.30429 89.99346 -8.210675 12.81426 89.97414 -3.330064 12.12479 89.76854 -8.017403 9.64285 89.76854 -8.103194 12.87409 89.99346 -7.981434 9.593061 89.7 -3.487723 11.5 89.99346 -8.115747 9.853248 89.89132 -3.55 11.5 90 -8.521581 12.51629 89.83346 -3.350343 11.90926 89.89132 -8.593492 12.39035 89.76854 -8.62184 12.32973 89.7 -8.152179 9.986191 89.93905 -8.45526 12.57698 89.89132 -3.435706 11.69687 89.97414 -7.975717 9.598563 89.76854 -8.358039 12.66754 89.93905 -8.153058 10.09334 89.97414 -3.352835 12.11946 89.83346 -8.159477 10.21618 89.99346 -3.399584 11.90166 89.93905 -8.614275 12.32734 89.76854 -8.051058 10.15998 90 -8.068423 9.794184 89.89132 -8.261866 12.72406 89.97414 -3.385725 12.32734 89.76854 -3.37816 12.32973 89.7 -8.000197 9.658689 89.83346 -3.495095 11.69231 89.99346 -3.558368 11.70232 90 -8.159477 12.78382 89.99346 -8.154711 12.66607 90 -8.486707 12.50223 89.89132 -3.389446 12.11089 89.89132 -8.076429 9.883851 89.93905 -3.406508 12.39035 89.76854 -8.103583 10.02037 89.97414 -8.571373 12.38275 89.83346 -3.449368 12.528 89.7 -3.458301 11.89259 89.97414 -7.958866 9.61478 89.83346 -8.409632 12.55696 89.93905 -3.408022 12.32028 89.83346 -8.103194 10.12591 89.99346 -8.304794 12.64118 89.97414 -3.437961 12.09954 89.93905 -7.85715 9.482597 89.76854 -7.829646 9.446979 89.7 -3.428627 12.38275 89.83346 -8.029984 9.825885 89.93905 -8.591978 12.32028 89.83346 -8.209481 12.69571 89.99346 -3.456728 12.52503 89.76854 -7.972533 9.684155 89.89132 -8.658158 12.17314 89.76854 -8.677662 12.1266 89.7 -3.517166 11.8835 89.99346 -3.583415 11.90326 90 -8.054865 10.05464 89.99346 -3.44387 12.30894 89.89132 -8.440494 12.48361 89.93905 -7.933394 9.995179 90 -8.029543 9.920343 89.97414 -3.48889 12.60147 89.76854 -8.53581 12.37054 89.89132 -7.931775 9.640853 89.89132 -3.535545 12.72023 89.7 -8.251416 12.61475 89.99346 -8.243645 12.48415 90 -3.495811 12.086 89.97414 -7.841311 9.499803 89.83346 -3.46419 12.37054 89.89132 -8.355222 12.5331 89.97414 -7.984147 9.863686 89.97414 -8.55613 12.30894 89.89132 -3.478419 12.51629 89.83346 -7.935876 9.717901 89.93905 -3.491372 12.2939 89.93905 -7.982539 9.956928 89.99346 -8.635487 12.1674 89.83346 -7.684211 9.336126 89.76854 -8.385388 12.4614 89.97414 -3.542656 12.71671 89.76854 -7.66712 9.312945 89.7 -8.488685 12.35437 89.93905 -7.895875 9.675403 89.93905 -3.510307 12.59208 89.83346 -8.300676 12.50917 89.99346 -3.553808 12.07243 89.99346 -3.624969 12.10144 90 -7.815845 9.527467 89.89132 -8.704666 11.95133 89.76854 -8.717771 11.91979 89.7 -3.511315 12.35437 89.93905 -7.938194 9.901583 89.99346 -7.802524 9.84066 90 -3.513293 12.50223 89.89132 -7.892164 9.75814 89.97414 -8.508628 12.2939 89.93905 -3.588426 12.80508 89.76854 -3.636184 12.9053 89.7 -8.599038 12.15817 89.89132 -7.669847 9.354581 89.83346 -3.548017 12.27598 89.97414 -7.853066 9.716603 89.97414 -8.330143 12.43913 89.99346 -8.317252 12.29551 90 -8.432491 12.33508 89.97414 -7.782099 9.564124 89.93905 -3.563614 12.70633 89.83346 -7.848342 9.798481 89.99346 -3.54474 12.57698 89.89132 -8.681599 11.94748 89.83346 -7.499767 9.204435 89.76854 -3.567509 12.33508 89.97414 -8.451983 12.27598 89.97414 -7.494811 9.191745 89.7 -3.559506 12.48361 89.93905 -8.550738 12.14593 89.93905 -7.646752 9.384253 89.89132 -7.81015 9.757906 89.99346 -8.376155 12.31573 89.99346 -3.643005 12.90125 89.76854 -7.65934 9.697476 90 -7.74186 9.607836 89.97414 -3.608994 12.79395 89.83346 -8.732699 11.72644 89.76854 -3.604805 12.25801 89.99346 -3.682748 12.29551 90 -7.486976 9.224014 89.83346 -8.644512 11.94129 89.89132 -3.59731 12.68965 89.89132 -7.616149 9.423571 89.93905 -8.395195 12.25801 89.99346 -7.701519 9.651658 89.99346 -3.590368 12.55696 89.93905 -8.375031 12.10144 90 -8.493142 12.13135 89.97414 -7.309939 9.091063 89.76854 -3.623845 12.31573 89.99346 -8.709393 11.72451 89.83346 -3.704435 12.99977 89.76854 -3.750694 13.08213 89.7 -7.31373 9.084091 89.7 -7.466411 9.255491 89.89132 -8.595367 11.93309 89.93905 -3.614612 12.4614 89.97414 -7.579657 9.470457 89.97414 -3.663107 12.8893 89.83346 -8.435402 12.11673 89.99346 -7.298766 9.111608 89.83346 -3.642062 12.77605 89.89132 -8.671921 11.7214 89.89132 -3.641961 12.66754 89.93905 -7.439159 9.297203 89.93905 -8.536763 11.92331 89.97414 -3.644778 12.5331 89.97414 -7.121693 8.997856 89.76854 -8.622266 11.71729 89.93905 -7.124939 8.990615 89.7 -6.929546 8.911865 89.7 -3.757185 13.07756 89.76854 -7.543072 9.517461 89.99346 -3.669857 12.43913 89.99346 -7.504821 9.566606 90 -8.478012 11.91351 89.99346 -3.756355 12.48415 90 -8.416585 11.90326 90 -7.280804 9.14464 89.89132 -3.724014 12.98698 89.83346 -8.563056 11.71238 89.97414 -7.406663 9.346942 89.97414 -3.695427 12.87008 89.89132 -8.503696 11.70746 89.99346 -8.441632 11.70232 90 -7.112126 9.019196 89.83346 -3.685882 12.75234 89.93905 -3.699324 12.50917 89.99346 -7.257002 9.188412 89.93905 -3.695206 12.64118 89.97414 -6.926864 8.919333 89.76854 -3.836126 13.18421 89.76854 -7.374085 9.396806 89.99346 -7.340023 9.448942 90 -3.878405 13.24967 89.7 -3.776313 13.06411 89.83346 -7.096745 9.053506 89.89132 -3.755491 12.96641 89.89132 -7.228619 9.240607 89.97414 -3.738255 12.84462 89.93905 -6.918959 8.941343 89.83346 -7.076363 9.098972 89.93905 -3.884527 13.24462 89.76854 -3.738134 12.72406 89.97414 -3.748584 12.61475 89.99346 -6.726596 8.855955 89.76854 -6.728699 8.848303 89.7 -6.523576 8.800302 89.7 -3.845289 12.66607 90 -7.200164 9.292934 89.99346 -7.166071 9.345289 90 -3.854581 13.16985 89.83346 -6.90625 8.97673 89.89132 -3.807067 13.04247 89.89132 -7.052059 9.153187 89.97414 -3.797203 12.93916 89.93905 -6.720399 8.878505 89.83346 -3.789325 12.81426 89.97414 -6.889408 9.023622 89.93905 -6.522065 8.808092 89.76854 -3.790519 12.69571 89.99346 -7.027694 9.207539 89.99346 -6.984154 9.256355 90 -3.982597 13.35715 89.76854 -6.710436 8.914761 89.89132 -6.315379 8.768144 89.7 -6.517612 8.831051 89.83346 -3.840523 12.78382 89.99346 -6.386311 10.00798 87.9809 -6.320438 9.992458 87.9809 -6.391452 9.988123 87.99239 -5.094093 12.74687 87.9809 -5.184749 12.80795 87.9809 -5.082037 12.76347 87.99239 -5.1739 12.82535 87.99239 -4.700962 12.25 87.9 -4.786475 12.38168 87.9 -4.784239 12.3833 87.92334 -4.883229 12.50554 87.92334 -6.614538 10.11972 87.9454 -6.529279 10.0709 87.96494 -6.61985 10.10779 87.96494 -6.242284 9.918451 88 -6.401044 9.951077 88 -6.328603 9.954047 87.99808 -4.980272 12.63252 87.96494 -4.968722 12.64535 87.9809 -6.324702 9.972396 87.99239 -6.23933 9.937735 87.99808 -6.23649 9.956278 87.99239 -6.476264 10.03421 87.9809 -6.535274 10.05472 87.9809 -4.877183 12.51099 87.9454 -4.989011 12.62282 87.9454 -4.867477 12.51973 87.96494 -5.163977 12.84127 87.99808 -5.071011 12.77864 87.99808 -6.751382 10.19857 87.92334 -6.665391 10.14351 87.9454 -6.75545 10.19152 87.9454 -5.153658 12.85783 88 -6.794908 10.22469 87.92334 -5.02063 12.76524 88 -4.777657 12.38808 87.9454 -6.671143 10.13178 87.96494 -4.629682 12.1101 87.9 -4.698569 12.25138 87.92334 -6.881678 10.28647 87.9 -6.883302 10.28424 87.92334 -6.482602 10.0147 87.99239 -4.954998 12.66059 87.99239 -6.396154 9.969963 87.99808 -4.854649 12.53128 87.9809 -6.799211 10.21778 87.9454 -4.767091 12.39576 87.96494 -6.626871 10.09202 87.9809 -4.942445 12.67453 87.99808 -6.542398 10.03548 87.99239 -4.897653 12.65967 88 -4.691523 12.25545 87.9454 -6.76198 10.18021 87.96494 -6.678745 10.11628 87.9809 -4.627158 12.11123 87.92334 -6.555688 9.999597 88 -6.488399 9.996864 87.99808 -4.839407 12.545 87.99239 -6.888084 10.27766 87.9454 -4.753126 12.40591 87.9809 -6.80612 10.2067 87.96494 -4.680212 12.26198 87.96494 -7.003696 10.38528 87.9 -7.005545 10.38323 87.92334 -7.114717 10.4963 87.9 -4.825466 12.55755 87.99808 -4.785987 12.5422 88 -6.635213 10.07329 87.99239 -6.548913 10.01789 87.99808 -4.619725 12.11454 87.9454 -6.770611 10.16526 87.9809 -4.736533 12.41796 87.99239 -6.687777 10.09787 87.99239 -4.570787 11.96438 87.92334 -4.573415 11.96353 87.9 -4.532779 11.81187 87.9 -6.895761 10.26709 87.96494 -4.665263 12.27061 87.9809 -6.815251 10.19205 87.9809 -6.704631 10.06351 88 -6.642844 10.05615 87.99808 -4.607794 12.11985 87.96494 -7.010989 10.37718 87.9454 -4.721356 12.42899 87.99808 -4.686778 12.41403 88 -6.696039 10.08103 87.99808 -4.563049 11.96689 87.9454 -6.780866 10.1475 87.99239 -7.116771 10.49446 87.92334 -7.213525 10.61832 87.9 -4.647501 12.28087 87.99239 -4.530076 11.81244 87.92334 -6.905907 10.25313 87.9809 -6.8261 10.17465 87.99239 -4.592024 12.12687 87.9809 -7.019728 10.36748 87.96494 -4.550628 11.97093 87.96494 -6.846342 10.14217 88 -6.790245 10.13125 87.99808 -4.631255 12.29025 87.99808 -7.122817 10.48901 87.9454 -4.601045 12.27648 88 -6.836023 10.15873 87.99808 -4.522117 11.81413 87.9454 -6.917963 10.23653 87.99239 -4.573287 12.13521 87.99239 -4.505469 11.65708 87.92334 -4.508217 11.65679 87.9 -7.299038 10.75 87.9 -7.215761 10.6167 87.92334 -4.5 11.5 87.9 -4.497239 11.5 87.92335 -4.489102 11.5 87.9454 -4.534211 11.97626 87.9809 -7.031278 10.35465 87.9809 -4.509343 11.81685 87.96494 -7.132523 10.48027 87.96494 -4.529668 12.13097 88 -4.55615 12.14284 87.99808 -6.97937 10.23476 88 -6.928989 10.22136 87.99808 -4.497378 11.65793 87.9454 -7.222343 10.61192 87.9454 -4.514705 11.9826 87.99239 -7.045002 10.33941 87.99239 -4.492458 11.82044 87.9809 -7.370318 10.8899 87.9 -7.301431 10.74862 87.92334 -4.484389 11.6593 87.96494 -4.476039 11.5 87.96494 -4.458778 11.5 87.9809 -4.496864 11.9884 87.99808 -7.145351 10.46872 87.9809 -4.473377 11.97898 88 -4.472396 11.8247 87.99239 -7.232909 10.60424 87.96494 -4.467221 11.6611 87.9809 -7.102347 10.34033 88 -7.057555 10.32547 87.99808 -4.454047 11.8286 87.99808 -7.308477 10.74455 87.9454 -4.432752 11.82208 88 -4.446824 11.66325 87.99239 -4.43827 11.5 87.99239 -4.419511 11.5 87.99808 -7.372842 10.88877 87.92334 -4.408209 11.66187 88 -4.428167 11.66521 87.99808 -7.160593 10.455 87.99239 -7.246874 10.59409 87.9809 -7.319788 10.73802 87.96494 -7.214013 10.4578 88 -7.174534 10.44245 87.99808 -7.380275 10.88546 87.9454 -7.426585 11.03647 87.9 -7.429213 11.03562 87.92334 -7.467221 11.18813 87.9 -7.263467 10.58204 87.99239 -7.334737 10.72939 87.9809 -7.392206 10.88015 87.96494 -7.313222 10.58597 88 -7.278644 10.57101 87.99808 -7.436951 11.03311 87.9454 -7.491783 11.34321 87.9 -7.469924 11.18756 87.92334 -7.352499 10.71913 87.99239 -7.407976 10.87313 87.9809 -7.449372 11.02907 87.96494 -7.398955 10.72352 88 -7.368745 10.70975 87.99808 -7.477883 11.18587 87.9454 -7.494531 11.34292 87.92334 -7.426713 10.86479 87.99239 -7.465789 11.02374 87.9809 -7.490657 11.18315 87.96494 -7.470332 10.86903 88 -7.44385 10.85716 87.99808 -7.502622 11.34207 87.9454 -7.5 11.5 87.9 -7.502763 11.5 87.92334 -7.485295 11.0174 87.99239 -7.507542 11.17956 87.9809 -7.515611 11.3407 87.96494 -7.526623 11.02102 88 -7.503136 11.0116 87.99808 -7.510899 11.5 87.9454 -7.491783 11.65679 87.9 -7.495053 11.65203 87.92334 -7.527604 11.1753 87.99239 -7.532779 11.3389 87.9809 -7.523959 11.5 87.96494 -7.567248 11.17792 88 -7.545953 11.1714 87.99808 -7.503147 11.65286 87.9454 -7.467221 11.81187 87.9 -7.472001 11.8025 87.92334 -7.553176 11.33675 87.99239 -7.541221 11.5 87.9809 -7.51614 11.65418 87.96494 -7.571833 11.33479 87.99808 -7.591791 11.33813 88 -7.479971 11.80414 87.9454 -7.426585 11.96353 87.9 -7.433845 11.94987 87.92334 -7.561732 11.5 87.99239 -7.533314 11.65592 87.9809 -7.492764 11.80677 87.96494 -7.580491 11.5 87.99808 -7.6 11.5 88 -7.441608 11.95231 87.9454 -7.380976 12.09262 87.92334 -7.370318 12.1101 87.9 -7.553719 11.658 87.99239 -7.509673 11.81025 87.9809 -7.454069 11.95622 87.96494 -7.572382 11.6599 87.99808 -7.591791 11.66187 88 -7.388453 12.09583 87.9454 -7.313936 12.22929 87.92334 -7.299038 12.25 87.9 -7.529763 11.81437 87.99239 -7.47054 11.96138 87.9809 -7.400454 12.10098 87.96494 -7.548138 11.81815 87.99808 -7.567248 11.82208 88 -7.32105 12.23324 87.9454 -7.213525 12.38168 87.9 -7.233413 12.35848 87.92334 -7.490109 11.96752 87.99239 -7.416318 12.10779 87.9809 -7.332469 12.23958 87.96494 -7.508008 11.97314 87.99808 -7.526623 11.97898 88 -7.240091 12.36313 87.9454 -7.140234 12.47886 87.92334 -7.114717 12.5037 87.9 -7.435166 12.11588 87.99239 -7.347562 12.24796 87.9809 -4.4 11.5 88 -4.508217 11.34321 87.9 -4.504947 11.34797 87.92334 -7.25081 12.37059 87.96494 -7.452405 12.12328 87.99808 -4.496853 11.34714 87.9454 -7.470332 12.13097 88 -7.146407 12.48416 87.9454 -4.532779 11.18813 87.9 -4.527999 11.1975 87.92334 -7.035354 12.58919 87.92334 -7.003696 12.61472 87.9 -4.48386 11.34582 87.96494 -7.365495 12.25791 87.99239 -4.520029 11.19586 87.9454 -7.264978 12.38045 87.9809 -4.573415 11.03647 87.9 -4.566155 11.05013 87.92334 -7.156317 12.49267 87.96494 -7.381897 12.26702 87.99808 -4.466686 11.34408 87.9809 -7.398955 12.27648 88 -7.04096 12.59509 87.9454 -4.507236 11.19323 87.96494 -6.91985 12.68835 87.92334 -4.558392 11.04769 87.9454 -6.881678 12.71353 87.9 -4.629682 10.8899 87.9 -4.619024 10.90738 87.92334 -7.281812 12.39217 87.99239 -7.169414 12.50391 87.9809 -4.446281 11.342 87.99239 -7.049958 12.60455 87.96494 -4.490327 11.18975 87.9809 -7.297209 12.40288 87.99808 -7.313222 12.41403 88 -4.545931 11.04378 87.96494 -6.924831 12.69478 87.9454 -4.427618 11.3401 87.99808 -4.408209 11.33813 88 -6.794908 12.77531 87.92334 -6.75 12.79904 87.9 -4.611547 10.90417 87.9454 -7.184977 12.51727 87.99239 -4.700962 10.75 87.9 -4.686064 10.77071 87.92334 -7.061851 12.61707 87.9809 -4.470237 11.18563 87.99239 -4.52946 11.03862 87.9809 -6.751382 12.80143 87.92334 -6.932825 12.70511 87.96494 -4.599546 10.89902 87.96494 -7.19921 12.52949 87.99808 -4.451862 11.18185 87.99808 -4.432752 11.17792 88 -7.214013 12.5422 88 -6.799211 12.78222 87.9454 -4.67895 10.76676 87.9454 -6.610105 12.87032 87.9 -6.661808 12.84919 87.92334 -4.786475 10.61832 87.9 -4.766587 10.64152 87.92334 -7.075981 12.63193 87.99239 -4.509891 11.03248 87.99239 -6.75545 12.80848 87.9454 -6.943391 12.71876 87.9809 -4.583682 10.89221 87.9809 -6.611229 12.87284 87.92334 -4.667531 10.76042 87.96494 -4.473377 11.02102 88 -4.491992 11.02686 87.99808 -6.80612 12.7933 87.96494 -4.759909 10.63687 87.9454 -7.088906 12.64553 87.99808 -4.885283 10.4963 87.9 -4.859766 10.52114 87.92334 -7.102347 12.65967 88 -6.665391 12.85649 87.9454 -4.564834 10.88412 87.99239 -6.76198 12.81979 87.96494 -6.463525 12.92658 87.9 -6.521917 12.90922 87.92334 -4.652438 10.75204 87.9809 -6.955945 12.73498 87.99239 -4.74919 10.62941 87.96494 -4.529668 10.86903 88 -4.547595 10.87672 87.99808 -6.614538 12.88028 87.9454 -4.853593 10.51584 87.9454 -6.815251 12.80795 87.9809 -4.996304 10.38528 87.9 -4.964646 10.41081 87.92334 -6.464379 12.92921 87.92334 -4.634505 10.74209 87.99239 -4.735022 10.61955 87.9809 -6.671143 12.86822 87.96494 -6.770611 12.83474 87.9809 -6.967428 12.74981 87.99808 -4.843683 10.50733 87.96494 -6.97937 12.76524 88 -4.601045 10.72352 88 -4.618103 10.73298 87.99808 -6.524743 12.91685 87.9454 -4.95904 10.40491 87.9454 -6.61985 12.89221 87.96494 -5.118322 10.28647 87.9 -5.08015 10.31165 87.92334 -6.376671 12.95479 87.92334 -6.311868 12.96722 87.9 -6.8261 12.82535 87.99239 -4.718188 10.60783 87.99239 -6.466894 12.93695 87.9454 -4.830586 10.49609 87.9809 -6.678745 12.88372 87.9809 -4.950042 10.39545 87.96494 -6.312442 12.96992 87.92334 -4.702791 10.59712 87.99808 -4.686778 10.58597 88 -6.780866 12.8525 87.99239 -5.075169 10.30522 87.9454 -5.25 10.20096 87.9 -5.205092 10.22469 87.92334 -6.529279 12.9291 87.96494 -6.626871 12.90798 87.9809 -4.815023 10.48273 87.99239 -6.836023 12.84127 87.99808 -6.846342 12.85783 88 -6.378711 12.96267 87.9454 -4.938149 10.38293 87.9809 -6.470929 12.94937 87.96494 -5.248618 10.19857 87.92334 -6.22756 12.98543 87.92334 -5.067175 10.29489 87.96494 -6.156793 12.99178 87.9 -4.785987 10.4578 88 -4.80079 10.47051 87.99808 -6.790245 12.86875 87.99808 -6.704631 12.93649 88 -6.687777 12.90213 87.99239 -5.200789 10.21778 87.9454 -6.314134 12.97788 87.9454 -5.389895 10.12968 87.9 -5.338192 10.15081 87.92334 -6.535274 12.94528 87.9809 -4.924019 10.36807 87.99239 -6.635213 12.92671 87.99239 -5.24455 10.19152 87.9454 -5.056609 10.28124 87.9809 -6.157082 12.99453 87.92334 -6.381984 12.97531 87.96494 -6.476264 12.96579 87.9809 -5.388771 10.12716 87.92334 -5.19388 10.2067 87.96494 -6.696039 12.91897 87.99808 -4.911094 10.35447 87.99808 -6.228792 12.99348 87.9454 -4.897653 10.34033 88 -6.316849 12.99066 87.96494 -5.334609 10.14351 87.9454 -6.076114 13.00083 87.92334 -6 13 87.9 -5.23802 10.18021 87.96494 -6.542398 12.96452 87.99239 -5.536475 10.07342 87.9 -5.478083 10.09078 87.92334 -6.642844 12.94385 87.99808 -5.044055 10.26502 87.99239 -6.555688 13.0004 88 -6.157932 13.00262 87.9454 -5.385462 10.11972 87.9454 -6.386311 12.99202 87.9809 -5.184749 10.19205 87.9809 -6.482602 12.9853 87.99239 -5.535621 10.07079 87.92334 -5.328857 10.13178 87.96494 -6 13.00276 87.92334 -6.23077 13.00639 87.96494 -5.229389 10.16526 87.9809 -6.548913 12.98211 87.99808 -5.02063 10.23476 88 -5.032572 10.25019 87.99808 -6.320438 13.00754 87.9809 -5.475257 10.08315 87.9454 -6.076526 13.00896 87.9454 -5.38015 10.10779 87.96494 -5.923886 13.00083 87.92334 -5.688132 10.03278 87.9 -5.623329 10.04521 87.92334 -5.843207 12.99178 87.9 -6.159297 13.01561 87.96494 -5.1739 10.17465 87.99239 -6.391452 13.01188 87.99239 -5.533106 10.06305 87.9454 -6.488399 13.00314 87.99808 -5.321255 10.11628 87.9809 -6.401044 13.04892 88 -6 13.0109 87.9454 -5.219134 10.1475 87.99239 -5.687558 10.03008 87.92334 -6.233384 13.02345 87.9809 -6.324702 13.0276 87.99239 -5.470721 10.0709 87.96494 -5.842918 12.99453 87.92334 -5.373129 10.09202 87.9809 -6.077187 13.022 87.96494 -5.153658 10.14217 88 -5.163977 10.15873 87.99808 -6.396154 13.03004 87.99808 -5.621289 10.03733 87.9454 -5.923474 13.00896 87.9454 -5.529071 10.05063 87.96494 -6.161102 13.03278 87.9809 -5.843207 10.00822 87.9 -5.77244 10.01457 87.92334 -5.77244 12.98543 87.92334 -5.688132 12.96722 87.9 -5.209755 10.13125 87.99808 -5.295369 10.06351 88 -5.312223 10.09787 87.99239 -6 13.02396 87.96494 -5.685866 10.02212 87.9454 -6.23649 13.04372 87.99239 -6.328603 13.04595 87.99808 -5.464726 10.05472 87.9809 -6.242284 13.08155 88 -5.842068 13.00262 87.9454 -5.842918 10.00547 87.92334 -6.078062 13.03924 87.9809 -5.364787 10.07329 87.99239 -5.618016 10.02469 87.96494 -5.922813 13.022 87.96494 -5.523736 10.03421 87.9809 -5.687558 12.96992 87.92334 -5.303961 10.08103 87.99808 -6.163245 13.05318 87.99239 -6.23933 13.06227 87.99808 -5.771208 10.00652 87.9454 -5.683151 10.00934 87.96494 -5.771208 12.99348 87.9454 -6 13.04122 87.9809 -6 10 87.9 -5.923886 9.999166 87.92334 -5.536475 12.92658 87.9 -5.623329 12.95479 87.92334 -5.457602 10.03548 87.99239 -5.840703 13.01561 87.96494 -5.444312 9.999597 88 -5.357156 10.05615 87.99808 -5.842068 9.997378 87.9454 -6.0791 13.05973 87.99239 -6.165206 13.07183 87.99808 -5.613689 10.00798 87.9809 -6.081039 13.09795 88 -5.921938 13.03924 87.9809 -6 9.997237 87.92334 -5.517398 10.0147 87.99239 -5.685866 12.97788 87.9454 -5.76923 9.993614 87.96494 -5.76923 13.00639 87.96494 -5.451087 10.01789 87.99808 -5.535621 12.92921 87.92334 -5.679562 9.992458 87.9809 -6 13.06173 87.99239 -6.080051 13.07846 87.99808 -5.923474 9.99104 87.9454 -6.156793 10.00822 87.9 -6.076114 9.999166 87.92334 -5.621289 12.96267 87.9454 -5.840703 9.984389 87.96494 -5.838898 13.03278 87.9809 -5.608548 9.988123 87.99239 -5.389895 12.87032 87.9 -5.478083 12.90922 87.92334 -5.511601 9.996864 87.99808 -5.598956 9.951077 88 -5.9209 13.05973 87.99239 -5.683151 12.99066 87.96494 -6 9.989101 87.9454 -6 13.08049 87.99808 -5.918961 13.09795 88 -5.766616 9.976551 87.9809 -5.766616 13.02345 87.9809 -6.157082 10.00547 87.92334 -5.533106 12.93695 87.9454 -5.675298 9.972396 87.99239 -5.618016 12.97531 87.96494 -5.922813 9.977997 87.96494 -5.836755 13.05318 87.99239 -5.603846 9.969963 87.99808 -5.388771 12.87284 87.92334 -6.076526 9.99104 87.9454 -5.838898 9.967221 87.9809 -5.919949 13.07846 87.99808 -5.475257 12.91685 87.9454 -6.311868 10.03278 87.9 -6.22756 10.01457 87.92334 -5.679562 13.00754 87.9809 -6 9.976041 87.96494 -5.338192 12.84919 87.92334 -5.25 12.79904 87.9 -5.76351 9.956278 87.99239 -5.76351 13.04372 87.99239 -5.671397 9.954047 87.99808 -5.757716 9.918451 88 -5.529071 12.94937 87.96494 -6.157932 9.997378 87.9454 -5.834794 13.07183 87.99808 -5.757716 13.08155 88 -5.613689 12.99202 87.9809 -5.921938 9.960757 87.9809 -6.077187 9.977997 87.96494 -5.385462 12.88028 87.9454 -6.312442 10.03008 87.92334 -5.470721 12.9291 87.96494 -5.836755 9.946824 87.99239 -5.675298 13.0276 87.99239 -5.76067 9.937735 87.99808 -5.248618 12.80143 87.92334 -6.228792 10.00652 87.9454 -5.76067 13.06227 87.99808 -6 9.958779 87.9809 -5.334609 12.85649 87.9454 -6.463525 10.07342 87.9 -6.376671 10.04521 87.92334 -5.523736 12.96579 87.9809 -6.159297 9.984389 87.96494 -5.118322 12.71353 87.9 -5.205092 12.77531 87.92334 -5.9209 9.940273 87.99239 -5.608548 13.01188 87.99239 -5.918961 9.902054 88 -5.834794 9.928167 87.99808 -5.38015 12.89221 87.96494 -6.078062 9.960757 87.9809 -5.671397 13.04595 87.99808 -5.598956 13.04892 88 -6.314134 10.02212 87.9454 -5.464726 12.94528 87.9809 -6.23077 9.993614 87.96494 -5.24455 12.80848 87.9454 -6 9.938268 87.99239 -5.328857 12.86822 87.96494 -6.464379 10.07079 87.92334 -4.996304 12.61472 87.9 -5.116698 12.71576 87.92334 -5.919949 9.921538 87.99808 -5.517398 12.9853 87.99239 -6.378711 10.03733 87.9454 -5.603846 13.03004 87.99808 -6.161102 9.967221 87.9809 -6.610105 10.12968 87.9 -6.521917 10.09078 87.92334 -5.200789 12.78222 87.9454 -5.373129 12.90798 87.9809 -6.0791 9.940273 87.99239 -6.316849 10.00934 87.96494 -5.457602 12.96452 87.99239 -5.23802 12.81979 87.96494 -6.081039 9.902054 88 -6 9.919509 87.99808 -5.321255 12.88372 87.9809 -6.233384 9.976551 87.9809 -5.511601 13.00314 87.99808 -5.444312 13.0004 88 -6.466894 10.06305 87.9454 -5.111916 12.72234 87.9454 -6.381984 10.02469 87.96494 -5.19388 12.7933 87.96494 -6.163245 9.946824 87.99239 -4.994455 12.61677 87.92334 -5.364787 12.92671 87.99239 -6.611229 10.12716 87.92334 -6.080051 9.921538 87.99808 -5.451087 12.98211 87.99808 -6.524743 10.08315 87.9454 -5.229389 12.83474 87.9809 -5.312223 12.90213 87.99239 -6.661808 10.15081 87.92334 -5.104239 12.73291 87.96494 -6.75 10.20096 87.9 -6.470929 10.05063 87.96494 -5.357156 12.94385 87.99808 -6.165206 9.928167 87.99808 -5.295369 12.93649 88 -5.303961 12.91897 87.99808 -5.219134 12.8525 87.99239 -4.885283 12.5037 87.9 -5.209755 12.86875 87.99808 -8.75 11.5 88 -8.741931 11.28949 88 -8.717771 11.08021 88 -8.677662 10.8734 88 -8.62184 10.67027 88 -8.550632 10.472 88 -8.464455 10.27977 88 -8.363816 10.0947 88 -8.249306 9.917874 88 -8.121595 9.750333 88 -7.981434 9.593061 88 -7.829646 9.446979 88 -7.66712 9.312945 88 -7.494811 9.191745 88 -7.31373 9.084091 88 -7.124939 8.990615 88 -6.929546 8.911865 88 -6.728699 8.848303 88 -6.523576 8.800302 88 -6.315379 8.768144 88 -6.105333 8.752018 88 -5.894667 8.752018 88 -5.684621 8.768144 88 -5.476424 8.800302 88 -5.271301 8.848303 88 -5.070454 8.911865 88 -4.875061 8.990615 88 -4.68627 9.084091 88 -4.505189 9.191745 88 -4.33288 9.312945 88 -4.170354 9.446979 88 -4.018566 9.593061 88 -3.878405 9.750333 88 -3.750694 9.917874 88 -3.636184 10.0947 88 -3.535545 10.27977 88 -3.449368 10.472 88 -3.37816 10.67027 88 -3.322338 10.8734 88 -3.282229 11.08021 88 -3.258069 11.28949 88 -3.25 11.5 88 -3.258069 11.71051 88 -3.282229 11.91979 88 -3.322338 12.1266 88 -3.37816 12.32973 88 -3.449368 12.528 88 -3.535545 12.72023 88 -3.636184 12.9053 88 -3.750694 13.08213 88 -3.878405 13.24967 88 -4.018566 13.40694 88 -4.170354 13.55302 88 -4.33288 13.68706 88 -4.505189 13.80825 88 -4.68627 13.91591 88 -4.875061 14.00938 88 -5.070454 14.08814 88 -5.271301 14.1517 88 -5.476424 14.1997 88 -5.684621 14.23186 88 -5.894667 14.24798 88 -6.105333 14.24798 88 -6.315379 14.23186 88 -6.523576 14.1997 88 -6.728699 14.1517 88 -6.929546 14.08814 88 -7.124939 14.00938 88 -7.31373 13.91591 88 -7.494811 13.80825 88 -7.66712 13.68706 88 -7.829646 13.55302 88 -7.981434 13.40694 88 -8.121595 13.24967 88 -8.249306 13.08213 88 -8.363816 12.9053 88 -8.464455 12.72023 88 -8.550632 12.528 88 -8.62184 12.32973 88 -8.677662 12.1266 88 -8.717771 11.91979 88 -8.741931 11.71051 88 -7.5 11.5 78.2805 -7.491783 11.34321 78.2805 -7.467221 11.18813 78.2805 -7.426585 11.03647 78.2805 -7.370318 10.8899 78.2805 -7.299038 10.75 78.2805 -7.213525 10.61832 78.2805 -7.114717 10.4963 78.2805 -7.003696 10.38528 78.2805 -6.881678 10.28647 78.2805 -6.75 10.20096 78.2805 -6.610105 10.12968 78.2805 -6.463525 10.07342 78.2805 -6.311868 10.03278 78.2805 -6.156793 10.00822 78.2805 -6 10 78.2805 -5.843207 10.00822 78.2805 -5.688132 10.03278 78.2805 -5.536475 10.07342 78.2805 -5.389895 10.12968 78.2805 -5.25 10.20096 78.2805 -5.118322 10.28647 78.2805 -4.996304 10.38528 78.2805 -4.885283 10.4963 78.2805 -4.786475 10.61832 78.2805 -4.700962 10.75 78.2805 -4.629682 10.8899 78.2805 -4.573415 11.03647 78.2805 -4.532779 11.18813 78.2805 -4.508217 11.34321 78.2805 -4.5 11.5 78.2805 -4.508217 11.65679 78.2805 -4.532779 11.81187 78.2805 -4.573415 11.96353 78.2805 -4.629682 12.1101 78.2805 -4.700962 12.25 78.2805 -4.786475 12.38168 78.2805 -4.885283 12.5037 78.2805 -4.996304 12.61472 78.2805 -5.118322 12.71353 78.2805 -5.25 12.79904 78.2805 -5.389895 12.87032 78.2805 -5.536475 12.92658 78.2805 -5.688132 12.96722 78.2805 -5.843207 12.99178 78.2805 -6 13 78.2805 -6.156793 12.99178 78.2805 -6.311868 12.96722 78.2805 -6.463525 12.92658 78.2805 -6.610105 12.87032 78.2805 -6.75 12.79904 78.2805 -6.881678 12.71353 78.2805 -7.003696 12.61472 78.2805 -7.114717 12.5037 78.2805 -7.213525 12.38168 78.2805 -7.299038 12.25 78.2805 -7.370318 12.1101 78.2805 -7.426585 11.96353 78.2805 -7.467221 11.81187 78.2805 -7.491783 11.65679 78.2805 -7.2195 11.5 78 -7.211254 11.35842 78 -7.186628 11.21876 78 -7.145955 11.08291 78 -7.089785 10.95269 78 -7.018877 10.82987 78 -6.934191 10.71612 78 -6.836872 10.61297 78 -6.728235 10.52181 78 -6.60975 10.44388 78 -6.483019 10.38024 78 -6.349757 10.33173 78 -6.211764 10.29903 78 -6.070908 10.28256 78 -5.929092 10.28256 78 -5.788236 10.29903 78 -5.650243 10.33173 78 -5.516981 10.38024 78 -5.39025 10.44388 78 -5.271765 10.52181 78 -5.163128 10.61297 78 -5.065809 10.71612 78 -4.981123 10.82987 78 -4.910215 10.95269 78 -4.854045 11.08291 78 -4.813372 11.21876 78 -4.788746 11.35842 78 -4.7805 11.5 78 -4.788746 11.64158 78 -4.813372 11.78124 78 -4.854045 11.91709 78 -4.910215 12.04731 78 -4.981123 12.17013 78 -5.065809 12.28388 78 -5.163128 12.38703 78 -5.271765 12.47819 78 -5.39025 12.55612 78 -5.516981 12.61976 78 -5.650243 12.66827 78 -5.788236 12.70097 78 -5.929092 12.71744 78 -6.070908 12.71744 78 -6.211764 12.70097 78 -6.349757 12.66827 78 -6.483019 12.61976 78 -6.60975 12.55612 78 -6.728235 12.47819 78 -6.836872 12.38703 78 -6.934191 12.28388 78 -7.018877 12.17013 78 -7.089785 12.04731 78 -7.145955 11.91709 78 -7.186628 11.78124 78 -7.211254 11.64158 78 -6 12.6547 90 -6 10.3453 90 -7 10.92265 90 -5 10.92265 90 -5 12.07735 90 -7 12.07735 90 -7 10.92265 88.5 -6 10.3453 88.5 -7 12.07735 88.5 -6 12.6547 88.5 -5 12.07735 88.5 -5 10.92265 88.5 + + + + + + + + + + 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 0.5 -7.911378e-16 0.8660254 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.825 6.661338e-16 -4.121703e-16 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -0.17 2.220446e-16 -8.493206e-17 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -2.75 3.205769e-15 -1.373901e-15 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -1.5 1.748601e-15 -7.494005e-16 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -0.8623167 1.212611e-15 -0.8623167 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 4.996004e-16 2.404903e-16 -1 0.5 0.8660254 4.580709e-16 0.5 0.8660254 4.580709e-16 0.5 0.8660254 4.580709e-16 1 3.783721e-16 4.996004e-16 1 3.783721e-16 4.996004e-16 1 3.783721e-16 4.996004e-16 0.5 -0.8660254 4.152949e-17 0.5 -0.8660254 4.152949e-17 0.5 -0.8660254 4.152949e-17 -0.5 -0.8660254 -4.580709e-16 -0.5 -0.8660254 -4.580709e-16 -0.5 -0.8660254 -4.580709e-16 -1 -2.793499e-18 -4.996004e-16 -1 -2.793499e-18 -4.996004e-16 -1 -2.793499e-18 -4.996004e-16 -0.5 0.8660254 -4.152949e-17 -0.5 0.8660254 -4.152949e-17 -0.5 0.8660254 -4.152949e-17 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 -4.996004e-16 -2.404903e-16 1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 4 2 5 2 6 2 7 3 4 3 6 3 8 4 7 4 6 4 9 5 10 5 11 5 12 6 13 6 11 6 13 7 14 7 11 7 10 8 12 8 11 8 3 9 15 9 16 9 2 10 3 10 16 10 17 11 18 11 19 11 20 12 17 12 19 12 21 13 20 13 19 13 3 14 21 14 19 14 11 15 14 15 22 15 17 16 9 16 22 16 14 17 23 17 22 17 9 18 11 18 22 18 3 19 19 19 24 19 19 20 18 20 24 20 18 21 25 21 24 21 15 22 3 22 24 22 18 23 17 23 26 23 17 24 22 24 26 24 22 25 23 25 26 25 23 26 27 26 26 26 24 27 25 27 28 27 15 28 24 28 28 28 25 29 29 29 28 29 30 30 15 30 28 30 25 31 18 31 31 31 26 32 27 32 31 32 18 33 26 33 31 33 27 34 32 34 31 34 28 35 29 35 33 35 34 36 30 36 33 36 29 37 35 37 33 37 30 38 28 38 33 38 29 39 25 39 36 39 25 40 31 40 36 40 32 41 37 41 36 41 31 42 32 42 36 42 35 43 38 43 39 43 34 44 33 44 39 44 33 45 35 45 39 45 40 46 34 46 39 46 36 47 37 47 41 47 29 48 36 48 41 48 35 49 29 49 41 49 37 50 42 50 41 50 38 51 43 51 44 51 40 52 39 52 44 52 39 53 38 53 44 53 45 54 40 54 44 54 38 55 35 55 46 55 35 56 41 56 46 56 41 57 42 57 46 57 42 58 47 58 46 58 44 59 43 59 48 59 45 60 44 60 48 60 49 61 45 61 48 61 43 62 50 62 48 62 51 63 52 63 53 63 43 64 38 64 54 64 46 65 47 65 54 65 47 66 55 66 54 66 38 67 46 67 54 67 50 68 56 68 57 68 49 69 48 69 57 69 48 70 50 70 57 70 51 71 49 71 57 71 53 72 52 72 58 72 55 73 59 73 60 73 54 74 55 74 60 74 43 75 54 75 60 75 50 76 43 76 60 76 52 77 61 77 62 77 58 78 52 78 62 78 63 79 58 79 62 79 63 80 62 80 64 80 62 81 61 81 64 81 56 82 65 82 66 82 51 83 57 83 66 83 57 84 56 84 66 84 52 85 51 85 66 85 61 86 67 86 68 86 64 87 61 87 68 87 56 88 50 88 69 88 60 89 59 89 69 89 59 90 70 90 69 90 50 91 60 91 69 91 68 92 67 92 71 92 61 93 52 93 72 93 65 94 73 94 72 94 66 95 65 95 72 95 52 96 66 96 72 96 67 97 74 97 75 97 71 98 67 98 75 98 70 99 76 99 77 99 65 100 56 100 77 100 69 101 70 101 77 101 56 102 69 102 77 102 75 103 74 103 78 103 73 104 79 104 80 104 67 105 61 105 80 105 72 106 73 106 80 106 61 107 72 107 80 107 74 108 81 108 82 108 78 109 74 109 82 109 73 110 65 110 83 110 77 111 76 111 83 111 65 112 77 112 83 112 76 113 84 113 83 113 82 114 81 114 85 114 79 115 86 115 87 115 80 116 79 116 87 116 74 117 67 117 87 117 67 118 80 118 87 118 83 119 84 119 88 119 79 120 73 120 88 120 73 121 83 121 88 121 84 122 89 122 88 122 74 123 87 123 90 123 87 124 86 124 90 124 81 125 74 125 90 125 86 126 91 126 90 126 85 127 81 127 92 127 92 128 93 128 94 128 81 129 90 129 92 129 90 130 91 130 92 130 93 131 85 131 92 131 86 132 79 132 95 132 79 133 88 133 95 133 88 134 89 134 95 134 89 135 96 135 95 135 95 136 96 136 97 136 91 137 86 137 97 137 86 138 95 138 97 138 96 139 98 139 97 139 99 140 4 140 100 140 101 141 98 141 100 141 4 142 101 142 100 142 102 143 103 143 104 143 94 144 102 144 104 144 94 145 104 145 105 145 104 146 103 146 105 146 94 147 105 147 106 147 103 148 107 148 106 148 105 149 103 149 106 149 106 150 107 150 108 150 94 151 106 151 108 151 94 152 108 152 109 152 108 153 107 153 109 153 107 154 110 154 109 154 94 155 109 155 111 155 109 156 110 156 111 156 111 157 110 157 112 157 110 158 113 158 112 158 113 159 114 159 112 159 94 160 4 160 115 160 116 161 94 161 115 161 117 162 116 162 115 162 118 163 117 163 115 163 4 164 7 164 115 164 7 165 119 165 115 165 119 166 118 166 115 166 2 167 16 167 120 167 5 168 121 168 122 168 121 169 123 169 122 169 123 170 124 170 122 170 6 171 5 171 122 171 16 172 15 172 125 172 15 173 30 173 125 173 126 174 120 174 125 174 120 175 16 175 125 175 126 176 125 176 127 176 125 177 30 177 128 177 30 178 34 178 128 178 127 179 125 179 128 179 34 180 127 180 128 180 34 181 40 181 129 181 127 182 34 182 129 182 130 183 129 183 131 183 40 184 45 184 132 184 129 185 40 185 132 185 131 186 129 186 132 186 130 187 131 187 133 187 134 188 135 188 13 188 132 189 45 189 133 189 131 190 132 190 133 190 133 191 45 191 136 191 45 192 49 192 136 192 49 193 51 193 137 193 136 194 49 194 137 194 68 195 71 195 138 195 71 196 75 196 138 196 75 197 78 197 138 197 138 198 78 198 139 198 94 199 138 199 139 199 139 200 78 200 140 200 78 201 82 201 140 201 94 202 139 202 140 202 140 203 82 203 141 203 94 204 140 204 141 204 141 205 82 205 142 205 82 206 85 206 142 206 13 207 135 207 14 207 94 208 141 208 142 208 143 209 144 209 14 209 142 210 85 210 145 210 94 211 142 211 145 211 145 212 85 212 146 212 135 213 143 213 14 213 93 214 94 214 146 214 94 215 145 215 146 215 85 216 93 216 146 216 94 217 92 217 147 217 92 218 91 218 147 218 91 219 97 219 147 219 97 220 98 220 147 220 98 221 101 221 147 221 101 222 4 222 147 222 4 223 94 223 147 223 99 224 100 224 148 224 149 225 150 225 148 225 150 226 151 226 148 226 151 227 99 227 148 227 111 228 112 228 152 228 112 229 114 229 152 229 94 230 111 230 152 230 114 231 153 231 152 231 152 232 153 232 154 232 153 233 155 233 154 233 155 234 0 234 154 234 152 235 154 235 156 235 154 236 0 236 156 236 2 237 120 237 156 237 144 238 157 238 23 238 157 239 158 239 23 239 0 240 2 240 156 240 158 241 159 241 23 241 6 242 122 242 160 242 8 243 6 243 160 243 13 244 8 244 160 244 134 245 13 245 160 245 124 246 161 246 160 246 14 247 144 247 23 247 161 248 134 248 160 248 122 249 124 249 160 249 127 250 129 250 162 250 129 251 130 251 162 251 133 252 136 252 163 252 136 253 137 253 163 253 164 254 163 254 165 254 163 255 137 255 165 255 53 256 164 256 165 256 137 257 51 257 165 257 51 258 53 258 165 258 164 259 53 259 166 259 159 260 167 260 27 260 58 261 63 261 166 261 167 262 168 262 27 262 53 263 58 263 166 263 168 264 169 264 27 264 164 265 166 265 170 265 166 266 63 266 170 266 94 267 164 267 170 267 23 268 159 268 27 268 64 269 68 269 170 269 63 270 64 270 170 270 68 271 138 271 170 271 138 272 94 272 170 272 171 273 172 273 173 273 172 274 149 274 173 274 100 275 98 275 173 275 148 276 100 276 173 276 96 277 171 277 173 277 149 278 148 278 173 278 98 279 96 279 173 279 152 280 156 280 174 280 156 281 120 281 174 281 94 282 152 282 174 282 164 283 94 283 174 283 120 284 126 284 174 284 174 285 126 285 175 285 126 286 127 286 175 286 127 287 162 287 175 287 164 288 174 288 175 288 162 289 130 289 176 289 175 290 162 290 176 290 163 291 164 291 177 291 178 292 179 292 32 292 133 293 163 293 177 293 175 294 176 294 177 294 130 295 133 295 177 295 176 296 130 296 177 296 164 297 175 297 177 297 169 298 178 298 32 298 27 299 169 299 32 299 179 300 180 300 37 300 180 301 181 301 37 301 181 302 182 302 37 302 32 303 179 303 37 303 182 304 183 304 42 304 183 305 184 305 42 305 184 306 185 306 42 306 37 307 182 307 42 307 186 308 187 308 47 308 185 309 186 309 47 309 42 310 185 310 47 310 47 311 187 311 55 311 187 312 188 312 55 312 188 313 189 313 55 313 189 314 190 314 55 314 190 315 191 315 59 315 191 316 192 316 59 316 192 317 193 317 59 317 55 318 190 318 59 318 59 319 193 319 70 319 194 320 195 320 70 320 193 321 194 321 70 321 195 322 196 322 76 322 196 323 197 323 76 323 197 324 198 324 76 324 70 325 195 325 76 325 76 326 198 326 84 326 198 327 199 327 84 327 199 328 200 328 84 328 200 329 201 329 84 329 202 330 203 330 89 330 201 331 202 331 89 331 84 332 201 332 89 332 203 333 171 333 96 333 89 334 203 334 96 334 117 335 103 335 116 335 103 336 102 336 116 336 116 337 94 337 102 337 103 338 117 338 107 338 117 339 204 339 107 339 107 340 204 340 110 340 204 341 205 341 113 341 110 342 204 342 113 342 113 343 205 343 114 343 119 344 10 344 118 344 204 345 117 345 118 345 114 346 205 346 153 346 205 347 21 347 153 347 153 348 21 348 155 348 10 349 9 349 206 349 205 350 204 350 206 350 204 351 118 351 206 351 118 352 10 352 206 352 155 353 21 353 1 353 0 354 155 354 1 354 21 355 3 355 1 355 8 356 13 356 12 356 10 357 119 357 12 357 119 358 7 358 12 358 7 359 8 359 12 359 9 360 17 360 20 360 205 361 206 361 20 361 21 362 205 362 20 362 206 363 9 363 20 363 207 364 208 364 209 364 210 365 211 365 212 365 207 366 213 366 208 366 214 367 215 367 216 367 217 368 212 368 218 368 217 369 218 369 219 369 217 370 219 370 220 370 214 371 216 371 221 371 222 372 223 372 224 372 222 373 224 373 211 373 225 374 226 374 227 374 225 375 221 375 226 375 228 376 229 376 230 376 231 377 220 377 232 377 228 378 233 378 234 378 228 379 235 379 233 379 228 380 234 380 229 380 236 381 230 381 237 381 238 382 217 382 220 382 236 383 237 383 215 383 239 384 240 384 241 384 239 385 241 385 242 385 243 386 225 386 227 386 239 387 242 387 244 387 239 388 244 388 223 388 243 389 227 389 245 389 246 390 213 390 207 390 247 391 211 391 210 391 247 392 222 392 211 392 246 393 245 393 213 393 248 394 212 394 217 394 249 395 215 395 214 395 248 396 210 396 212 396 249 397 236 397 215 397 250 398 232 398 251 398 250 399 231 399 232 399 252 400 214 400 221 400 252 401 221 401 225 401 253 402 230 402 236 402 253 403 235 403 228 403 254 404 223 404 222 404 254 405 239 405 223 405 253 406 228 406 230 406 255 407 220 407 231 407 256 408 207 408 209 408 255 409 238 409 220 409 256 410 209 410 257 410 258 411 225 411 243 411 259 412 217 412 238 412 259 413 248 413 217 413 258 414 252 414 225 414 260 415 222 415 247 415 260 416 254 416 222 416 261 417 243 417 245 417 261 418 245 418 246 418 262 419 247 419 210 419 262 420 210 420 248 420 263 421 253 421 236 421 263 422 235 422 253 422 263 423 264 423 235 423 263 424 236 424 249 424 265 425 250 425 251 425 266 426 249 426 214 426 266 427 214 427 252 427 267 428 231 428 250 428 267 429 255 429 231 429 268 430 246 430 207 430 269 431 270 431 240 431 269 432 240 432 239 432 269 433 239 433 254 433 268 434 207 434 256 434 271 435 259 435 238 435 272 436 266 436 252 436 272 437 252 437 258 437 271 438 238 438 255 438 273 439 262 439 248 439 274 440 243 440 261 440 274 441 258 441 243 441 273 442 248 442 259 442 275 443 269 443 254 443 275 444 270 444 269 444 276 445 249 445 266 445 275 446 254 446 260 446 276 447 264 447 263 447 277 448 265 448 251 448 276 449 263 449 249 449 277 450 251 450 278 450 279 451 257 451 280 451 281 452 260 452 247 452 279 453 268 453 256 453 281 454 262 454 273 454 279 455 256 455 257 455 281 456 247 456 262 456 282 457 261 457 246 457 283 458 250 458 265 458 282 459 246 459 268 459 283 460 267 460 250 460 284 461 285 461 264 461 284 462 264 462 276 462 284 463 266 463 272 463 286 464 255 464 267 464 284 465 276 465 266 465 286 466 271 466 255 466 287 467 272 467 258 467 287 468 258 468 274 468 288 469 259 469 271 469 288 470 273 470 259 470 289 471 268 471 279 471 289 472 282 472 268 472 290 473 277 473 278 473 291 474 261 474 282 474 292 475 281 475 273 475 291 476 274 476 261 476 293 477 284 477 272 477 294 478 295 478 270 478 294 479 275 479 260 479 293 480 285 480 284 480 293 481 272 481 287 481 294 482 270 482 275 482 294 483 260 483 281 483 296 484 280 484 297 484 296 485 279 485 280 485 296 486 289 486 279 486 298 487 283 487 265 487 298 488 265 488 277 488 298 489 277 489 290 489 299 490 286 490 267 490 300 491 282 491 289 491 300 492 291 492 282 492 299 493 267 493 283 493 301 494 287 494 274 494 301 495 274 495 291 495 302 496 271 496 286 496 302 497 288 497 271 497 303 498 289 498 296 498 304 499 292 499 273 499 305 500 301 500 291 500 304 501 273 501 288 501 306 502 281 502 292 502 306 503 295 503 294 503 306 504 294 504 281 504 305 505 291 505 300 505 307 506 298 506 290 506 308 507 309 507 310 507 308 508 297 508 309 508 308 509 296 509 297 509 311 510 312 510 285 510 313 511 290 511 278 511 313 512 278 512 314 512 311 513 287 513 301 513 311 514 293 514 287 514 311 515 285 515 293 515 315 516 300 516 289 516 316 517 283 517 298 517 316 518 299 518 283 518 315 519 289 519 303 519 317 520 302 520 286 520 318 521 311 521 301 521 317 522 286 522 299 522 318 523 301 523 305 523 319 524 296 524 308 524 320 525 313 525 314 525 319 526 303 526 296 526 321 527 318 527 305 527 321 528 305 528 300 528 322 529 288 529 302 529 322 530 304 530 288 530 323 531 324 531 295 531 321 532 300 532 315 532 323 533 292 533 304 533 323 534 295 534 306 534 323 535 306 535 292 535 325 536 298 536 307 536 326 537 308 537 310 537 327 538 312 538 311 538 325 539 316 539 298 539 327 540 311 540 318 540 327 541 328 541 312 541 329 542 303 542 319 542 330 543 290 543 313 543 329 544 321 544 315 544 330 545 307 545 290 545 329 546 315 546 303 546 331 547 299 547 316 547 331 548 317 548 299 548 332 549 318 549 321 549 333 550 319 550 308 550 333 551 308 551 326 551 334 552 302 552 317 552 334 553 322 553 302 553 335 554 330 554 313 554 336 555 321 555 329 555 335 556 313 556 320 556 337 557 324 557 323 557 337 558 304 558 322 558 338 559 310 559 339 559 337 560 323 560 304 560 338 561 326 561 310 561 340 562 314 562 341 562 340 563 320 563 314 563 342 564 327 564 318 564 342 565 328 565 327 565 342 566 318 566 332 566 342 567 343 567 328 567 344 568 331 568 316 568 345 569 329 569 319 569 344 570 316 570 325 570 345 571 336 571 329 571 345 572 319 572 333 572 346 573 332 573 321 573 346 574 321 574 336 574 347 575 325 575 307 575 347 576 307 576 330 576 346 577 342 577 332 577 348 578 317 578 331 578 348 579 334 579 317 579 349 580 337 580 322 580 349 581 350 581 324 581 351 582 326 582 338 582 349 583 324 583 337 583 351 584 333 584 326 584 349 585 322 585 334 585 352 586 336 586 345 586 353 587 347 587 330 587 353 588 330 588 335 588 354 589 339 589 355 589 356 590 320 590 340 590 354 591 338 591 339 591 357 592 358 592 343 592 356 593 335 593 320 593 357 594 343 594 342 594 357 595 342 595 346 595 359 596 331 596 344 596 359 597 348 597 331 597 360 598 345 598 333 598 361 599 344 599 325 599 360 600 333 600 351 600 360 601 352 601 345 601 362 602 355 602 363 602 362 603 354 603 355 603 361 604 325 604 347 604 364 605 334 605 348 605 364 606 349 606 334 606 364 607 350 607 349 607 365 608 346 608 336 608 365 609 336 609 352 609 366 610 340 610 341 610 366 611 341 611 367 611 368 612 351 612 338 612 368 613 354 613 362 613 369 614 361 614 347 614 368 615 338 615 354 615 369 616 347 616 353 616 370 617 352 617 360 617 371 618 353 618 335 618 371 619 335 619 356 619 372 620 373 620 350 620 374 621 368 621 362 621 372 622 348 622 359 622 372 623 364 623 348 623 372 624 350 624 364 624 375 625 359 625 344 625 376 626 362 626 363 626 375 627 344 627 361 627 377 628 358 628 357 628 377 629 378 629 358 629 379 630 356 630 340 630 377 631 346 631 365 631 377 632 357 632 346 632 380 633 360 633 351 633 380 634 351 634 368 634 379 635 340 635 366 635 380 636 370 636 360 636 380 637 368 637 374 637 381 638 361 638 369 638 382 639 363 639 383 639 381 640 375 640 361 640 382 641 376 641 363 641 384 642 353 642 371 642 385 643 365 643 352 643 384 644 369 644 353 644 385 645 352 645 370 645 385 646 377 646 365 646 386 647 359 647 375 647 386 648 373 648 372 648 386 649 372 649 359 649 387 650 380 650 374 650 388 651 366 651 367 651 388 652 367 652 389 652 390 653 374 653 362 653 390 654 362 654 376 654 391 655 371 655 356 655 390 656 376 656 382 656 392 657 380 657 387 657 391 658 356 658 379 658 392 659 370 659 380 659 393 660 375 660 381 660 393 661 394 661 373 661 393 662 373 662 386 662 393 663 386 663 375 663 395 664 382 664 383 664 396 665 381 665 369 665 396 666 369 666 384 666 397 667 390 667 382 667 397 668 382 668 395 668 398 669 379 669 366 669 398 670 366 670 388 670 399 671 400 671 378 671 399 672 378 672 377 672 399 673 377 673 385 673 401 674 384 674 371 674 401 675 371 675 391 675 402 676 392 676 387 676 403 677 387 677 374 677 404 678 393 678 381 678 404 679 381 679 396 679 404 680 394 680 393 680 403 681 374 681 390 681 405 682 395 682 383 682 405 683 383 683 406 683 407 684 389 684 408 684 407 685 388 685 389 685 409 686 370 686 392 686 409 687 392 687 402 687 410 688 391 688 379 688 409 689 399 689 385 689 410 690 379 690 398 690 409 691 385 691 370 691 411 692 395 692 405 692 412 693 384 693 401 693 411 694 397 694 395 694 412 695 396 695 384 695 413 696 390 696 397 696 413 697 403 697 390 697 414 698 398 698 388 698 414 699 388 699 407 699 415 700 409 700 402 700 416 701 387 701 403 701 416 702 402 702 387 702 417 703 401 703 391 703 417 704 391 704 410 704 418 705 405 705 406 705 419 706 408 706 420 706 419 707 407 707 408 707 421 708 405 708 418 708 422 709 423 709 394 709 421 710 411 710 405 710 422 711 394 711 404 711 422 712 404 712 396 712 422 713 396 713 412 713 424 714 399 714 409 714 424 715 400 715 399 715 424 716 409 716 415 716 425 717 410 717 398 717 424 718 426 718 400 718 427 719 413 719 397 719 425 720 398 720 414 720 427 721 397 721 411 721 427 722 411 722 421 722 428 723 403 723 413 723 429 724 412 724 401 724 428 725 416 725 403 725 429 726 401 726 417 726 430 727 425 727 414 727 431 728 424 728 415 728 430 729 414 729 407 729 431 730 426 730 424 730 430 731 407 731 419 731 432 732 406 732 433 732 432 733 418 733 406 733 434 734 410 734 425 734 435 735 402 735 416 735 434 736 417 736 410 736 435 737 415 737 402 737 436 738 419 738 420 738 437 739 421 739 418 739 437 740 418 740 432 740 436 741 420 741 438 741 439 742 412 742 429 742 439 743 440 743 423 743 439 744 423 744 422 744 441 745 427 745 421 745 439 746 422 746 412 746 441 747 421 747 437 747 442 748 428 748 413 748 443 749 425 749 430 749 442 750 413 750 427 750 444 751 417 751 434 751 442 752 427 752 441 752 444 753 429 753 417 753 445 754 432 754 433 754 446 755 419 755 436 755 447 756 416 756 428 756 447 757 435 757 416 757 446 758 430 758 419 758 448 759 425 759 443 759 447 760 428 760 442 760 449 761 431 761 415 761 449 762 415 762 435 762 448 763 434 763 425 763 449 764 450 764 426 764 449 765 426 765 431 765 451 766 436 766 438 766 452 767 437 767 432 767 451 768 438 768 453 768 454 769 455 769 440 769 454 770 429 770 444 770 454 771 440 771 439 771 456 772 441 772 437 772 454 773 439 773 429 773 457 774 443 774 430 774 457 775 430 775 446 775 458 776 442 776 441 776 457 777 448 777 443 777 458 778 441 778 456 778 459 779 442 779 458 779 460 780 444 780 434 780 459 781 447 781 442 781 460 782 434 782 448 782 461 783 449 783 435 783 461 784 435 784 447 784 461 785 450 785 449 785 462 786 436 786 451 786 462 787 446 787 436 787 463 788 432 788 445 788 463 789 452 789 432 789 464 790 433 790 465 790 466 791 448 791 457 791 464 792 463 792 445 792 464 793 445 793 433 793 467 794 437 794 452 794 468 795 451 795 453 795 467 796 456 796 437 796 468 797 453 797 469 797 470 798 471 798 455 798 470 799 455 799 454 799 470 800 454 800 444 800 470 801 444 801 460 801 472 802 458 802 456 802 473 803 469 803 474 803 473 804 468 804 469 804 475 805 464 805 465 805 476 806 457 806 446 806 477 807 458 807 472 807 476 808 446 808 462 808 477 809 459 809 458 809 478 810 459 810 477 810 478 811 479 811 450 811 478 812 450 812 461 812 480 813 460 813 448 813 478 814 447 814 459 814 478 815 461 815 447 815 480 816 448 816 466 816 480 817 470 817 460 817 481 818 451 818 468 818 481 819 462 819 451 819 482 820 467 820 452 820 482 821 452 821 463 821 483 822 463 822 464 822 481 823 468 823 473 823 483 824 482 824 463 824 483 825 464 825 475 825 484 826 481 826 473 826 485 827 456 827 467 827 486 828 457 828 476 828 485 829 472 829 456 829 487 830 477 830 472 830 486 831 466 831 457 831 488 832 483 832 475 832 489 833 473 833 474 833 490 834 491 834 471 834 492 835 477 835 487 835 490 836 470 836 480 836 492 837 478 837 477 837 490 838 471 838 470 838 492 839 479 839 478 839 493 840 475 840 465 840 494 841 462 841 481 841 493 842 465 842 495 842 493 843 488 843 475 843 494 844 486 844 476 844 494 845 476 845 462 845 496 846 467 846 482 846 497 847 474 847 498 847 496 848 485 848 467 848 497 849 489 849 474 849 499 850 482 850 483 850 499 851 496 851 482 851 500 852 481 852 484 852 499 853 483 853 488 853 501 854 487 854 472 854 500 855 494 855 481 855 501 856 472 856 485 856 502 857 480 857 466 857 502 858 466 858 486 858 503 859 492 859 487 859 503 860 479 860 492 860 503 861 504 861 479 861 505 862 499 862 488 862 506 863 484 863 473 863 506 864 473 864 489 864 507 865 488 865 493 865 507 866 505 866 488 866 508 867 486 867 494 867 509 868 485 868 496 868 509 869 501 869 485 869 510 870 497 870 498 870 511 871 496 871 499 871 511 872 499 872 505 872 511 873 509 873 496 873 512 874 489 874 497 874 513 875 503 875 487 875 512 876 506 876 489 876 513 877 487 877 501 877 512 878 497 878 510 878 514 879 515 879 491 879 513 880 504 880 503 880 514 881 491 881 490 881 514 882 480 882 502 882 514 883 490 883 480 883 516 884 495 884 517 884 516 885 493 885 495 885 518 886 494 886 500 886 519 887 511 887 505 887 518 888 508 888 494 888 520 889 484 889 506 889 520 890 500 890 484 890 521 891 505 891 507 891 522 892 498 892 523 892 524 893 525 893 504 893 522 894 510 894 498 894 524 895 501 895 509 895 524 896 513 896 501 896 526 897 514 897 502 897 524 898 504 898 513 898 527 899 511 899 519 899 526 900 502 900 486 900 527 901 509 901 511 901 526 902 486 902 508 902 527 903 524 903 509 903 528 904 493 904 516 904 529 905 510 905 522 905 528 906 507 906 493 906 529 907 512 907 510 907 530 908 512 908 529 908 531 909 527 909 519 909 530 910 520 910 506 910 530 911 506 911 512 911 532 912 526 912 508 912 532 913 508 913 518 913 533 914 519 914 505 914 533 915 505 915 521 915 534 916 500 916 520 916 533 917 531 917 519 917 534 918 518 918 500 918 535 919 525 919 524 919 535 920 524 920 527 920 535 921 527 921 531 921 536 922 522 922 523 922 537 923 517 923 538 923 537 924 516 924 517 924 539 925 529 925 522 925 540 926 507 926 528 926 539 927 522 927 536 927 540 928 521 928 507 928 541 929 542 929 515 929 541 930 515 930 514 930 541 931 514 931 526 931 543 932 544 932 525 932 545 933 530 933 529 933 543 934 525 934 535 934 543 935 535 935 531 935 546 936 520 936 530 936 547 937 531 937 533 937 546 938 534 938 520 938 548 939 516 939 537 939 546 940 530 940 545 940 548 941 528 941 516 941 549 942 541 942 526 942 549 943 526 943 532 943 549 944 542 944 541 944 550 945 536 945 523 945 550 946 523 946 551 946 552 947 533 947 521 947 552 948 521 948 540 948 553 949 543 949 531 949 554 950 518 950 534 950 554 951 532 951 518 951 553 952 544 952 543 952 553 953 531 953 547 953 555 954 538 954 556 954 557 955 536 955 550 955 555 956 537 956 538 956 557 957 539 957 536 957 558 958 529 958 539 958 558 959 545 959 529 959 559 960 528 960 548 960 559 961 540 961 528 961 560 962 546 962 545 962 561 963 547 963 533 963 562 964 534 964 546 964 561 965 533 965 552 965 562 966 554 966 534 966 562 967 546 967 560 967 563 968 537 968 555 968 564 969 565 969 566 969 567 970 550 970 551 970 563 971 548 971 537 971 568 972 557 972 550 972 569 973 540 973 559 973 568 974 550 974 567 974 570 975 571 975 542 975 569 976 552 976 540 976 570 977 542 977 549 977 570 978 549 978 532 978 572 979 556 979 573 979 570 980 532 980 554 980 572 981 555 981 556 981 574 982 558 982 539 982 575 983 544 983 553 983 574 984 539 984 557 984 575 985 553 985 547 985 575 986 576 986 544 986 575 987 547 987 561 987 577 988 548 988 563 988 578 989 545 989 558 989 578 990 560 990 545 990 579 991 571 991 570 991 577 992 559 992 548 992 579 993 554 993 562 993 580 994 552 994 569 994 579 995 570 995 554 995 580 996 561 996 552 996 581 997 562 997 560 997 581 998 579 998 562 998 582 999 563 999 555 999 582 1000 555 1000 572 1000 583 1001 551 1001 584 1001 583 1002 567 1002 551 1002 585 1003 564 1003 566 1003 586 1004 569 1004 559 1004 585 1005 587 1005 564 1005 588 1006 568 1006 567 1006 586 1007 559 1007 577 1007 588 1008 567 1008 583 1008 585 1009 589 1009 590 1009 585 1010 566 1010 589 1010 591 1011 557 1011 568 1011 592 1012 593 1012 594 1012 591 1013 568 1013 588 1013 592 1014 573 1014 593 1014 591 1015 574 1015 557 1015 595 1016 587 1016 585 1016 592 1017 572 1017 573 1017 596 1018 558 1018 574 1018 597 1019 561 1019 580 1019 596 1020 578 1020 558 1020 597 1021 575 1021 561 1021 598 1022 595 1022 585 1022 597 1023 576 1023 575 1023 598 1024 585 1024 590 1024 597 1025 599 1025 576 1025 600 1026 577 1026 563 1026 600 1027 563 1027 582 1027 600 1028 586 1028 577 1028 601 1029 587 1029 595 1029 601 1030 602 1030 587 1030 603 1031 583 1031 584 1031 604 1032 560 1032 578 1032 605 1033 580 1033 569 1033 604 1034 581 1034 560 1034 606 1035 595 1035 598 1035 607 1036 608 1036 571 1036 606 1037 601 1037 595 1037 607 1038 571 1038 579 1038 605 1039 569 1039 586 1039 609 1040 582 1040 572 1040 607 1041 579 1041 581 1041 609 1042 572 1042 592 1042 610 1043 588 1043 583 1043 611 1044 612 1044 602 1044 611 1045 613 1045 612 1045 611 1046 602 1046 601 1046 614 1047 598 1047 590 1047 615 1048 586 1048 600 1048 616 1049 591 1049 588 1049 614 1050 617 1050 618 1050 614 1051 590 1051 617 1051 619 1052 592 1052 594 1052 620 1053 591 1053 616 1053 619 1054 609 1054 592 1054 621 1055 611 1055 601 1055 621 1056 601 1056 606 1056 620 1057 574 1057 591 1057 620 1058 596 1058 574 1058 622 1059 597 1059 580 1059 623 1060 604 1060 578 1060 622 1061 580 1061 605 1061 622 1062 624 1062 599 1062 625 1063 613 1063 611 1063 622 1064 599 1064 597 1064 623 1065 578 1065 596 1065 623 1066 596 1066 620 1066 626 1067 600 1067 582 1067 627 1068 581 1068 604 1068 626 1069 582 1069 609 1069 627 1070 608 1070 607 1070 628 1071 598 1071 614 1071 626 1072 615 1072 600 1072 627 1073 607 1073 581 1073 628 1074 606 1074 598 1074 629 1075 583 1075 603 1075 630 1076 605 1076 586 1076 629 1077 610 1077 583 1077 630 1078 586 1078 615 1078 631 1079 625 1079 611 1079 631 1080 611 1080 621 1080 632 1081 584 1081 633 1081 634 1082 628 1082 614 1082 635 1083 626 1083 609 1083 632 1084 603 1084 584 1084 635 1085 609 1085 619 1085 634 1086 614 1086 618 1086 636 1087 588 1087 610 1087 636 1088 616 1088 588 1088 637 1089 613 1089 625 1089 638 1090 615 1090 626 1090 637 1091 639 1091 613 1091 637 1092 640 1092 639 1092 637 1093 641 1093 640 1093 642 1094 594 1094 643 1094 642 1095 619 1095 594 1095 644 1096 621 1096 606 1096 645 1097 620 1097 616 1097 644 1098 606 1098 628 1098 646 1099 622 1099 605 1099 647 1100 632 1100 633 1100 646 1101 648 1101 624 1101 649 1102 634 1102 618 1102 646 1103 605 1103 630 1103 646 1104 624 1104 622 1104 649 1105 618 1105 650 1105 651 1106 643 1106 652 1106 653 1107 637 1107 625 1107 654 1108 623 1108 620 1108 654 1109 620 1109 645 1109 655 1110 604 1110 623 1110 651 1111 642 1111 643 1111 653 1112 625 1112 631 1112 655 1113 656 1113 608 1113 655 1114 608 1114 627 1114 657 1115 628 1115 634 1115 655 1116 627 1116 604 1116 657 1117 644 1117 628 1117 658 1118 626 1118 635 1118 657 1119 634 1119 649 1119 658 1120 638 1120 626 1120 659 1121 636 1121 610 1121 660 1122 630 1122 615 1122 659 1123 610 1123 629 1123 660 1124 615 1124 638 1124 661 1125 632 1125 647 1125 662 1126 621 1126 644 1126 660 1127 646 1127 630 1127 661 1128 603 1128 632 1128 662 1129 631 1129 621 1129 663 1130 657 1130 649 1130 664 1131 635 1131 619 1131 664 1132 619 1132 642 1132 661 1133 629 1133 603 1133 665 1134 645 1134 616 1134 666 1135 663 1135 649 1135 665 1136 616 1136 636 1136 667 1137 664 1137 642 1137 666 1138 649 1138 650 1138 668 1139 637 1139 653 1139 667 1140 642 1140 651 1140 668 1141 641 1141 637 1141 669 1142 654 1142 645 1142 668 1143 670 1143 641 1143 671 1144 644 1144 657 1144 671 1145 662 1145 644 1145 672 1146 638 1146 658 1146 673 1147 661 1147 647 1147 672 1148 660 1148 638 1148 674 1149 655 1149 623 1149 675 1150 667 1150 651 1150 674 1151 654 1151 669 1151 674 1152 656 1152 655 1152 676 1153 666 1153 650 1153 675 1154 651 1154 652 1154 674 1155 623 1155 654 1155 676 1156 650 1156 677 1156 678 1157 679 1157 648 1157 680 1158 647 1158 633 1158 678 1159 648 1159 646 1159 681 1160 653 1160 631 1160 680 1161 633 1161 682 1161 678 1162 646 1162 660 1162 683 1163 672 1163 658 1163 681 1164 631 1164 662 1164 683 1165 635 1165 664 1165 683 1166 658 1166 635 1166 684 1167 665 1167 636 1167 685 1168 675 1168 652 1168 686 1169 671 1169 657 1169 684 1170 636 1170 659 1170 685 1171 652 1171 687 1171 686 1172 657 1172 663 1172 688 1173 659 1173 629 1173 689 1174 686 1174 663 1174 688 1175 661 1175 673 1175 688 1176 629 1176 661 1176 690 1177 683 1177 664 1177 689 1178 663 1178 666 1178 691 1179 692 1179 656 1179 691 1180 656 1180 674 1180 689 1181 666 1181 676 1181 691 1182 674 1182 669 1182 693 1183 681 1183 662 1183 690 1184 664 1184 667 1184 693 1185 662 1185 671 1185 694 1186 645 1186 665 1186 695 1187 678 1187 660 1187 694 1188 669 1188 645 1188 695 1189 660 1189 672 1189 696 1190 675 1190 685 1190 696 1191 690 1191 667 1191 697 1192 676 1192 677 1192 698 1193 689 1193 676 1193 699 1194 688 1194 673 1194 696 1195 667 1195 675 1195 700 1196 647 1196 680 1196 701 1197 672 1197 683 1197 700 1198 673 1198 647 1198 702 1199 668 1199 653 1199 702 1200 670 1200 668 1200 702 1201 653 1201 681 1201 702 1202 703 1202 670 1202 704 1203 693 1203 671 1203 705 1204 665 1204 684 1204 705 1205 694 1205 665 1205 706 1206 685 1206 687 1206 707 1207 659 1207 688 1207 708 1208 696 1208 685 1208 704 1209 671 1209 686 1209 707 1210 684 1210 659 1210 708 1211 685 1211 706 1211 709 1212 689 1212 698 1212 707 1213 688 1213 699 1213 709 1214 704 1214 686 1214 710 1215 692 1215 691 1215 709 1216 686 1216 689 1216 711 1217 712 1217 679 1217 710 1218 691 1218 669 1218 713 1219 697 1219 677 1219 710 1220 669 1220 694 1220 711 1221 678 1221 695 1221 711 1222 679 1222 678 1222 714 1223 683 1223 690 1223 713 1224 677 1224 715 1224 716 1225 682 1225 717 1225 718 1226 702 1226 681 1226 714 1227 701 1227 683 1227 718 1228 681 1228 693 1228 716 1229 680 1229 682 1229 719 1230 690 1230 696 1230 719 1231 714 1231 690 1231 720 1232 698 1232 676 1232 721 1233 707 1233 699 1233 722 1234 706 1234 687 1234 720 1235 676 1235 697 1235 722 1236 687 1236 723 1236 720 1237 697 1237 713 1237 724 1238 699 1238 673 1238 724 1239 673 1239 700 1239 725 1240 711 1240 695 1240 726 1241 709 1241 698 1241 725 1242 672 1242 701 1242 727 1243 728 1243 692 1243 727 1244 692 1244 710 1244 729 1245 718 1245 693 1245 727 1246 694 1246 705 1246 727 1247 710 1247 694 1247 725 1248 695 1248 672 1248 729 1249 693 1249 704 1249 730 1250 706 1250 722 1250 731 1251 705 1251 684 1251 730 1252 708 1252 706 1252 731 1253 684 1253 707 1253 732 1254 709 1254 726 1254 732 1255 729 1255 704 1255 731 1256 707 1256 721 1256 732 1257 704 1257 709 1257 731 1258 727 1258 705 1258 733 1259 719 1259 696 1259 734 1260 700 1260 680 1260 735 1261 713 1261 715 1261 734 1262 680 1262 716 1262 733 1263 696 1263 708 1263 736 1264 701 1264 714 1264 736 1265 725 1265 701 1265 737 1266 720 1266 713 1266 738 1267 731 1267 721 1267 739 1268 714 1268 719 1268 739 1269 736 1269 714 1269 740 1270 703 1270 702 1270 740 1271 741 1271 703 1271 740 1272 702 1272 718 1272 742 1273 699 1273 724 1273 742 1274 721 1274 699 1274 743 1275 726 1275 698 1275 744 1276 727 1276 731 1276 744 1277 731 1277 738 1277 743 1278 698 1278 720 1278 745 1279 722 1279 723 1279 744 1280 728 1280 727 1280 746 1281 730 1281 722 1281 747 1282 732 1282 726 1282 746 1283 722 1283 745 1283 748 1284 717 1284 749 1284 750 1285 711 1285 725 1285 751 1286 741 1286 740 1286 750 1287 712 1287 711 1287 748 1288 716 1288 717 1288 750 1289 752 1289 712 1289 751 1290 718 1290 729 1290 751 1291 740 1291 718 1291 753 1292 700 1292 734 1292 754 1293 708 1293 730 1293 755 1294 735 1294 715 1294 754 1295 733 1295 708 1295 755 1296 715 1296 756 1296 753 1297 724 1297 700 1297 754 1298 730 1298 746 1298 757 1299 744 1299 738 1299 758 1300 719 1300 733 1300 759 1301 729 1301 732 1301 757 1302 728 1302 744 1302 758 1303 739 1303 719 1303 757 1304 760 1304 728 1304 759 1305 732 1305 747 1305 761 1306 738 1306 721 1306 759 1307 751 1307 729 1307 762 1308 750 1308 725 1308 763 1309 713 1309 735 1309 763 1310 737 1310 713 1310 761 1311 721 1311 742 1311 762 1312 752 1312 750 1312 764 1313 716 1313 748 1313 762 1314 725 1314 736 1314 763 1315 735 1315 755 1315 765 1316 723 1316 766 1316 767 1317 743 1317 720 1317 767 1318 720 1318 737 1318 764 1319 734 1319 716 1319 765 1320 745 1320 723 1320 768 1321 742 1321 724 1321 769 1322 736 1322 739 1322 770 1323 726 1323 743 1323 770 1324 747 1324 726 1324 768 1325 724 1325 753 1325 769 1326 762 1326 736 1326 771 1327 746 1327 745 1327 772 1328 757 1328 738 1328 773 1329 759 1329 747 1329 772 1330 760 1330 757 1330 771 1331 745 1331 765 1331 772 1332 738 1332 761 1332 774 1333 754 1333 746 1333 775 1334 755 1334 756 1334 774 1335 746 1335 771 1335 776 1336 733 1336 754 1336 777 1337 749 1337 778 1337 777 1338 748 1338 749 1338 776 1339 758 1339 733 1339 779 1340 741 1340 751 1340 779 1341 751 1341 759 1341 779 1342 759 1342 773 1342 779 1343 780 1343 741 1343 781 1344 734 1344 764 1344 782 1345 739 1345 758 1345 783 1346 763 1346 755 1346 783 1347 755 1347 775 1347 782 1348 769 1348 739 1348 781 1349 753 1349 734 1349 784 1350 767 1350 737 1350 784 1351 737 1351 763 1351 785 1352 765 1352 766 1352 786 1353 761 1353 742 1353 786 1354 742 1354 768 1354 787 1355 764 1355 748 1355 787 1356 748 1356 777 1356 788 1357 771 1357 765 1357 789 1358 770 1358 743 1358 789 1359 743 1359 767 1359 788 1360 765 1360 785 1360 790 1361 791 1361 752 1361 790 1362 752 1362 762 1362 792 1363 780 1363 779 1363 790 1364 762 1364 769 1364 792 1365 779 1365 773 1365 793 1366 768 1366 753 1366 793 1367 753 1367 781 1367 794 1368 771 1368 788 1368 795 1369 747 1369 770 1369 794 1370 774 1370 771 1370 795 1371 773 1371 747 1371 796 1372 777 1372 778 1372 797 1373 774 1373 794 1373 797 1374 754 1374 774 1374 798 1375 775 1375 756 1375 796 1376 778 1376 799 1376 797 1377 776 1377 754 1377 798 1378 756 1378 800 1378 801 1379 761 1379 786 1379 802 1380 790 1380 769 1380 801 1381 803 1381 760 1381 802 1382 791 1382 790 1382 804 1383 783 1383 775 1383 801 1384 760 1384 772 1384 802 1385 769 1385 782 1385 801 1386 772 1386 761 1386 805 1387 764 1387 787 1387 806 1388 758 1388 776 1388 807 1389 763 1389 783 1389 806 1390 782 1390 758 1390 807 1391 784 1391 763 1391 805 1392 781 1392 764 1392 808 1393 766 1393 809 1393 810 1394 786 1394 768 1394 808 1395 785 1395 766 1395 811 1396 789 1396 767 1396 810 1397 768 1397 793 1397 812 1398 788 1398 785 1398 811 1399 767 1399 784 1399 813 1400 777 1400 796 1400 812 1401 785 1401 808 1401 813 1402 787 1402 777 1402 814 1403 798 1403 800 1403 815 1404 794 1404 788 1404 816 1405 770 1405 789 1405 817 1406 797 1406 794 1406 818 1407 793 1407 781 1407 816 1408 795 1408 770 1408 818 1409 781 1409 805 1409 819 1410 780 1410 792 1410 819 1411 792 1411 773 1411 820 1412 821 1412 822 1412 819 1413 823 1413 780 1413 820 1414 799 1414 821 1414 819 1415 773 1415 795 1415 824 1416 798 1416 814 1416 825 1417 808 1417 809 1417 824 1418 804 1418 775 1418 820 1419 796 1419 799 1419 826 1420 801 1420 786 1420 827 1421 776 1421 797 1421 826 1422 828 1422 803 1422 827 1423 797 1423 817 1423 824 1424 775 1424 798 1424 826 1425 803 1425 801 1425 826 1426 786 1426 810 1426 827 1427 806 1427 776 1427 829 1428 791 1428 802 1428 830 1429 783 1429 804 1429 829 1430 802 1430 782 1430 831 1431 805 1431 787 1431 829 1432 782 1432 806 1432 831 1433 787 1433 813 1433 830 1434 807 1434 783 1434 829 1435 832 1435 791 1435 833 1436 812 1436 808 1436 833 1437 808 1437 825 1437 834 1438 811 1438 784 1438 835 1439 810 1439 793 1439 834 1440 784 1440 807 1440 835 1441 793 1441 818 1441 836 1442 789 1442 811 1442 836 1443 816 1443 789 1443 837 1444 815 1444 788 1444 838 1445 813 1445 796 1445 837 1446 788 1446 812 1446 839 1447 824 1447 814 1447 838 1448 796 1448 820 1448 840 1449 794 1449 815 1449 840 1450 817 1450 794 1450 841 1451 805 1451 831 1451 842 1452 795 1452 816 1452 841 1453 818 1453 805 1453 843 1454 827 1454 817 1454 842 1455 823 1455 819 1455 842 1456 819 1456 795 1456 844 1457 820 1457 822 1457 845 1458 814 1458 800 1458 846 1459 827 1459 843 1459 846 1460 806 1460 827 1460 846 1461 829 1461 806 1461 846 1462 832 1462 829 1462 844 1463 838 1463 820 1463 845 1464 800 1464 847 1464 848 1465 810 1465 835 1465 849 1466 804 1466 824 1466 848 1467 850 1467 828 1467 849 1468 824 1468 839 1468 851 1469 833 1469 825 1469 848 1470 828 1470 826 1470 848 1471 826 1471 810 1471 849 1472 830 1472 804 1472 852 1473 831 1473 813 1473 853 1474 809 1474 854 1474 855 1475 807 1475 830 1475 853 1476 825 1476 809 1476 855 1477 834 1477 807 1477 852 1478 813 1478 838 1478 852 1479 841 1479 831 1479 856 1480 812 1480 833 1480 857 1481 835 1481 818 1481 856 1482 837 1482 812 1482 857 1483 818 1483 841 1483 858 1484 845 1484 847 1484 859 1485 815 1485 837 1485 859 1486 840 1486 815 1486 860 1487 836 1487 811 1487 860 1488 811 1488 834 1488 861 1489 838 1489 844 1489 861 1490 852 1490 838 1490 862 1491 816 1491 836 1491 862 1492 842 1492 816 1492 862 1493 823 1493 842 1493 863 1494 841 1494 852 1494 864 1495 853 1495 854 1495 862 1496 865 1496 823 1496 866 1497 849 1497 839 1497 867 1498 817 1498 840 1498 867 1499 843 1499 817 1499 868 1500 822 1500 869 1500 868 1501 844 1501 822 1501 870 1502 839 1502 814 1502 871 1503 872 1503 850 1503 873 1504 846 1504 843 1504 870 1505 814 1505 845 1505 873 1506 832 1506 846 1506 870 1507 845 1507 858 1507 871 1508 848 1508 835 1508 873 1509 874 1509 832 1509 871 1510 850 1510 848 1510 871 1511 835 1511 857 1511 875 1512 833 1512 851 1512 876 1513 863 1513 852 1513 877 1514 830 1514 849 1514 877 1515 849 1515 866 1515 877 1516 855 1516 830 1516 876 1517 852 1517 861 1517 875 1518 856 1518 833 1518 878 1519 868 1519 869 1519 879 1520 860 1520 834 1520 880 1521 825 1521 853 1521 878 1522 869 1522 881 1522 879 1523 834 1523 855 1523 882 1524 841 1524 863 1524 880 1525 853 1525 864 1525 882 1526 871 1526 857 1526 880 1527 851 1527 825 1527 883 1528 870 1528 858 1528 884 1529 837 1529 856 1529 884 1530 859 1530 837 1530 882 1531 857 1531 841 1531 885 1532 861 1532 844 1532 886 1533 862 1533 836 1533 887 1534 867 1534 840 1534 886 1535 836 1535 860 1535 887 1536 840 1536 859 1536 886 1537 865 1537 862 1537 885 1538 844 1538 868 1538 885 1539 868 1539 878 1539 887 1540 859 1540 884 1540 888 1541 863 1541 876 1541 889 1542 883 1542 858 1542 889 1543 858 1543 847 1543 888 1544 882 1544 863 1544 889 1545 847 1545 890 1545 891 1546 885 1546 878 1546 892 1547 877 1547 866 1547 893 1548 880 1548 864 1548 894 1549 843 1549 867 1549 894 1550 873 1550 843 1550 894 1551 874 1551 873 1551 895 1552 878 1552 881 1552 896 1553 866 1553 839 1553 896 1554 839 1554 870 1554 897 1555 854 1555 898 1555 895 1556 891 1556 878 1556 899 1557 900 1557 872 1557 897 1558 864 1558 854 1558 901 1559 886 1559 860 1559 899 1560 872 1560 871 1560 901 1561 860 1561 879 1561 899 1562 871 1562 882 1562 902 1563 876 1563 861 1563 903 1564 884 1564 856 1564 901 1565 865 1565 886 1565 903 1566 856 1566 875 1566 901 1567 904 1567 865 1567 905 1568 877 1568 892 1568 905 1569 879 1569 855 1569 902 1570 861 1570 885 1570 905 1571 855 1571 877 1571 906 1572 895 1572 881 1572 907 1573 875 1573 851 1573 908 1574 870 1574 883 1574 907 1575 851 1575 880 1575 906 1576 881 1576 909 1576 908 1577 896 1577 870 1577 910 1578 911 1578 874 1578 910 1579 894 1579 867 1579 910 1580 867 1580 887 1580 912 1581 899 1581 882 1581 912 1582 882 1582 888 1582 910 1583 874 1583 894 1583 913 1584 883 1584 889 1584 914 1585 885 1585 891 1585 915 1586 887 1586 884 1586 913 1587 908 1587 883 1587 916 1588 905 1588 892 1588 914 1589 902 1589 885 1589 917 1590 907 1590 880 1590 918 1591 891 1591 895 1591 919 1592 892 1592 866 1592 918 1593 895 1593 906 1593 919 1594 866 1594 896 1594 917 1595 880 1595 893 1595 920 1596 876 1596 902 1596 921 1597 879 1597 905 1597 921 1598 905 1598 916 1598 921 1599 901 1599 879 1599 922 1600 893 1600 864 1600 921 1601 904 1601 901 1601 922 1602 864 1602 897 1602 920 1603 888 1603 876 1603 923 1604 913 1604 889 1604 924 1605 915 1605 884 1605 925 1606 906 1606 909 1606 924 1607 884 1607 903 1607 923 1608 890 1608 926 1608 923 1609 889 1609 890 1609 927 1610 875 1610 907 1610 928 1611 919 1611 896 1611 927 1612 903 1612 875 1612 928 1613 896 1613 908 1613 929 1614 918 1614 906 1614 930 1615 910 1615 887 1615 931 1616 899 1616 912 1616 931 1617 932 1617 900 1617 930 1618 911 1618 910 1618 933 1619 908 1619 913 1619 931 1620 900 1620 899 1620 930 1621 887 1621 915 1621 934 1622 898 1622 935 1622 936 1623 902 1623 914 1623 937 1624 904 1624 921 1624 936 1625 920 1625 902 1625 937 1626 921 1626 916 1626 937 1627 938 1627 904 1627 934 1628 897 1628 898 1628 939 1629 914 1629 891 1629 939 1630 891 1630 918 1630 940 1631 916 1631 892 1631 941 1632 927 1632 907 1632 940 1633 892 1633 919 1633 941 1634 907 1634 917 1634 942 1635 909 1635 943 1635 944 1636 917 1636 893 1636 942 1637 925 1637 909 1637 945 1638 933 1638 913 1638 945 1639 913 1639 923 1639 946 1640 912 1640 888 1640 944 1641 893 1641 922 1641 947 1642 940 1642 919 1642 947 1643 919 1643 928 1643 948 1644 911 1644 930 1644 946 1645 888 1645 920 1645 948 1646 930 1646 915 1646 948 1647 949 1647 911 1647 948 1648 915 1648 924 1648 950 1649 927 1649 941 1649 951 1650 928 1650 908 1650 950 1651 924 1651 903 1651 951 1652 947 1652 928 1652 952 1653 906 1653 925 1653 952 1654 929 1654 906 1654 951 1655 908 1655 933 1655 952 1656 925 1656 942 1656 950 1657 903 1657 927 1657 953 1658 938 1658 937 1658 954 1659 918 1659 929 1659 953 1660 916 1660 940 1660 954 1661 939 1661 918 1661 955 1662 922 1662 897 1662 953 1663 937 1663 916 1663 955 1664 897 1664 934 1664 956 1665 923 1665 926 1665 957 1666 920 1666 936 1666 958 1667 950 1667 941 1667 957 1668 946 1668 920 1668 956 1669 926 1669 959 1669 960 1670 936 1670 914 1670 961 1671 917 1671 944 1671 960 1672 914 1672 939 1672 960 1673 957 1673 936 1673 962 1674 951 1674 933 1674 962 1675 933 1675 945 1675 963 1676 938 1676 953 1676 961 1677 941 1677 917 1677 963 1678 940 1678 947 1678 964 1679 949 1679 948 1679 965 1680 942 1680 943 1680 963 1681 953 1681 940 1681 963 1682 966 1682 938 1682 964 1683 924 1683 950 1683 967 1684 947 1684 951 1684 964 1685 948 1685 924 1685 968 1686 952 1686 942 1686 969 1687 935 1687 565 1687 967 1688 963 1688 947 1688 969 1689 934 1689 935 1689 968 1690 942 1690 965 1690 970 1691 912 1691 946 1691 969 1692 564 1692 587 1692 970 1693 971 1693 932 1693 972 1694 923 1694 956 1694 969 1695 565 1695 564 1695 972 1696 945 1696 923 1696 970 1697 931 1697 912 1697 970 1698 932 1698 931 1698 973 1699 944 1699 922 1699 974 1700 929 1700 952 1700 973 1701 922 1701 955 1701 974 1702 954 1702 929 1702 975 1703 951 1703 962 1703 975 1704 967 1704 951 1704 974 1705 952 1705 968 1705 976 1706 950 1706 958 1706 976 1707 964 1707 950 1707 976 1708 949 1708 964 1708 977 1709 966 1709 963 1709 978 1710 939 1710 954 1710 976 1711 979 1711 949 1711 977 1712 963 1712 967 1712 978 1713 960 1713 939 1713 980 1714 958 1714 941 1714 980 1715 941 1715 961 1715 981 1716 956 1716 959 1716 982 1717 970 1717 946 1717 982 1718 946 1718 957 1718 982 1719 971 1719 970 1719 983 1720 934 1720 969 1720 984 1721 943 1721 985 1721 983 1722 955 1722 934 1722 981 1723 959 1723 986 1723 983 1724 969 1724 587 1724 984 1725 965 1725 943 1725 987 1726 945 1726 972 1726 987 1727 962 1727 945 1727 988 1728 944 1728 973 1728 989 1729 957 1729 960 1729 990 1730 967 1730 975 1730 991 1731 965 1731 984 1731 990 1732 977 1732 967 1732 988 1733 961 1733 944 1733 992 1734 958 1734 980 1734 993 1735 972 1735 956 1735 991 1736 968 1736 965 1736 992 1737 976 1737 958 1737 992 1738 979 1738 976 1738 993 1739 956 1739 981 1739 994 1740 974 1740 968 1740 995 1741 955 1741 983 1741 995 1742 973 1742 955 1742 995 1743 587 1743 602 1743 996 1744 974 1744 994 1744 995 1745 983 1745 587 1745 997 1746 975 1746 962 1746 996 1747 954 1747 974 1747 998 1748 980 1748 961 1748 996 1749 978 1749 954 1749 997 1750 962 1750 987 1750 999 1751 989 1751 960 1751 998 1752 961 1752 988 1752 1000 1753 981 1753 986 1753 999 1754 960 1754 978 1754 1001 1755 988 1755 973 1755 1000 1756 1002 1756 1003 1756 1000 1757 986 1757 1002 1757 1001 1758 973 1758 995 1758 1001 1759 995 1759 602 1759 1004 1760 984 1760 985 1760 1001 1761 602 1761 612 1761 1005 1762 966 1762 977 1762 1001 1763 612 1763 613 1763 1005 1764 977 1764 990 1764 1006 1765 982 1765 957 1765 1005 1766 1007 1766 966 1766 1008 1767 980 1767 998 1767 1008 1768 992 1768 980 1768 1006 1769 1009 1769 971 1769 1008 1770 1010 1770 979 1770 1006 1771 971 1771 982 1771 1006 1772 957 1772 989 1772 1008 1773 979 1773 992 1773 1011 1774 987 1774 972 1774 1012 1775 991 1775 984 1775 1011 1776 972 1776 993 1776 1013 1777 988 1777 1001 1777 1013 1778 1001 1778 613 1778 1013 1779 998 1779 988 1779 1012 1780 984 1780 1004 1780 1014 1781 990 1781 975 1781 1015 1782 968 1782 991 1782 1016 1783 1017 1783 1010 1783 1016 1784 640 1784 1017 1784 1014 1785 975 1785 997 1785 1016 1786 1008 1786 998 1786 1016 1787 1010 1787 1008 1787 1016 1788 1013 1788 613 1788 1015 1789 994 1789 968 1789 1016 1790 998 1790 1013 1790 1018 1791 981 1791 1000 1791 1016 1792 613 1792 639 1792 1016 1793 639 1793 640 1793 1018 1794 993 1794 981 1794 1019 1795 996 1795 994 1795 1020 1796 989 1796 999 1796 1020 1797 1009 1797 1006 1797 1020 1798 1006 1798 989 1798 1021 1799 997 1799 987 1799 1022 1800 978 1800 996 1800 1021 1801 987 1801 1011 1801 1022 1802 996 1802 1019 1802 1022 1803 999 1803 978 1803 1023 1804 1018 1804 1000 1804 1023 1805 1000 1805 1003 1805 1024 1806 1004 1806 985 1806 1025 1807 1026 1807 1007 1807 1024 1808 985 1808 1027 1808 1025 1809 1007 1809 1005 1809 1025 1810 1005 1810 990 1810 1028 1811 1012 1811 1004 1811 1025 1812 990 1812 1014 1812 1028 1813 1004 1813 1024 1813 1029 1814 1011 1814 993 1814 1030 1815 991 1815 1012 1815 1029 1816 993 1816 1018 1816 1029 1817 1021 1817 1011 1817 1031 1818 1014 1818 997 1818 1030 1819 1015 1819 991 1819 1031 1820 997 1820 1021 1820 1032 1821 994 1821 1015 1821 1032 1822 1019 1822 994 1822 1033 1823 1018 1823 1023 1823 1033 1824 1029 1824 1018 1824 1034 1825 1021 1825 1029 1825 1035 1826 1024 1826 1027 1826 1036 1827 1022 1827 1019 1827 1037 1828 1020 1828 999 1828 1038 1829 1039 1829 1040 1829 1037 1830 999 1830 1022 1830 1038 1831 1003 1831 1039 1831 1037 1832 1041 1832 1009 1832 1037 1833 1009 1833 1020 1833 1038 1834 1023 1834 1003 1834 1042 1835 1043 1835 1026 1835 1037 1836 1022 1836 1036 1836 1044 1837 1028 1837 1024 1837 1042 1838 1014 1838 1031 1838 1042 1839 1026 1839 1025 1839 1042 1840 1025 1840 1014 1840 1045 1841 1029 1841 1033 1841 1045 1842 1034 1842 1029 1842 1046 1843 1030 1843 1012 1843 1046 1844 1012 1844 1028 1844 1047 1845 1042 1845 1031 1845 1048 1846 1032 1846 1015 1846 1047 1847 1031 1847 1021 1847 1047 1848 1021 1848 1034 1848 1049 1849 1023 1849 1038 1849 1048 1850 1015 1850 1030 1850 1050 1851 1019 1851 1032 1851 1049 1852 1033 1852 1023 1852 1050 1853 1036 1853 1019 1853 1051 1854 1034 1854 1045 1854 1051 1855 1047 1855 1034 1855 226 1856 1024 1856 1035 1856 226 1857 1044 1857 1024 1857 1052 1858 1049 1858 1038 1858 1053 1859 1041 1859 1037 1859 1053 1860 1037 1860 1036 1860 1052 1861 1038 1861 1040 1861 1054 1862 1043 1862 1042 1862 1054 1863 1055 1863 1043 1863 1056 1864 1027 1864 208 1864 1056 1865 1035 1865 1027 1865 1054 1866 1042 1866 1047 1866 1057 1867 1045 1867 1033 1867 216 1868 1028 1868 1044 1868 1057 1869 1033 1869 1049 1869 216 1870 1046 1870 1028 1870 218 1871 1052 1871 1040 1871 218 1872 1040 1872 1058 1872 237 1873 1030 1873 1046 1873 237 1874 1048 1874 1030 1874 244 1875 1047 1875 1051 1875 244 1876 1054 1876 1047 1876 213 1877 1056 1877 208 1877 1059 1878 1049 1878 1052 1878 1059 1879 1057 1879 1049 1879 229 1880 1032 1880 1048 1880 1059 1881 1052 1881 218 1881 229 1882 1050 1882 1032 1882 229 1883 1048 1883 237 1883 1060 1884 233 1884 1041 1884 224 1885 1051 1885 1045 1885 1060 1886 1041 1886 1053 1886 224 1887 1045 1887 1057 1887 1060 1888 1036 1888 1050 1888 1060 1889 1053 1889 1036 1889 221 1890 1044 1890 226 1890 221 1891 216 1891 1044 1891 212 1892 1059 1892 218 1892 219 1893 218 1893 1058 1893 227 1894 226 1894 1035 1894 227 1895 1035 1895 1056 1895 242 1896 241 1896 1055 1896 227 1897 1056 1897 213 1897 242 1898 1055 1898 1054 1898 215 1899 237 1899 1046 1899 242 1900 1054 1900 244 1900 215 1901 1046 1901 216 1901 211 1902 1057 1902 1059 1902 211 1903 224 1903 1057 1903 211 1904 1059 1904 212 1904 230 1905 229 1905 237 1905 220 1906 219 1906 1058 1906 245 1907 227 1907 213 1907 220 1908 1058 1908 232 1908 223 1909 1051 1909 224 1909 223 1910 244 1910 1051 1910 234 1911 233 1911 1060 1911 234 1912 1050 1912 229 1912 234 1913 1060 1913 1050 1913 1061 1914 1062 1914 1063 1914 1064 1915 1065 1915 1066 1915 1065 1916 1067 1916 1066 1916 1068 1917 1069 1917 1070 1917 1069 1918 1071 1918 1070 1918 1072 1919 1073 1919 1074 1919 1075 1920 1076 1920 1077 1920 1078 1921 1064 1921 1079 1921 1063 1922 1080 1922 1077 1922 1081 1923 1075 1923 1077 1923 1080 1924 1082 1924 1077 1924 1082 1925 1081 1925 1077 1925 1073 1926 1083 1926 1084 1926 1064 1927 1066 1927 1079 1927 1074 1928 1073 1928 1084 1928 1085 1929 1086 1929 1087 1929 1086 1930 1078 1930 1087 1930 1067 1931 1088 1931 1089 1931 1090 1932 1091 1932 1092 1932 1088 1933 1093 1933 1089 1933 1066 1934 1067 1934 1089 1934 1094 1935 1090 1935 1092 1935 1093 1936 1095 1936 1089 1936 1070 1937 1071 1937 1096 1937 1091 1938 1072 1938 1097 1938 1072 1939 1074 1939 1097 1939 1092 1940 1091 1940 1097 1940 1071 1941 1085 1941 1096 1941 1098 1942 1068 1942 1099 1942 1100 1943 1094 1943 1101 1943 1068 1944 1070 1944 1099 1944 1084 1945 1083 1945 1102 1945 1079 1946 1066 1946 1103 1946 1083 1947 1061 1947 1102 1947 1066 1948 1089 1948 1103 1948 1061 1949 1063 1949 1102 1949 1063 1950 1077 1950 1104 1950 1078 1951 1079 1951 1105 1951 1077 1952 1076 1952 1104 1952 1087 1953 1078 1953 1105 1953 1094 1954 1092 1954 1106 1954 1101 1955 1094 1955 1106 1955 1096 1956 1085 1956 1107 1956 1074 1957 1084 1957 1108 1957 1097 1958 1074 1958 1108 1958 1085 1959 1087 1959 1107 1959 1089 1960 1095 1960 1109 1960 1084 1961 1102 1961 1110 1961 1103 1962 1089 1962 1109 1962 1108 1963 1084 1963 1110 1963 1095 1964 1111 1964 1109 1964 1099 1965 1070 1965 1112 1965 1092 1966 1097 1966 1113 1966 1097 1967 1108 1967 1114 1967 1070 1968 1096 1968 1112 1968 1099 1969 1112 1969 1115 1969 1113 1970 1097 1970 1114 1970 1076 1971 1116 1971 1117 1971 1104 1972 1076 1972 1117 1972 1102 1973 1063 1973 1117 1973 1098 1974 1099 1974 1115 1974 1063 1975 1104 1975 1117 1975 1110 1976 1102 1976 1117 1976 1105 1977 1079 1977 1118 1977 1101 1978 1106 1978 1119 1978 1079 1979 1103 1979 1118 1979 1107 1980 1087 1980 1120 1980 1087 1981 1105 1981 1120 1981 1106 1982 1092 1982 1121 1982 1092 1983 1113 1983 1121 1983 1096 1984 1107 1984 1122 1984 1123 1985 1100 1985 1124 1985 1125 1986 1123 1986 1124 1986 1100 1987 1101 1987 1124 1987 1112 1988 1096 1988 1122 1988 1118 1989 1103 1989 1126 1989 1103 1990 1109 1990 1126 1990 1109 1991 1111 1991 1126 1991 1111 1992 1127 1992 1126 1992 1108 1993 1110 1993 1128 1993 1110 1994 1117 1994 1129 1994 1112 1995 1122 1995 1130 1995 1128 1996 1110 1996 1129 1996 1117 1997 1116 1997 1129 1997 1113 1998 1114 1998 1131 1998 1115 1999 1112 1999 1130 1999 1105 2000 1118 2000 1132 2000 1121 2001 1113 2001 1131 2001 1120 2002 1105 2002 1132 2002 1108 2003 1128 2003 1133 2003 1114 2004 1108 2004 1133 2004 1131 2005 1114 2005 1133 2005 1098 2006 1115 2006 1134 2006 1135 2007 1098 2007 1134 2007 1136 2008 1135 2008 1134 2008 1119 2009 1106 2009 1137 2009 1106 2010 1121 2010 1137 2010 1107 2011 1120 2011 1138 2011 1122 2012 1107 2012 1138 2012 1121 2013 1131 2013 1139 2013 1137 2014 1121 2014 1139 2014 1116 2015 1140 2015 1141 2015 1130 2016 1122 2016 1142 2016 1129 2017 1116 2017 1141 2017 1128 2018 1129 2018 1141 2018 1122 2019 1138 2019 1142 2019 1133 2020 1128 2020 1141 2020 1101 2021 1119 2021 1143 2021 1132 2022 1118 2022 1144 2022 1118 2023 1126 2023 1144 2023 1124 2024 1101 2024 1143 2024 1126 2025 1127 2025 1144 2025 1127 2026 1145 2026 1144 2026 1133 2027 1141 2027 1146 2027 1134 2028 1115 2028 1147 2028 1141 2029 1140 2029 1146 2029 1131 2030 1133 2030 1148 2030 1115 2031 1130 2031 1147 2031 1133 2032 1146 2032 1148 2032 1125 2033 1124 2033 1149 2033 1124 2034 1143 2034 1149 2034 1150 2035 1125 2035 1149 2035 1138 2036 1120 2036 1151 2036 1120 2037 1132 2037 1151 2037 1136 2038 1134 2038 1152 2038 1137 2039 1139 2039 1153 2039 1134 2040 1147 2040 1152 2040 1139 2041 1131 2041 1154 2041 1142 2042 1138 2042 1155 2042 1131 2043 1148 2043 1154 2043 1143 2044 1119 2044 1156 2044 1138 2045 1151 2045 1155 2045 1119 2046 1137 2046 1156 2046 1130 2047 1142 2047 1157 2047 1147 2048 1130 2048 1157 2048 1140 2049 1158 2049 1159 2049 1148 2050 1146 2050 1159 2050 1146 2051 1140 2051 1159 2051 1132 2052 1144 2052 1160 2052 1143 2053 1156 2053 1161 2053 1145 2054 1162 2054 1160 2054 1151 2055 1132 2055 1160 2055 1149 2056 1143 2056 1161 2056 1144 2057 1145 2057 1160 2057 1154 2058 1148 2058 1163 2058 1159 2059 1158 2059 1163 2059 1152 2060 1147 2060 1164 2060 1147 2061 1157 2061 1164 2061 1148 2062 1159 2062 1163 2062 1153 2063 1139 2063 1165 2063 1155 2064 1151 2064 1166 2064 1139 2065 1154 2065 1165 2065 1151 2066 1160 2066 1166 2066 1154 2067 1163 2067 1165 2067 1136 2068 1152 2068 1167 2068 1168 2069 1136 2069 1167 2069 1169 2070 1150 2070 1170 2070 1171 2071 1168 2071 1167 2071 1172 2072 1171 2072 1167 2072 1150 2073 1149 2073 1170 2073 1173 2074 1172 2074 1167 2074 1142 2075 1155 2075 1174 2075 1157 2076 1142 2076 1174 2076 1137 2077 1153 2077 1175 2077 1156 2078 1137 2078 1175 2078 1157 2079 1174 2079 1176 2079 1161 2080 1156 2080 1177 2080 1164 2081 1157 2081 1176 2081 1156 2082 1175 2082 1177 2082 1162 2083 1178 2083 1179 2083 1158 2084 1180 2084 1181 2084 1163 2085 1158 2085 1181 2085 1166 2086 1160 2086 1179 2086 1160 2087 1162 2087 1179 2087 1165 2088 1163 2088 1181 2088 1152 2089 1164 2089 1182 2089 1173 2090 1167 2090 1182 2090 1149 2091 1161 2091 1183 2091 1167 2092 1152 2092 1182 2092 1155 2093 1166 2093 1184 2093 1170 2094 1149 2094 1183 2094 1174 2095 1155 2095 1184 2095 1153 2096 1165 2096 1185 2096 1175 2097 1153 2097 1185 2097 1176 2098 1174 2098 1186 2098 1187 2099 1169 2099 1188 2099 1174 2100 1184 2100 1186 2100 1169 2101 1170 2101 1188 2101 1164 2102 1176 2102 1189 2102 1173 2103 1182 2103 1189 2103 1190 2104 1173 2104 1189 2104 1191 2105 1190 2105 1189 2105 1182 2106 1164 2106 1189 2106 1166 2107 1179 2107 1192 2107 1177 2108 1175 2108 1193 2108 1178 2109 1194 2109 1192 2109 1175 2110 1185 2110 1193 2110 1179 2111 1178 2111 1192 2111 1184 2112 1166 2112 1192 2112 1186 2113 1184 2113 1195 2113 1161 2114 1177 2114 1196 2114 1183 2115 1161 2115 1196 2115 1184 2116 1192 2116 1195 2116 1176 2117 1186 2117 1197 2117 1180 2118 1198 2118 1199 2118 1189 2119 1176 2119 1197 2119 1185 2120 1165 2120 1199 2120 1191 2121 1189 2121 1197 2121 1181 2122 1180 2122 1199 2122 1165 2123 1181 2123 1199 2123 1192 2124 1194 2124 1200 2124 1195 2125 1192 2125 1200 2125 1170 2126 1183 2126 1201 2126 1194 2127 1202 2127 1200 2127 1188 2128 1170 2128 1201 2128 1186 2129 1195 2129 1203 2129 1195 2130 1200 2130 1203 2130 1191 2131 1197 2131 1203 2131 1204 2132 1191 2132 1203 2132 1205 2133 1204 2133 1203 2133 1187 2134 1188 2134 1206 2134 1197 2135 1186 2135 1203 2135 1207 2136 1205 2136 1208 2136 1203 2137 1200 2137 1208 2137 1188 2138 1201 2138 1206 2138 1205 2139 1203 2139 1208 2139 1200 2140 1202 2140 1208 2140 1202 2141 1207 2141 1208 2141 1193 2142 1185 2142 1209 2142 1196 2143 1177 2143 1210 2143 1177 2144 1193 2144 1210 2144 1183 2145 1196 2145 1211 2145 1201 2146 1183 2146 1211 2146 1198 2147 1212 2147 1213 2147 1209 2148 1185 2148 1213 2148 1199 2149 1198 2149 1213 2149 1185 2150 1199 2150 1213 2150 1206 2151 1201 2151 1214 2151 1201 2152 1211 2152 1214 2152 1215 2153 1187 2153 1216 2153 1217 2154 1215 2154 1216 2154 1187 2155 1206 2155 1216 2155 1193 2156 1209 2156 1218 2156 1210 2157 1193 2157 1218 2157 1196 2158 1210 2158 1219 2158 1211 2159 1196 2159 1219 2159 1214 2160 1211 2160 1220 2160 1211 2161 1219 2161 1220 2161 1212 2162 1221 2162 1222 2162 1213 2163 1212 2163 1222 2163 1209 2164 1213 2164 1222 2164 1218 2165 1209 2165 1222 2165 1206 2166 1214 2166 1223 2166 1216 2167 1206 2167 1223 2167 1224 2168 1217 2168 1225 2168 1217 2169 1216 2169 1225 2169 1219 2170 1210 2170 1226 2170 1210 2171 1218 2171 1226 2171 1219 2172 1226 2172 1227 2172 1220 2173 1219 2173 1227 2173 1214 2174 1220 2174 1228 2174 1223 2175 1214 2175 1228 2175 1221 2176 1229 2176 1230 2176 1218 2177 1222 2177 1230 2177 1226 2178 1218 2178 1230 2178 1222 2179 1221 2179 1230 2179 1216 2180 1223 2180 1231 2180 1225 2181 1216 2181 1231 2181 1225 2182 1231 2182 1232 2182 1224 2183 1225 2183 1232 2183 1227 2184 1226 2184 1233 2184 1226 2185 1230 2185 1233 2185 1228 2186 1220 2186 1234 2186 1220 2187 1227 2187 1234 2187 1223 2188 1228 2188 1235 2188 1231 2189 1223 2189 1235 2189 1229 2190 1236 2190 1237 2190 1230 2191 1229 2191 1237 2191 1233 2192 1230 2192 1237 2192 1231 2193 1235 2193 1238 2193 1232 2194 1231 2194 1238 2194 1239 2195 1224 2195 1240 2195 1224 2196 1232 2196 1240 2196 1234 2197 1227 2197 1241 2197 1227 2198 1233 2198 1241 2198 1228 2199 1234 2199 1242 2199 1235 2200 1228 2200 1242 2200 1238 2201 1235 2201 1243 2201 1235 2202 1242 2202 1243 2202 1236 2203 1244 2203 1245 2203 1237 2204 1236 2204 1245 2204 1233 2205 1237 2205 1245 2205 1241 2206 1233 2206 1245 2206 1232 2207 1238 2207 1246 2207 1240 2208 1232 2208 1246 2208 1247 2209 1239 2209 1248 2209 1239 2210 1240 2210 1248 2210 1242 2211 1234 2211 1249 2211 1234 2212 1241 2212 1249 2212 1243 2213 1242 2213 1250 2213 1242 2214 1249 2214 1250 2214 1238 2215 1243 2215 1251 2215 1246 2216 1238 2216 1251 2216 1244 2217 1252 2217 1253 2217 1245 2218 1244 2218 1253 2218 1241 2219 1245 2219 1253 2219 1249 2220 1241 2220 1253 2220 1240 2221 1246 2221 1254 2221 1248 2222 1240 2222 1254 2222 1255 2223 1247 2223 1256 2223 1247 2224 1248 2224 1256 2224 1249 2225 1253 2225 1257 2225 1250 2226 1249 2226 1257 2226 1243 2227 1250 2227 1258 2227 1251 2228 1243 2228 1258 2228 1246 2229 1251 2229 1259 2229 1254 2230 1246 2230 1259 2230 1253 2231 1252 2231 1260 2231 1257 2232 1253 2232 1260 2232 1252 2233 1261 2233 1260 2233 1256 2234 1248 2234 1262 2234 1248 2235 1254 2235 1262 2235 1263 2236 1255 2236 1264 2236 1255 2237 1256 2237 1264 2237 1250 2238 1257 2238 1265 2238 1258 2239 1250 2239 1265 2239 1259 2240 1251 2240 1266 2240 1251 2241 1258 2241 1266 2241 1254 2242 1259 2242 1267 2242 1262 2243 1254 2243 1267 2243 1265 2244 1257 2244 1268 2244 1257 2245 1260 2245 1268 2245 1260 2246 1261 2246 1268 2246 1261 2247 1269 2247 1268 2247 1264 2248 1256 2248 1270 2248 1256 2249 1262 2249 1270 2249 1263 2250 1264 2250 1271 2250 1272 2251 1263 2251 1271 2251 1266 2252 1258 2252 1273 2252 1258 2253 1265 2253 1273 2253 1259 2254 1266 2254 1274 2254 1267 2255 1259 2255 1274 2255 1262 2256 1267 2256 1275 2256 1270 2257 1262 2257 1275 2257 1265 2258 1268 2258 1276 2258 1273 2259 1265 2259 1276 2259 1268 2260 1269 2260 1276 2260 1269 2261 1277 2261 1276 2261 1271 2262 1264 2262 1278 2262 1264 2263 1270 2263 1278 2263 1272 2264 1271 2264 1279 2264 1280 2265 1272 2265 1279 2265 1266 2266 1273 2266 1281 2266 1274 2267 1266 2267 1281 2267 1275 2268 1267 2268 1282 2268 1267 2269 1274 2269 1282 2269 1278 2270 1270 2270 1283 2270 1270 2271 1275 2271 1283 2271 1273 2272 1276 2272 1284 2272 1281 2273 1273 2273 1284 2273 1276 2274 1277 2274 1284 2274 1277 2275 1285 2275 1284 2275 1271 2276 1278 2276 1286 2276 1279 2277 1271 2277 1286 2277 1287 2278 1280 2278 1288 2278 1280 2279 1279 2279 1288 2279 1279 2280 1286 2280 1288 2280 1274 2281 1281 2281 1289 2281 1282 2282 1274 2282 1289 2282 1275 2283 1282 2283 1290 2283 1283 2284 1275 2284 1290 2284 1286 2285 1278 2285 1291 2285 1278 2286 1283 2286 1291 2286 1281 2287 1284 2287 1292 2287 1289 2288 1281 2288 1292 2288 1284 2289 1285 2289 1292 2289 1285 2290 1293 2290 1292 2290 1286 2291 1291 2291 1294 2291 1288 2292 1286 2292 1294 2292 1287 2293 1288 2293 1295 2293 1296 2294 1287 2294 1295 2294 1282 2295 1289 2295 1297 2295 1290 2296 1282 2296 1297 2296 1283 2297 1290 2297 1298 2297 1291 2298 1283 2298 1298 2298 1205 2299 1207 2299 1299 2299 1300 2300 1171 2300 1301 2300 1291 2301 1298 2301 1302 2301 1171 2302 1172 2302 1301 2302 1294 2303 1291 2303 1302 2303 1289 2304 1292 2304 1303 2304 1297 2305 1289 2305 1303 2305 1292 2306 1293 2306 1303 2306 1172 2307 1173 2307 1304 2307 1293 2308 1305 2308 1303 2308 1295 2309 1288 2309 1306 2309 1301 2310 1172 2310 1304 2310 1307 2311 1300 2311 1308 2311 1288 2312 1294 2312 1306 2312 1300 2313 1301 2313 1308 2313 1296 2314 1295 2314 1309 2314 1310 2315 1296 2315 1309 2315 1304 2316 1173 2316 1311 2316 1173 2317 1190 2317 1311 2317 1290 2318 1297 2318 1312 2318 1298 2319 1290 2319 1312 2319 1301 2320 1304 2320 1313 2320 1302 2321 1298 2321 1314 2321 1308 2322 1301 2322 1313 2322 1315 2323 1307 2323 1316 2323 1298 2324 1312 2324 1314 2324 1294 2325 1302 2325 1317 2325 1307 2326 1308 2326 1316 2326 1306 2327 1294 2327 1317 2327 1297 2328 1303 2328 1318 2328 1312 2329 1297 2329 1318 2329 1190 2330 1191 2330 1319 2330 1303 2331 1305 2331 1318 2331 1311 2332 1190 2332 1319 2332 1305 2333 1320 2333 1318 2333 1295 2334 1306 2334 1321 2334 1304 2335 1311 2335 1322 2335 1313 2336 1304 2336 1322 2336 1309 2337 1295 2337 1321 2337 1310 2338 1309 2338 1323 2338 1308 2339 1313 2339 1324 2339 1316 2340 1308 2340 1324 2340 1325 2341 1310 2341 1323 2341 1309 2342 1321 2342 1323 2342 1326 2343 1315 2343 1327 2343 1314 2344 1312 2344 1328 2344 1315 2345 1316 2345 1327 2345 1312 2346 1318 2346 1328 2346 1302 2347 1314 2347 1329 2347 1317 2348 1302 2348 1329 2348 1191 2349 1204 2349 1330 2349 1204 2350 1205 2350 1330 2350 1319 2351 1191 2351 1330 2351 1321 2352 1306 2352 1331 2352 1322 2353 1311 2353 1332 2353 1306 2354 1317 2354 1331 2354 1311 2355 1319 2355 1332 2355 1318 2356 1320 2356 1333 2356 1328 2357 1318 2357 1333 2357 1320 2358 1334 2358 1333 2358 1313 2359 1322 2359 1335 2359 1321 2360 1331 2360 1336 2360 1324 2361 1313 2361 1335 2361 1323 2362 1321 2362 1336 2362 1330 2363 1205 2363 1337 2363 1299 2364 1338 2364 1337 2364 1205 2365 1299 2365 1337 2365 1325 2366 1323 2366 1339 2366 1340 2367 1325 2367 1339 2367 1327 2368 1316 2368 1341 2368 1323 2369 1336 2369 1339 2369 1316 2370 1324 2370 1341 2370 1329 2371 1314 2371 1342 2371 1343 2372 1326 2372 1344 2372 1314 2373 1328 2373 1342 2373 1326 2374 1327 2374 1344 2374 1327 2375 1341 2375 1344 2375 1317 2376 1329 2376 1345 2376 1319 2377 1330 2377 1346 2377 1331 2378 1317 2378 1345 2378 1332 2379 1319 2379 1346 2379 1335 2380 1322 2380 1347 2380 1340 2381 1339 2381 1348 2381 1322 2382 1332 2382 1347 2382 1336 2383 1331 2383 1349 2383 1331 2384 1345 2384 1349 2384 1324 2385 1335 2385 1350 2385 1342 2386 1328 2386 1351 2386 1328 2387 1333 2387 1351 2387 1341 2388 1324 2388 1350 2388 1333 2389 1334 2389 1351 2389 1337 2390 1338 2390 1352 2390 1338 2391 1353 2391 1352 2391 1334 2392 1354 2392 1351 2392 1330 2393 1337 2393 1352 2393 1339 2394 1336 2394 1355 2394 1346 2395 1330 2395 1352 2395 1336 2396 1349 2396 1355 2396 1348 2397 1339 2397 1355 2397 1344 2398 1341 2398 1356 2398 1341 2399 1350 2399 1356 2399 1357 2400 1340 2400 1358 2400 1359 2401 1343 2401 1360 2401 1340 2402 1348 2402 1358 2402 1329 2403 1342 2403 1361 2403 1343 2404 1344 2404 1360 2404 1345 2405 1329 2405 1361 2405 1332 2406 1346 2406 1362 2406 1347 2407 1332 2407 1362 2407 1346 2408 1352 2408 1362 2408 1348 2409 1355 2409 1363 2409 1358 2410 1348 2410 1363 2410 1345 2411 1361 2411 1364 2411 1350 2412 1335 2412 1365 2412 1349 2413 1345 2413 1364 2413 1335 2414 1347 2414 1365 2414 1357 2415 1358 2415 1366 2415 1350 2416 1365 2416 1367 2416 1356 2417 1350 2417 1367 2417 1353 2418 1368 2418 1369 2418 1362 2419 1352 2419 1369 2419 1349 2420 1364 2420 1370 2420 1352 2421 1353 2421 1369 2421 1355 2422 1349 2422 1370 2422 1363 2423 1355 2423 1370 2423 1360 2424 1344 2424 1371 2424 1342 2425 1351 2425 1372 2425 1344 2426 1356 2426 1371 2426 1361 2427 1342 2427 1372 2427 1373 2428 1359 2428 1374 2428 1351 2429 1354 2429 1372 2429 1354 2430 1375 2430 1372 2430 1359 2431 1360 2431 1374 2431 1360 2432 1371 2432 1374 2432 1358 2433 1363 2433 1376 2433 1365 2434 1347 2434 1377 2434 1363 2435 1370 2435 1378 2435 1347 2436 1362 2436 1377 2436 1376 2437 1363 2437 1378 2437 1379 2438 1357 2438 1380 2438 1365 2439 1377 2439 1381 2439 1357 2440 1366 2440 1380 2440 1367 2441 1365 2441 1381 2441 1361 2442 1372 2442 1382 2442 1364 2443 1361 2443 1382 2443 1371 2444 1356 2444 1383 2444 1356 2445 1367 2445 1383 2445 1368 2446 1384 2446 1385 2446 1358 2447 1376 2447 1386 2447 1377 2448 1362 2448 1385 2448 1366 2449 1358 2449 1386 2449 1369 2450 1368 2450 1385 2450 1362 2451 1369 2451 1385 2451 1374 2452 1371 2452 1387 2452 1380 2453 1366 2453 1386 2453 1371 2454 1383 2454 1387 2454 1370 2455 1364 2455 1388 2455 1364 2456 1382 2456 1388 2456 1389 2457 1373 2457 1390 2457 1378 2458 1370 2458 1388 2458 1373 2459 1374 2459 1390 2459 1379 2460 1380 2460 1391 2460 1377 2461 1385 2461 1392 2461 1381 2462 1377 2462 1392 2462 1383 2463 1367 2463 1393 2463 1376 2464 1378 2464 1394 2464 1394 2465 1378 2465 1395 2465 1367 2466 1381 2466 1393 2466 1378 2467 1388 2467 1395 2467 1382 2468 1372 2468 1396 2468 1383 2469 1393 2469 1397 2469 1387 2470 1383 2470 1397 2470 1375 2471 1398 2471 1396 2471 1372 2472 1375 2472 1396 2472 1384 2473 1399 2473 1400 2473 1385 2474 1384 2474 1400 2474 1392 2475 1385 2475 1400 2475 1380 2476 1386 2476 1401 2476 1374 2477 1387 2477 1402 2477 1376 2478 1394 2478 1403 2478 1390 2479 1374 2479 1402 2479 1401 2480 1386 2480 1403 2480 1386 2481 1376 2481 1403 2481 1404 2482 1389 2482 1405 2482 1379 2483 1391 2483 1406 2483 1390 2484 1402 2484 1405 2484 1407 2485 1379 2485 1406 2485 1389 2486 1390 2486 1405 2486 1388 2487 1382 2487 1408 2487 1382 2488 1396 2488 1408 2488 1381 2489 1392 2489 1409 2489 1395 2490 1388 2490 1408 2490 1393 2491 1381 2491 1409 2491 1380 2492 1401 2492 1410 2492 1393 2493 1409 2493 1411 2493 1397 2494 1393 2494 1411 2494 1391 2495 1380 2495 1410 2495 1394 2496 1395 2496 1412 2496 1387 2497 1397 2497 1413 2497 1402 2498 1387 2498 1413 2498 1407 2499 1406 2499 1414 2499 1409 2500 1392 2500 1415 2500 1399 2501 1416 2501 1415 2501 1400 2502 1399 2502 1415 2502 1412 2503 1395 2503 1417 2503 1392 2504 1400 2504 1415 2504 1395 2505 1408 2505 1417 2505 1402 2506 1413 2506 1418 2506 1405 2507 1402 2507 1418 2507 1419 2508 1404 2508 1420 2508 1401 2509 1403 2509 1421 2509 1421 2510 1403 2510 1422 2510 1403 2511 1394 2511 1422 2511 1394 2512 1412 2512 1422 2512 1404 2513 1405 2513 1420 2513 1411 2514 1409 2514 1423 2514 1408 2515 1396 2515 1424 2515 1396 2516 1398 2516 1424 2516 1409 2517 1415 2517 1423 2517 1417 2518 1408 2518 1424 2518 1398 2519 1425 2519 1424 2519 1406 2520 1391 2520 1426 2520 1413 2521 1397 2521 1427 2521 1391 2522 1410 2522 1426 2522 1414 2523 1406 2523 1426 2523 1397 2524 1411 2524 1427 2524 1401 2525 1421 2525 1428 2525 1410 2526 1401 2526 1428 2526 1419 2527 1420 2527 1429 2527 1407 2528 1414 2528 1430 2528 1418 2529 1413 2529 1431 2529 1432 2530 1407 2530 1430 2530 1413 2531 1427 2531 1431 2531 1416 2532 1433 2532 1434 2532 1423 2533 1415 2533 1434 2533 1417 2534 1424 2534 1435 2534 1424 2535 1425 2535 1435 2535 1415 2536 1416 2536 1434 2536 1425 2537 1436 2537 1435 2537 1412 2538 1417 2538 1437 2538 1429 2539 1420 2539 1438 2539 1420 2540 1405 2540 1438 2540 1417 2541 1435 2541 1437 2541 1405 2542 1418 2542 1438 2542 1414 2543 1426 2543 1439 2543 1430 2544 1414 2544 1439 2544 1440 2545 1419 2545 1441 2545 1419 2546 1429 2546 1441 2546 1421 2547 1422 2547 1442 2547 1427 2548 1411 2548 1443 2548 1411 2549 1423 2549 1443 2549 1422 2550 1412 2550 1444 2550 1412 2551 1437 2551 1444 2551 1442 2552 1422 2552 1444 2552 1429 2553 1438 2553 1445 2553 1431 2554 1427 2554 1446 2554 1432 2555 1430 2555 1447 2555 1426 2556 1410 2556 1448 2556 1410 2557 1428 2557 1448 2557 1427 2558 1443 2558 1446 2558 1439 2559 1426 2559 1448 2559 1421 2560 1442 2560 1449 2560 1428 2561 1421 2561 1449 2561 1440 2562 1441 2562 1450 2562 1418 2563 1431 2563 1451 2563 1438 2564 1418 2564 1451 2564 1445 2565 1438 2565 1451 2565 1435 2566 1436 2566 1452 2566 1437 2567 1435 2567 1452 2567 1443 2568 1423 2568 1453 2568 1423 2569 1434 2569 1453 2569 1430 2570 1439 2570 1454 2570 1433 2571 1455 2571 1453 2571 1434 2572 1433 2572 1453 2572 1439 2573 1448 2573 1456 2573 1441 2574 1429 2574 1457 2574 1454 2575 1439 2575 1456 2575 1429 2576 1445 2576 1457 2576 1450 2577 1441 2577 1457 2577 1432 2578 1447 2578 1458 2578 1459 2579 1432 2579 1458 2579 1445 2580 1451 2580 1460 2580 1442 2581 1444 2581 1461 2581 1462 2582 1440 2582 1463 2582 1440 2583 1450 2583 1463 2583 1444 2584 1437 2584 1464 2584 1437 2585 1452 2585 1464 2585 1461 2586 1444 2586 1464 2586 1443 2587 1453 2587 1465 2587 1452 2588 1436 2588 1464 2588 1446 2589 1443 2589 1465 2589 1436 2590 1466 2590 1464 2590 1430 2591 1454 2591 1467 2591 1447 2592 1430 2592 1467 2592 1450 2593 1457 2593 1468 2593 1448 2594 1428 2594 1469 2594 1463 2595 1450 2595 1468 2595 1428 2596 1449 2596 1469 2596 1456 2597 1448 2597 1469 2597 1451 2598 1431 2598 1470 2598 1431 2599 1446 2599 1470 2599 1460 2600 1451 2600 1470 2600 1442 2601 1461 2601 1471 2601 1462 2602 1463 2602 1472 2602 1449 2603 1442 2603 1471 2603 1457 2604 1445 2604 1473 2604 1445 2605 1460 2605 1473 2605 1459 2606 1458 2606 1474 2606 1468 2607 1457 2607 1473 2607 1454 2608 1456 2608 1475 2608 1460 2609 1470 2609 1476 2609 1461 2610 1464 2610 1477 2610 1455 2611 1478 2611 1479 2611 1464 2612 1466 2612 1477 2612 1475 2613 1456 2613 1480 2613 1453 2614 1455 2614 1479 2614 1456 2615 1469 2615 1480 2615 1465 2616 1453 2616 1479 2616 1472 2617 1463 2617 1481 2617 1474 2618 1458 2618 1482 2618 1463 2619 1468 2619 1481 2619 1458 2620 1447 2620 1482 2620 1468 2621 1473 2621 1483 2621 1447 2622 1467 2622 1482 2622 1459 2623 1474 2623 1484 2623 1485 2624 1462 2624 1486 2624 1487 2625 1459 2625 1484 2625 1462 2626 1472 2626 1486 2626 1454 2627 1475 2627 1488 2627 1446 2628 1465 2628 1489 2628 1470 2629 1446 2629 1489 2629 1467 2630 1454 2630 1488 2630 1476 2631 1470 2631 1489 2631 1449 2632 1471 2632 1490 2632 1472 2633 1481 2633 1491 2633 1480 2634 1469 2634 1490 2634 1469 2635 1449 2635 1490 2635 1471 2636 1461 2636 1492 2636 1461 2637 1477 2637 1492 2637 1473 2638 1460 2638 1493 2638 1477 2639 1466 2639 1492 2639 1466 2640 1494 2640 1492 2640 1460 2641 1476 2641 1493 2641 1483 2642 1473 2642 1493 2642 1484 2643 1474 2643 1495 2643 1476 2644 1489 2644 1496 2644 1474 2645 1482 2645 1495 2645 1485 2646 1486 2646 1497 2646 1475 2647 1480 2647 1498 2647 1480 2648 1490 2648 1499 2648 1498 2649 1480 2649 1499 2649 1481 2650 1468 2650 1500 2650 1468 2651 1483 2651 1500 2651 1487 2652 1484 2652 1501 2652 1483 2653 1493 2653 1502 2653 1500 2654 1483 2654 1502 2654 1482 2655 1467 2655 1503 2655 1467 2656 1488 2656 1503 2656 1478 2657 1504 2657 1505 2657 1479 2658 1478 2658 1505 2658 1489 2659 1465 2659 1505 2659 1465 2660 1479 2660 1505 2660 1496 2661 1489 2661 1505 2661 1490 2662 1471 2662 1506 2662 1471 2663 1492 2663 1506 2663 1492 2664 1494 2664 1506 2664 1497 2665 1486 2665 1507 2665 1486 2666 1472 2666 1507 2666 1472 2667 1491 2667 1507 2667 1484 2668 1495 2668 1508 2668 1491 2669 1481 2669 1509 2669 1475 2670 1498 2670 1510 2670 1481 2671 1500 2671 1509 2671 1511 2672 1485 2672 1512 2672 1488 2673 1475 2673 1510 2673 1487 2674 1501 2674 1513 2674 1485 2675 1497 2675 1512 2675 1514 2676 1487 2676 1513 2676 1496 2677 1505 2677 1515 2677 1504 2678 1516 2678 1515 2678 1505 2679 1504 2679 1515 2679 1502 2680 1493 2680 1517 2680 1508 2681 1495 2681 1518 2681 1482 2682 1503 2682 1518 2682 1495 2683 1482 2683 1518 2683 1493 2684 1476 2684 1517 2684 1476 2685 1496 2685 1517 2685 1497 2686 1507 2686 1519 2686 1498 2687 1499 2687 1520 2687 1512 2688 1497 2688 1519 2688 1499 2689 1490 2689 1521 2689 1506 2690 1494 2690 1521 2690 1500 2691 1502 2691 1522 2691 1494 2692 1523 2692 1521 2692 1490 2693 1506 2693 1521 2693 1509 2694 1500 2694 1522 2694 1501 2695 1484 2695 1524 2695 1511 2696 1512 2696 1525 2696 1484 2697 1508 2697 1524 2697 1513 2698 1501 2698 1524 2698 1503 2699 1488 2699 1526 2699 1518 2700 1503 2700 1526 2700 1488 2701 1510 2701 1526 2701 1502 2702 1517 2702 1527 2702 1491 2703 1509 2703 1528 2703 1508 2704 1518 2704 1529 2704 1507 2705 1491 2705 1528 2705 1509 2706 1522 2706 1530 2706 1514 2707 1513 2707 1531 2707 1496 2708 1515 2708 1532 2708 1515 2709 1516 2709 1532 2709 1498 2710 1520 2710 1533 2710 1510 2711 1498 2711 1533 2711 1517 2712 1496 2712 1532 2712 1499 2713 1521 2713 1534 2713 1512 2714 1519 2714 1535 2714 1520 2715 1499 2715 1534 2715 1521 2716 1523 2716 1534 2716 1519 2717 1507 2717 1536 2717 1513 2718 1524 2718 1537 2718 1507 2719 1528 2719 1536 2719 1531 2720 1513 2720 1537 2720 1535 2721 1519 2721 1536 2721 1518 2722 1526 2722 1538 2722 1539 2723 1511 2723 1540 2723 1529 2724 1518 2724 1538 2724 1511 2725 1525 2725 1540 2725 1541 2726 1514 2726 1542 2726 1522 2727 1502 2727 1543 2727 1502 2728 1527 2728 1543 2728 1514 2729 1531 2729 1542 2729 1508 2730 1529 2730 1544 2730 1516 2731 1545 2731 1546 2731 1524 2732 1508 2732 1544 2732 1527 2733 1517 2733 1546 2733 1517 2734 1532 2734 1546 2734 1532 2735 1516 2735 1546 2735 1543 2736 1527 2736 1546 2736 1525 2737 1512 2737 1547 2737 1526 2738 1510 2738 1548 2738 1510 2739 1533 2739 1548 2739 1512 2740 1535 2740 1547 2740 1540 2741 1525 2741 1547 2741 1520 2742 1534 2742 1549 2742 1533 2743 1520 2743 1549 2743 1509 2744 1530 2744 1550 2744 1523 2745 1551 2745 1549 2745 1536 2746 1528 2746 1550 2746 1534 2747 1523 2747 1549 2747 1528 2748 1509 2748 1550 2748 1529 2749 1538 2749 1552 2749 1539 2750 1540 2750 1553 2750 1530 2751 1522 2751 1554 2751 1531 2752 1537 2752 1555 2752 1522 2753 1543 2753 1554 2753 1535 2754 1536 2754 1556 2754 1524 2755 1544 2755 1557 2755 1537 2756 1524 2756 1557 2756 1546 2757 1545 2757 1558 2757 1541 2758 1542 2758 1559 2758 1543 2759 1546 2759 1558 2759 1536 2760 1550 2760 1560 2760 1538 2761 1526 2761 1561 2761 1556 2762 1536 2762 1560 2762 1526 2763 1548 2763 1561 2763 1552 2764 1538 2764 1561 2764 1548 2765 1533 2765 1562 2765 1540 2766 1547 2766 1563 2766 1533 2767 1549 2767 1562 2767 1549 2768 1551 2768 1562 2768 1561 2769 1548 2769 1562 2769 1564 2770 1539 2770 1565 2770 1531 2771 1555 2771 1566 2771 1559 2772 1542 2772 1566 2772 1539 2773 1553 2773 1565 2773 1542 2774 1531 2774 1566 2774 1547 2775 1535 2775 1567 2775 1529 2776 1552 2776 1568 2776 1535 2777 1556 2777 1567 2777 1563 2778 1547 2778 1567 2778 1557 2779 1544 2779 1568 2779 1544 2780 1529 2780 1568 2780 1550 2781 1530 2781 1569 2781 1570 2782 1541 2782 1571 2782 1530 2783 1554 2783 1569 2783 1541 2784 1559 2784 1571 2784 1558 2785 1545 2785 1572 2785 1545 2786 1573 2786 1572 2786 1554 2787 1543 2787 1572 2787 1552 2788 1561 2788 1574 2788 1543 2789 1558 2789 1572 2789 1555 2790 1537 2790 1575 2790 1553 2791 1540 2791 1576 2791 1540 2792 1563 2792 1576 2792 1565 2793 1553 2793 1576 2793 1537 2794 1557 2794 1575 2794 1561 2795 1562 2795 1577 2795 1562 2796 1551 2796 1577 2796 1574 2797 1561 2797 1577 2797 1551 2798 1578 2798 1577 2798 1556 2799 1560 2799 1579 2799 1557 2800 1568 2800 1580 2800 1575 2801 1557 2801 1580 2801 1564 2802 1565 2802 1581 2802 1571 2803 1559 2803 1582 2803 1559 2804 1566 2804 1582 2804 1560 2805 1550 2805 1583 2805 1550 2806 1569 2806 1583 2806 1566 2807 1555 2807 1584 2807 1579 2808 1560 2808 1583 2808 1563 2809 1567 2809 1585 2809 1555 2810 1575 2810 1584 2810 1568 2811 1552 2811 1586 2811 1552 2812 1574 2812 1586 2812 1572 2813 1573 2813 1587 2813 1569 2814 1554 2814 1587 2814 1554 2815 1572 2815 1587 2815 1570 2816 1571 2816 1588 2816 1565 2817 1576 2817 1589 2817 1585 2818 1567 2818 1590 2818 1574 2819 1577 2819 1591 2819 1577 2820 1578 2820 1591 2820 1567 2821 1556 2821 1590 2821 1571 2822 1582 2822 1592 2822 1556 2823 1579 2823 1590 2823 1588 2824 1571 2824 1592 2824 1593 2825 1564 2825 1594 2825 1564 2826 1581 2826 1594 2826 1575 2827 1580 2827 1595 2827 1563 2828 1585 2828 1596 2828 1570 2829 1588 2829 1597 2829 1598 2830 1570 2830 1597 2830 1576 2831 1563 2831 1596 2831 1579 2832 1583 2832 1599 2832 1568 2833 1586 2833 1600 2833 1583 2834 1569 2834 1601 2834 1580 2835 1568 2835 1600 2835 1587 2836 1573 2836 1601 2836 1573 2837 1602 2837 1601 2837 1582 2838 1566 2838 1603 2838 1566 2839 1584 2839 1603 2839 1569 2840 1587 2840 1601 2840 1592 2841 1582 2841 1603 2841 1565 2842 1589 2842 1604 2842 1594 2843 1581 2843 1604 2843 1574 2844 1591 2844 1605 2844 1586 2845 1574 2845 1605 2845 1591 2846 1578 2846 1605 2846 1581 2847 1565 2847 1604 2847 1578 2848 1606 2848 1605 2848 1584 2849 1575 2849 1607 2849 1575 2850 1595 2850 1607 2850 1603 2851 1584 2851 1607 2851 1585 2852 1590 2852 1608 2852 1576 2853 1596 2853 1609 2853 1588 2854 1592 2854 1610 2854 1589 2855 1576 2855 1609 2855 1593 2856 1594 2856 1611 2856 1592 2857 1603 2857 1612 2857 1579 2858 1599 2858 1613 2858 1590 2859 1579 2859 1613 2859 1595 2860 1580 2860 1614 2860 1580 2861 1600 2861 1614 2861 1608 2862 1590 2862 1613 2862 1599 2863 1583 2863 1615 2863 1601 2864 1602 2864 1615 2864 1583 2865 1601 2865 1615 2865 1598 2866 1597 2866 1616 2866 1594 2867 1604 2867 1617 2867 1611 2868 1594 2868 1617 2868 1586 2869 1605 2869 1618 2869 1596 2870 1585 2870 1619 2870 1600 2871 1586 2871 1618 2871 1585 2872 1608 2872 1619 2872 1609 2873 1596 2873 1619 2873 1605 2874 1606 2874 1618 2874 1597 2875 1588 2875 1620 2875 1616 2876 1597 2876 1620 2876 1588 2877 1610 2877 1620 2877 1621 2878 1593 2878 1622 2878 1593 2879 1611 2879 1622 2879 1603 2880 1607 2880 1623 2880 1617 2881 1604 2881 1624 2881 1612 2882 1603 2882 1623 2882 1604 2883 1589 2883 1624 2883 1589 2884 1609 2884 1624 2884 1625 2885 1598 2885 1626 2885 1598 2886 1616 2886 1626 2886 1608 2887 1613 2887 1627 2887 1595 2888 1614 2888 1628 2888 1602 2889 1629 2889 1630 2889 1607 2890 1595 2890 1628 2890 1615 2891 1602 2891 1630 2891 1613 2892 1599 2892 1630 2892 1599 2893 1615 2893 1630 2893 1627 2894 1613 2894 1630 2894 1592 2895 1612 2895 1631 2895 1609 2896 1619 2896 1632 2896 1610 2897 1592 2897 1631 2897 1614 2898 1600 2898 1633 2898 1600 2899 1618 2899 1633 2899 1606 2900 1634 2900 1633 2900 1618 2901 1606 2901 1633 2901 1611 2902 1617 2902 1635 2902 1612 2903 1623 2903 1636 2903 1622 2904 1611 2904 1635 2904 1631 2905 1612 2905 1636 2905 1617 2906 1624 2906 1637 2906 1626 2907 1616 2907 1638 2907 1619 2908 1608 2908 1639 2908 1616 2909 1620 2909 1638 2909 1608 2910 1627 2910 1639 2910 1638 2911 1620 2911 1640 2911 1610 2912 1631 2912 1640 2912 1620 2913 1610 2913 1640 2913 1621 2914 1622 2914 1641 2914 1642 2915 1625 2915 1643 2915 1630 2916 1629 2916 1644 2916 1625 2917 1626 2917 1643 2917 1627 2918 1630 2918 1644 2918 1607 2919 1628 2919 1645 2919 1622 2920 1635 2920 1646 2920 1641 2921 1622 2921 1646 2921 1623 2922 1607 2922 1645 2922 1636 2923 1623 2923 1645 2923 1645 2924 1628 2924 1647 2924 1624 2925 1609 2925 1648 2925 1628 2926 1614 2926 1647 2926 1609 2927 1632 2927 1648 2927 1614 2928 1633 2928 1647 2928 1637 2929 1624 2929 1648 2929 1633 2930 1634 2930 1647 2930 1649 2931 1621 2931 1650 2931 1621 2932 1641 2932 1650 2932 1626 2933 1638 2933 1651 2933 1631 2934 1636 2934 1652 2934 1632 2935 1619 2935 1653 2935 1619 2936 1639 2936 1653 2936 1635 2937 1617 2937 1654 2937 1636 2938 1645 2938 1655 2938 1617 2939 1637 2939 1654 2939 1638 2940 1640 2940 1656 2940 1651 2941 1638 2941 1656 2941 1629 2942 1657 2942 1658 2942 1639 2943 1627 2943 1658 2943 1627 2944 1644 2944 1658 2944 1640 2945 1631 2945 1659 2945 1631 2946 1652 2946 1659 2946 1644 2947 1629 2947 1658 2947 1656 2948 1640 2948 1659 2948 1637 2949 1648 2949 1660 2949 1645 2950 1647 2950 1661 2950 1647 2951 1634 2951 1661 2951 1654 2952 1637 2952 1660 2952 1655 2953 1645 2953 1661 2953 1634 2954 1662 2954 1661 2954 1641 2955 1646 2955 1663 2955 1643 2956 1626 2956 1664 2956 1626 2957 1651 2957 1664 2957 1650 2958 1641 2958 1663 2958 1635 2959 1654 2959 1665 2959 1651 2960 1656 2960 1666 2960 1646 2961 1635 2961 1665 2961 1648 2962 1632 2962 1667 2962 1632 2963 1653 2963 1667 2963 1643 2964 1664 2964 1668 2964 1660 2965 1648 2965 1667 2965 1642 2966 1643 2966 1668 2966 1652 2967 1636 2967 1669 2967 1649 2968 1650 2968 1670 2968 1636 2969 1655 2969 1669 2969 1658 2970 1657 2970 1671 2970 1653 2971 1639 2971 1671 2971 1655 2972 1661 2972 1672 2972 1639 2973 1658 2973 1671 2973 1661 2974 1662 2974 1672 2974 1650 2975 1663 2975 1673 2975 1656 2976 1659 2976 1674 2976 1670 2977 1650 2977 1673 2977 1666 2978 1656 2978 1674 2978 1659 2979 1652 2979 1675 2979 1652 2980 1669 2980 1675 2980 1665 2981 1654 2981 1062 2981 1674 2982 1659 2982 1675 2982 1654 2983 1660 2983 1062 2983 1649 2984 1670 2984 1676 2984 1664 2985 1651 2985 1677 2985 1651 2986 1666 2986 1677 2986 1678 2987 1649 2987 1676 2987 1660 2988 1667 2988 1082 2988 1646 2989 1665 2989 1679 2989 1666 2990 1674 2990 1065 2990 1669 2991 1655 2991 1680 2991 1655 2992 1672 2992 1680 2992 1663 2993 1646 2993 1679 2993 1672 2994 1662 2994 1680 2994 1673 2995 1663 2995 1679 2995 1657 2996 1075 2996 1681 2996 1662 2997 1682 2997 1680 2997 1653 2998 1671 2998 1681 2998 1082 2999 1667 2999 1681 2999 1664 3000 1677 3000 1086 3000 1667 3001 1653 3001 1681 3001 1668 3002 1664 3002 1086 3002 1671 3003 1657 3003 1681 3003 1665 3004 1062 3004 1061 3004 1669 3005 1680 3005 1683 3005 1679 3006 1665 3006 1061 3006 1675 3007 1669 3007 1683 3007 1680 3008 1682 3008 1683 3008 1674 3009 1675 3009 1684 3009 1676 3010 1670 3010 1072 3010 1670 3011 1673 3011 1072 3011 1065 3012 1674 3012 1684 3012 1675 3013 1683 3013 1684 3013 1685 3014 1642 3014 1071 3014 1642 3015 1668 3015 1071 3015 1069 3016 1685 3016 1071 3016 1673 3017 1679 3017 1073 3017 1072 3018 1673 3018 1073 3018 1062 3019 1660 3019 1080 3019 1666 3020 1065 3020 1064 3020 1677 3021 1666 3021 1064 3021 1660 3022 1082 3022 1080 3022 1065 3023 1684 3023 1067 3023 1678 3024 1676 3024 1090 3024 1086 3025 1677 3025 1078 3025 1677 3026 1064 3026 1078 3026 1681 3027 1075 3027 1081 3027 1082 3028 1681 3028 1081 3028 1682 3029 1093 3029 1686 3029 1683 3030 1682 3030 1686 3030 1684 3031 1683 3031 1686 3031 1676 3032 1072 3032 1091 3032 1067 3033 1684 3033 1686 3033 1090 3034 1676 3034 1091 3034 1071 3035 1668 3035 1085 3035 1679 3036 1061 3036 1083 3036 1668 3037 1086 3037 1085 3037 1073 3038 1679 3038 1083 3038 1100 3039 1678 3039 1094 3039 1067 3040 1686 3040 1088 3040 1686 3041 1093 3041 1088 3041 1678 3042 1090 3042 1094 3042 1062 3043 1080 3043 1063 3043 589 3044 1687 3044 1688 3044 589 3045 566 3045 1687 3045 590 3046 1688 3046 1689 3046 590 3047 589 3047 1688 3047 617 3048 1689 3048 1690 3048 617 3049 590 3049 1689 3049 618 3050 1690 3050 1691 3050 618 3051 617 3051 1690 3051 650 3052 1691 3052 1692 3052 650 3053 618 3053 1691 3053 677 3054 1692 3054 1693 3054 677 3055 650 3055 1692 3055 715 3056 1693 3056 1694 3056 715 3057 677 3057 1693 3057 756 3058 1694 3058 1695 3058 756 3059 715 3059 1694 3059 800 3060 756 3060 1695 3060 800 3061 1695 3061 1696 3061 847 3062 1696 3062 1697 3062 847 3063 800 3063 1696 3063 890 3064 1697 3064 1698 3064 890 3065 847 3065 1697 3065 926 3066 1698 3066 1699 3066 926 3067 890 3067 1698 3067 959 3068 1699 3068 1700 3068 959 3069 926 3069 1699 3069 986 3070 1700 3070 1701 3070 986 3071 959 3071 1700 3071 1002 3072 1701 3072 1702 3072 1002 3073 986 3073 1701 3073 1003 3074 1702 3074 1703 3074 1003 3075 1002 3075 1702 3075 1039 3076 1703 3076 1704 3076 1039 3077 1003 3077 1703 3077 1040 3078 1704 3078 1705 3078 1040 3079 1039 3079 1704 3079 1058 3080 1705 3080 1706 3080 1058 3081 1040 3081 1705 3081 232 3082 1706 3082 1707 3082 232 3083 1707 3083 1708 3083 232 3084 1058 3084 1706 3084 251 3085 1708 3085 1709 3085 251 3086 232 3086 1708 3086 278 3087 1709 3087 1710 3087 278 3088 251 3088 1709 3088 314 3089 1710 3089 1711 3089 314 3090 278 3090 1710 3090 341 3091 1711 3091 1712 3091 341 3092 314 3092 1711 3092 367 3093 1712 3093 1713 3093 367 3094 341 3094 1712 3094 389 3095 1713 3095 1714 3095 389 3096 367 3096 1713 3096 408 3097 1714 3097 1715 3097 408 3098 389 3098 1714 3098 420 3099 1715 3099 1716 3099 420 3100 408 3100 1715 3100 438 3101 1716 3101 1717 3101 438 3102 420 3102 1716 3102 453 3103 1717 3103 1718 3103 453 3104 438 3104 1717 3104 469 3105 1718 3105 1719 3105 469 3106 453 3106 1718 3106 474 3107 1719 3107 1720 3107 474 3108 469 3108 1719 3108 498 3109 474 3109 1720 3109 498 3110 1720 3110 1721 3110 523 3111 498 3111 1721 3111 523 3112 1721 3112 1722 3112 551 3113 523 3113 1722 3113 551 3114 1722 3114 1723 3114 584 3115 551 3115 1723 3115 584 3116 1723 3116 1724 3116 633 3117 584 3117 1724 3117 633 3118 1724 3118 1725 3118 682 3119 633 3119 1725 3119 682 3120 1725 3120 1726 3120 717 3121 682 3121 1726 3121 717 3122 1726 3122 1727 3122 749 3123 717 3123 1727 3123 749 3124 1727 3124 1728 3124 778 3125 749 3125 1728 3125 778 3126 1728 3126 1729 3126 799 3127 778 3127 1729 3127 799 3128 1729 3128 1730 3128 821 3129 799 3129 1730 3129 821 3130 1730 3130 1731 3130 822 3131 1731 3131 1732 3131 822 3132 821 3132 1731 3132 869 3133 822 3133 1732 3133 869 3134 1732 3134 1733 3134 881 3135 1733 3135 1734 3135 881 3136 869 3136 1733 3136 909 3137 1734 3137 1735 3137 909 3138 881 3138 1734 3138 943 3139 1735 3139 1736 3139 943 3140 909 3140 1735 3140 985 3141 1736 3141 1737 3141 985 3142 943 3142 1736 3142 1027 3143 1737 3143 1738 3143 1027 3144 985 3144 1737 3144 208 3145 1738 3145 1739 3145 208 3146 1027 3146 1738 3146 209 3147 1739 3147 1740 3147 209 3148 208 3148 1739 3148 257 3149 1740 3149 1741 3149 257 3150 209 3150 1740 3150 280 3151 1741 3151 1742 3151 280 3152 257 3152 1741 3152 297 3153 1742 3153 1743 3153 297 3154 280 3154 1742 3154 309 3155 1743 3155 1744 3155 309 3156 297 3156 1743 3156 310 3157 1744 3157 1745 3157 310 3158 309 3158 1744 3158 339 3159 1745 3159 1746 3159 339 3160 310 3160 1745 3160 355 3161 339 3161 1746 3161 355 3162 1746 3162 1747 3162 363 3163 355 3163 1747 3163 363 3164 1747 3164 1748 3164 383 3165 363 3165 1748 3165 383 3166 1748 3166 1749 3166 406 3167 383 3167 1749 3167 406 3168 1749 3168 1750 3168 433 3169 406 3169 1750 3169 465 3170 433 3170 1750 3170 465 3171 1750 3171 1751 3171 495 3172 465 3172 1751 3172 495 3173 1751 3173 1752 3173 517 3174 495 3174 1752 3174 517 3175 1752 3175 1753 3175 538 3176 517 3176 1753 3176 538 3177 1753 3177 1754 3177 556 3178 538 3178 1754 3178 556 3179 1754 3179 1755 3179 573 3180 556 3180 1755 3180 573 3181 1755 3181 1756 3181 593 3182 573 3182 1756 3182 593 3183 1756 3183 1757 3183 594 3184 593 3184 1757 3184 594 3185 1757 3185 1758 3185 643 3186 594 3186 1758 3186 643 3187 1758 3187 1759 3187 652 3188 643 3188 1759 3188 652 3189 1759 3189 1760 3189 687 3190 652 3190 1760 3190 687 3191 1760 3191 1761 3191 723 3192 687 3192 1761 3192 723 3193 1761 3193 1762 3193 766 3194 723 3194 1762 3194 766 3195 1762 3195 1763 3195 809 3196 766 3196 1763 3196 809 3197 1763 3197 1764 3197 854 3198 1764 3198 1765 3198 854 3199 809 3199 1764 3199 898 3200 1765 3200 1766 3200 898 3201 854 3201 1765 3201 935 3202 1766 3202 1767 3202 935 3203 898 3203 1766 3203 565 3204 1767 3204 1768 3204 565 3205 935 3205 1767 3205 566 3206 1768 3206 1687 3206 566 3207 565 3207 1768 3207 1224 3208 1769 3208 1770 3208 1224 3209 1239 3209 1769 3209 1217 3210 1770 3210 1771 3210 1217 3211 1224 3211 1770 3211 1215 3212 1771 3212 1772 3212 1215 3213 1217 3213 1771 3213 1187 3214 1772 3214 1773 3214 1187 3215 1215 3215 1772 3215 1169 3216 1773 3216 1774 3216 1169 3217 1187 3217 1773 3217 1150 3218 1774 3218 1775 3218 1150 3219 1169 3219 1774 3219 1125 3220 1775 3220 1776 3220 1125 3221 1150 3221 1775 3221 1123 3222 1776 3222 1777 3222 1123 3223 1125 3223 1776 3223 1100 3224 1777 3224 1778 3224 1100 3225 1123 3225 1777 3225 1678 3226 1778 3226 1779 3226 1678 3227 1100 3227 1778 3227 1649 3228 1779 3228 1780 3228 1649 3229 1678 3229 1779 3229 1621 3230 1780 3230 1781 3230 1621 3231 1649 3231 1780 3231 1593 3232 1781 3232 1782 3232 1593 3233 1621 3233 1781 3233 1564 3234 1782 3234 1783 3234 1564 3235 1593 3235 1782 3235 1539 3236 1783 3236 1784 3236 1539 3237 1564 3237 1783 3237 1511 3238 1784 3238 1785 3238 1511 3239 1539 3239 1784 3239 1485 3240 1785 3240 1786 3240 1485 3241 1511 3241 1785 3241 1462 3242 1786 3242 1787 3242 1462 3243 1485 3243 1786 3243 1440 3244 1787 3244 1788 3244 1440 3245 1462 3245 1787 3245 1419 3246 1440 3246 1788 3246 1419 3247 1788 3247 1789 3247 1404 3248 1419 3248 1789 3248 1404 3249 1789 3249 1790 3249 1389 3250 1404 3250 1790 3250 1389 3251 1790 3251 1791 3251 1373 3252 1389 3252 1791 3252 1373 3253 1791 3253 1792 3253 1359 3254 1373 3254 1792 3254 1359 3255 1792 3255 1793 3255 1343 3256 1793 3256 1794 3256 1343 3257 1359 3257 1793 3257 1326 3258 1794 3258 1795 3258 1326 3259 1343 3259 1794 3259 1315 3260 1795 3260 1796 3260 1315 3261 1326 3261 1795 3261 1307 3262 1796 3262 1797 3262 1307 3263 1315 3263 1796 3263 1300 3264 1797 3264 1798 3264 1300 3265 1307 3265 1797 3265 1171 3266 1798 3266 1799 3266 1171 3267 1300 3267 1798 3267 1168 3268 1799 3268 1800 3268 1168 3269 1171 3269 1799 3269 1136 3270 1800 3270 1801 3270 1136 3271 1168 3271 1800 3271 1135 3272 1801 3272 1802 3272 1135 3273 1136 3273 1801 3273 1098 3274 1802 3274 1803 3274 1098 3275 1135 3275 1802 3275 1068 3276 1803 3276 1804 3276 1068 3277 1098 3277 1803 3277 1069 3278 1804 3278 1805 3278 1069 3279 1068 3279 1804 3279 1685 3280 1805 3280 1806 3280 1685 3281 1069 3281 1805 3281 1642 3282 1806 3282 1807 3282 1642 3283 1685 3283 1806 3283 1625 3284 1807 3284 1808 3284 1625 3285 1642 3285 1807 3285 1598 3286 1808 3286 1809 3286 1598 3287 1625 3287 1808 3287 1570 3288 1809 3288 1810 3288 1570 3289 1598 3289 1809 3289 1541 3290 1810 3290 1811 3290 1541 3291 1570 3291 1810 3291 1514 3292 1811 3292 1812 3292 1514 3293 1541 3293 1811 3293 1487 3294 1812 3294 1813 3294 1487 3295 1514 3295 1812 3295 1459 3296 1487 3296 1813 3296 1459 3297 1813 3297 1814 3297 1432 3298 1459 3298 1814 3298 1432 3299 1814 3299 1815 3299 1407 3300 1432 3300 1815 3300 1407 3301 1815 3301 1816 3301 1379 3302 1407 3302 1816 3302 1379 3303 1816 3303 1817 3303 1357 3304 1379 3304 1817 3304 1357 3305 1817 3305 1818 3305 1340 3306 1357 3306 1818 3306 1340 3307 1818 3307 1819 3307 1325 3308 1340 3308 1819 3308 1325 3309 1819 3309 1820 3309 1310 3310 1325 3310 1820 3310 1310 3311 1820 3311 1821 3311 1296 3312 1310 3312 1821 3312 1296 3313 1821 3313 1822 3313 1287 3314 1296 3314 1822 3314 1287 3315 1822 3315 1823 3315 1280 3316 1287 3316 1823 3316 1280 3317 1823 3317 1824 3317 1272 3318 1280 3318 1824 3318 1272 3319 1824 3319 1825 3319 1263 3320 1272 3320 1825 3320 1263 3321 1825 3321 1826 3321 1255 3322 1826 3322 1827 3322 1255 3323 1263 3323 1826 3323 1247 3324 1827 3324 1828 3324 1247 3325 1255 3325 1827 3325 1239 3326 1828 3326 1769 3326 1239 3327 1247 3327 1828 3327 1770 3328 1829 3328 1830 3328 1770 3329 1769 3329 1829 3329 1771 3330 1830 3330 1831 3330 1771 3331 1770 3331 1830 3331 1772 3332 1831 3332 1832 3332 1772 3333 1771 3333 1831 3333 1773 3334 1832 3334 1833 3334 1773 3335 1772 3335 1832 3335 1774 3336 1833 3336 1834 3336 1774 3337 1773 3337 1833 3337 1775 3338 1834 3338 1835 3338 1775 3339 1774 3339 1834 3339 1776 3340 1835 3340 1836 3340 1776 3341 1775 3341 1835 3341 1777 3342 1836 3342 1837 3342 1777 3343 1776 3343 1836 3343 1778 3344 1837 3344 1838 3344 1778 3345 1777 3345 1837 3345 1779 3346 1778 3346 1838 3346 1780 3347 1838 3347 1839 3347 1780 3348 1779 3348 1838 3348 1781 3349 1839 3349 1840 3349 1781 3350 1780 3350 1839 3350 1782 3351 1840 3351 1841 3351 1782 3352 1781 3352 1840 3352 1783 3353 1841 3353 1842 3353 1783 3354 1782 3354 1841 3354 1784 3355 1842 3355 1843 3355 1784 3356 1783 3356 1842 3356 1785 3357 1843 3357 1844 3357 1785 3358 1784 3358 1843 3358 1786 3359 1844 3359 1845 3359 1786 3360 1785 3360 1844 3360 1787 3361 1845 3361 1846 3361 1787 3362 1786 3362 1845 3362 1788 3363 1846 3363 1847 3363 1788 3364 1787 3364 1846 3364 1789 3365 1788 3365 1847 3365 1790 3366 1789 3366 1847 3366 1790 3367 1847 3367 1848 3367 1791 3368 1848 3368 1849 3368 1791 3369 1790 3369 1848 3369 1792 3370 1791 3370 1849 3370 1792 3371 1849 3371 1850 3371 1793 3372 1792 3372 1850 3372 1793 3373 1850 3373 1851 3373 1794 3374 1793 3374 1851 3374 1794 3375 1851 3375 1852 3375 1795 3376 1794 3376 1852 3376 1795 3377 1852 3377 1853 3377 1796 3378 1795 3378 1853 3378 1796 3379 1853 3379 1854 3379 1797 3380 1854 3380 1855 3380 1797 3381 1796 3381 1854 3381 1798 3382 1855 3382 1856 3382 1798 3383 1797 3383 1855 3383 1799 3384 1798 3384 1856 3384 1800 3385 1856 3385 1857 3385 1800 3386 1799 3386 1856 3386 1801 3387 1857 3387 1858 3387 1801 3388 1800 3388 1857 3388 1802 3389 1858 3389 1859 3389 1802 3390 1801 3390 1858 3390 1803 3391 1859 3391 1860 3391 1803 3392 1802 3392 1859 3392 1804 3393 1860 3393 1861 3393 1804 3394 1803 3394 1860 3394 1805 3395 1861 3395 1862 3395 1805 3396 1804 3396 1861 3396 1806 3397 1862 3397 1863 3397 1806 3398 1805 3398 1862 3398 1807 3399 1863 3399 1864 3399 1807 3400 1806 3400 1863 3400 1808 3401 1864 3401 1865 3401 1808 3402 1807 3402 1864 3402 1809 3403 1808 3403 1865 3403 1810 3404 1865 3404 1866 3404 1810 3405 1809 3405 1865 3405 1811 3406 1866 3406 1867 3406 1811 3407 1810 3407 1866 3407 1812 3408 1867 3408 1868 3408 1812 3409 1811 3409 1867 3409 1813 3410 1868 3410 1869 3410 1813 3411 1812 3411 1868 3411 1814 3412 1869 3412 1870 3412 1814 3413 1813 3413 1869 3413 1815 3414 1870 3414 1871 3414 1815 3415 1814 3415 1870 3415 1816 3416 1871 3416 1872 3416 1816 3417 1815 3417 1871 3417 1817 3418 1816 3418 1872 3418 1817 3419 1872 3419 1873 3419 1818 3420 1817 3420 1873 3420 1818 3421 1873 3421 1874 3421 1819 3422 1818 3422 1874 3422 1820 3423 1819 3423 1874 3423 1820 3424 1874 3424 1875 3424 1821 3425 1820 3425 1875 3425 1821 3426 1875 3426 1876 3426 1822 3427 1821 3427 1876 3427 1822 3428 1876 3428 1877 3428 1823 3429 1822 3429 1877 3429 1823 3430 1877 3430 1878 3430 1824 3431 1823 3431 1878 3431 1824 3432 1878 3432 1879 3432 1825 3433 1824 3433 1879 3433 1825 3434 1879 3434 1880 3434 1826 3435 1825 3435 1880 3435 1826 3436 1880 3436 1881 3436 1827 3437 1826 3437 1881 3437 1827 3438 1881 3438 1882 3438 1828 3439 1827 3439 1882 3439 1828 3440 1882 3440 1829 3440 1769 3441 1828 3441 1829 3441 1883 3442 400 3442 426 3442 241 3443 240 3443 1884 3443 1883 3444 426 3444 450 3444 1883 3445 450 3445 479 3445 1883 3446 479 3446 504 3446 1883 3447 504 3447 525 3447 1883 3448 525 3448 544 3448 1883 3449 544 3449 576 3449 1055 3450 241 3450 1884 3450 1883 3451 576 3451 599 3451 624 3452 1883 3452 599 3452 780 3453 1885 3453 741 3453 1043 3454 1055 3454 1884 3454 1043 3455 1884 3455 1885 3455 823 3456 1885 3456 780 3456 1026 3457 1043 3457 1885 3457 865 3458 1885 3458 823 3458 1886 3459 850 3459 1887 3459 904 3460 1885 3460 865 3460 1886 3461 571 3461 608 3461 1886 3462 608 3462 656 3462 1007 3463 1026 3463 1885 3463 1886 3464 656 3464 692 3464 1886 3465 692 3465 728 3465 1886 3466 728 3466 760 3466 966 3467 1007 3467 1885 3467 1886 3468 760 3468 803 3468 1886 3469 803 3469 828 3469 1886 3470 828 3470 850 3470 938 3471 1885 3471 904 3471 938 3472 966 3472 1885 3472 542 3473 571 3473 1886 3473 515 3474 542 3474 1886 3474 1888 3475 1883 3475 624 3475 1888 3476 624 3476 648 3476 1888 3477 648 3477 679 3477 1888 3478 679 3478 712 3478 1888 3479 712 3479 752 3479 791 3480 1888 3480 752 3480 491 3481 515 3481 1886 3481 832 3482 1888 3482 791 3482 471 3483 491 3483 1886 3483 874 3484 1888 3484 832 3484 455 3485 471 3485 1886 3485 1884 3486 455 3486 1886 3486 911 3487 1888 3487 874 3487 440 3488 455 3488 1884 3488 949 3489 1888 3489 911 3489 423 3490 440 3490 1884 3490 979 3491 1888 3491 949 3491 394 3492 423 3492 1884 3492 1010 3493 1888 3493 979 3493 373 3494 394 3494 1884 3494 1017 3495 1888 3495 1010 3495 350 3496 373 3496 1884 3496 324 3497 350 3497 1884 3497 1887 3498 850 3498 872 3498 1887 3499 872 3499 900 3499 1887 3500 900 3500 932 3500 1887 3501 932 3501 971 3501 1887 3502 971 3502 1009 3502 1887 3503 1009 3503 1041 3503 640 3504 1885 3504 1888 3504 1887 3505 1041 3505 233 3505 1887 3506 233 3506 235 3506 640 3507 1888 3507 1017 3507 1887 3508 235 3508 264 3508 641 3509 1885 3509 640 3509 1887 3510 264 3510 285 3510 1887 3511 285 3511 312 3511 1887 3512 312 3512 328 3512 1887 3513 328 3513 343 3513 295 3514 324 3514 1884 3514 670 3515 1885 3515 641 3515 270 3516 295 3516 1884 3516 703 3517 1885 3517 670 3517 240 3518 270 3518 1884 3518 1883 3519 1887 3519 343 3519 741 3520 1885 3520 703 3520 1883 3521 343 3521 358 3521 1883 3522 358 3522 378 3522 1883 3523 378 3523 400 3523 1858 3524 1860 3524 1859 3524 1858 3525 1861 3525 1860 3525 1858 3526 1862 3526 1861 3526 1841 3527 1838 3527 1835 3527 1841 3528 1839 3528 1838 3528 1841 3529 1840 3529 1839 3529 1875 3530 1877 3530 1876 3530 1841 3531 1830 3531 1875 3531 1841 3532 1835 3532 1830 3532 1879 3533 1878 3533 1877 3533 1873 3534 1875 3534 1874 3534 1855 3535 1857 3535 1856 3535 1880 3536 1877 3536 1875 3536 1880 3537 1879 3537 1877 3537 1844 3538 1842 3538 1841 3538 1844 3539 1843 3539 1842 3539 1882 3540 1881 3540 1880 3540 1853 3541 1855 3541 1854 3541 1870 3542 1872 3542 1871 3542 1870 3543 1873 3543 1872 3543 1870 3544 1875 3544 1873 3544 1852 3545 1855 3545 1853 3545 1852 3546 1858 3546 1857 3546 1852 3547 1857 3547 1855 3547 1847 3548 1845 3548 1844 3548 1847 3549 1846 3549 1845 3549 1847 3550 1868 3550 1858 3550 1847 3551 1841 3551 1875 3551 1830 3552 1829 3552 1882 3552 1847 3553 1844 3553 1841 3553 1847 3554 1858 3554 1852 3554 1830 3555 1882 3555 1880 3555 1830 3556 1880 3556 1875 3556 1847 3557 1875 3557 1868 3557 1868 3558 1870 3558 1869 3558 1848 3559 1852 3559 1851 3559 1868 3560 1875 3560 1870 3560 1848 3561 1847 3561 1852 3561 1849 3562 1851 3562 1850 3562 1849 3563 1848 3563 1851 3563 1866 3564 1868 3564 1867 3564 1833 3565 1832 3565 1831 3565 1865 3566 1868 3566 1866 3566 1864 3567 1868 3567 1865 3567 1835 3568 1831 3568 1830 3568 1835 3569 1834 3569 1833 3569 1835 3570 1833 3570 1831 3570 1862 3571 1868 3571 1864 3571 1862 3572 1864 3572 1863 3572 1837 3573 1836 3573 1835 3573 1838 3574 1837 3574 1835 3574 1858 3575 1868 3575 1862 3575 1722 3576 1399 3576 1384 3576 1714 3577 1516 3577 1504 3577 1714 3578 1713 3578 1516 3578 1721 3579 1399 3579 1722 3579 1721 3580 1416 3580 1399 3580 1715 3581 1714 3581 1504 3581 1715 3582 1504 3582 1478 3582 1720 3583 1416 3583 1721 3583 1716 3584 1715 3584 1478 3584 1719 3585 1416 3585 1720 3585 1719 3586 1433 3586 1416 3586 1717 3587 1716 3587 1478 3587 1717 3588 1478 3588 1455 3588 1718 3589 1433 3589 1719 3589 1718 3590 1717 3590 1455 3590 1718 3591 1455 3591 1433 3591 1375 3592 1759 3592 1758 3592 1354 3593 1759 3593 1375 3593 1354 3594 1760 3594 1759 3594 1398 3595 1757 3595 1756 3595 1398 3596 1758 3596 1757 3596 1398 3597 1375 3597 1758 3597 1334 3598 1761 3598 1760 3598 1334 3599 1762 3599 1761 3599 1334 3600 1760 3600 1354 3600 1425 3601 1756 3601 1755 3601 1425 3602 1398 3602 1756 3602 1320 3603 1762 3603 1334 3603 1320 3604 1763 3604 1762 3604 1436 3605 1425 3605 1755 3605 1436 3606 1755 3606 1754 3606 1305 3607 1763 3607 1320 3607 1305 3608 1764 3608 1763 3608 1466 3609 1436 3609 1754 3609 1466 3610 1753 3610 1752 3610 1466 3611 1754 3611 1753 3611 1293 3612 1764 3612 1305 3612 1293 3613 1765 3613 1764 3613 1293 3614 1766 3614 1765 3614 1494 3615 1466 3615 1752 3615 1494 3616 1752 3616 1751 3616 1285 3617 1766 3617 1293 3617 1285 3618 1767 3618 1766 3618 1523 3619 1494 3619 1751 3619 1523 3620 1751 3620 1750 3620 1277 3621 1767 3621 1285 3621 1277 3622 1768 3622 1767 3622 1551 3623 1523 3623 1750 3623 1551 3624 1750 3624 1749 3624 1269 3625 1688 3625 1687 3625 1269 3626 1768 3626 1277 3626 1269 3627 1687 3627 1768 3627 1578 3628 1551 3628 1749 3628 1578 3629 1748 3629 1747 3629 1578 3630 1749 3630 1748 3630 1261 3631 1689 3631 1688 3631 1261 3632 1688 3632 1269 3632 1606 3633 1578 3633 1747 3633 1606 3634 1747 3634 1746 3634 1252 3635 1690 3635 1689 3635 1252 3636 1689 3636 1261 3636 1634 3637 1606 3637 1746 3637 1634 3638 1746 3638 1745 3638 1244 3639 1691 3639 1690 3639 1244 3640 1692 3640 1691 3640 1244 3641 1690 3641 1252 3641 1662 3642 1634 3642 1745 3642 1662 3643 1744 3643 1743 3643 1662 3644 1745 3644 1744 3644 1236 3645 1693 3645 1692 3645 1236 3646 1692 3646 1244 3646 1682 3647 1743 3647 1742 3647 1682 3648 1662 3648 1743 3648 1229 3649 1694 3649 1693 3649 1229 3650 1693 3650 1236 3650 1093 3651 1742 3651 1741 3651 1093 3652 1682 3652 1742 3652 1221 3653 1695 3653 1694 3653 1221 3654 1694 3654 1229 3654 1696 3655 1695 3655 1221 3655 1095 3656 1741 3656 1740 3656 1095 3657 1093 3657 1741 3657 1739 3658 1095 3658 1740 3658 1212 3659 1696 3659 1221 3659 1697 3660 1696 3660 1212 3660 1111 3661 1095 3661 1739 3661 1198 3662 1697 3662 1212 3662 1738 3663 1111 3663 1739 3663 1127 3664 1111 3664 1738 3664 1698 3665 1697 3665 1198 3665 1180 3666 1698 3666 1198 3666 1737 3667 1127 3667 1738 3667 1145 3668 1127 3668 1737 3668 1699 3669 1698 3669 1180 3669 1736 3670 1145 3670 1737 3670 1700 3671 1699 3671 1180 3671 1700 3672 1180 3672 1158 3672 1735 3673 1145 3673 1736 3673 1735 3674 1162 3674 1145 3674 1701 3675 1700 3675 1158 3675 1701 3676 1158 3676 1140 3676 1734 3677 1162 3677 1735 3677 1734 3678 1178 3678 1162 3678 1702 3679 1140 3679 1116 3679 1702 3680 1701 3680 1140 3680 1733 3681 1178 3681 1734 3681 1733 3682 1194 3682 1178 3682 1703 3683 1702 3683 1116 3683 1732 3684 1194 3684 1733 3684 1704 3685 1116 3685 1076 3685 1704 3686 1703 3686 1116 3686 1731 3687 1194 3687 1732 3687 1731 3688 1202 3688 1194 3688 1705 3689 1076 3689 1075 3689 1705 3690 1704 3690 1076 3690 1730 3691 1202 3691 1731 3691 1730 3692 1207 3692 1202 3692 1706 3693 1075 3693 1657 3693 1706 3694 1705 3694 1075 3694 1729 3695 1299 3695 1207 3695 1729 3696 1207 3696 1730 3696 1707 3697 1706 3697 1657 3697 1728 3698 1299 3698 1729 3698 1708 3699 1657 3699 1629 3699 1708 3700 1707 3700 1657 3700 1727 3701 1338 3701 1299 3701 1727 3702 1299 3702 1728 3702 1709 3703 1629 3703 1602 3703 1709 3704 1708 3704 1629 3704 1726 3705 1353 3705 1338 3705 1726 3706 1338 3706 1727 3706 1710 3707 1602 3707 1573 3707 1710 3708 1709 3708 1602 3708 1725 3709 1368 3709 1353 3709 1725 3710 1353 3710 1726 3710 1711 3711 1573 3711 1545 3711 1711 3712 1710 3712 1573 3712 1724 3713 1368 3713 1725 3713 1712 3714 1711 3714 1545 3714 1723 3715 1368 3715 1724 3715 1723 3716 1384 3716 1368 3716 1713 3717 1712 3717 1545 3717 1713 3718 1545 3718 1516 3718 1722 3719 1384 3719 1723 3719 194 3720 1885 3720 1884 3720 194 3721 1889 3721 1885 3721 1890 3722 194 3722 1884 3722 1888 3723 1885 3723 186 3723 1885 3724 1889 3724 186 3724 1888 3725 186 3725 1891 3725 178 3726 1883 3726 1888 3726 178 3727 1892 3727 1883 3727 1891 3728 178 3728 1888 3728 143 3729 1887 3729 1883 3729 143 3730 1893 3730 1887 3730 1892 3731 143 3731 1883 3731 1886 3732 1887 3732 4 3732 1887 3733 1893 3733 4 3733 1886 3734 4 3734 1894 3734 1884 3735 1886 3735 202 3735 1886 3736 1894 3736 202 3736 1884 3737 202 3737 1890 3737 161 3738 124 3738 1893 3738 134 3739 161 3739 1893 3739 135 3740 134 3740 1893 3740 1893 3741 124 3741 123 3741 1893 3742 123 3742 121 3742 1893 3743 121 3743 5 3743 5 3744 4 3744 1893 3744 135 3745 1893 3745 143 3745 169 3746 168 3746 1892 3746 1892 3747 168 3747 167 3747 1892 3748 167 3748 159 3748 1892 3749 159 3749 158 3749 1892 3750 158 3750 157 3750 1892 3751 157 3751 144 3751 144 3752 143 3752 1892 3752 169 3753 1892 3753 178 3753 1891 3754 180 3754 179 3754 180 3755 1891 3755 181 3755 181 3756 1891 3756 182 3756 182 3757 1891 3757 183 3757 183 3758 1891 3758 184 3758 184 3759 1891 3759 185 3759 179 3760 178 3760 1891 3760 185 3761 1891 3761 186 3761 188 3762 187 3762 1889 3762 189 3763 188 3763 1889 3763 189 3764 1889 3764 190 3764 190 3765 1889 3765 191 3765 191 3766 1889 3766 192 3766 187 3767 186 3767 1889 3767 193 3768 1889 3768 194 3768 192 3769 1889 3769 193 3769 196 3770 195 3770 1890 3770 197 3771 196 3771 1890 3771 198 3772 197 3772 1890 3772 199 3773 198 3773 1890 3773 199 3774 1890 3774 200 3774 200 3775 1890 3775 201 3775 195 3776 194 3776 1890 3776 201 3777 1890 3777 202 3777 172 3778 171 3778 1894 3778 149 3779 172 3779 1894 3779 150 3780 149 3780 1894 3780 151 3781 150 3781 1894 3781 99 3782 151 3782 1894 3782 203 3783 202 3783 1894 3783 171 3784 203 3784 1894 3784 99 3785 1894 3785 4 3785

+
+
+
+ + + + 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 2.164935e-15 3.25 3.608225e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 1.132427e-15 1.7 1.887379e-16 -4.440892e-16 -3.552714e-16 3.2 -4.440892e-16 -3.552714e-16 3.2 -4.440892e-16 -3.552714e-16 3.2 -4.440892e-16 -3.552714e-16 3.2 -4.440892e-16 -3.552714e-16 3.2 -4.440892e-16 -3.552714e-16 3.2 6.661338e-16 1 1.110223e-16 6.661338e-16 1 1.110223e-16 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -1.387779e-16 -2.249299e-16 1 -3.064573e-16 -0.258819 0.9659258 -3.064573e-16 -0.258819 0.9659258 3.835898e-17 0.258819 0.9659258 3.835898e-17 0.258819 0.9659258 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -1.387779e-16 -4.52745e-16 1 -6.661338e-16 -1 -9.78384e-16 -6.661338e-16 -1 -9.78384e-16 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1.387779e-16 2.947193e-16 -1 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 1 -6.661338e-16 1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1 6.661338e-16 -1.387779e-16 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 -1.387779e-16 -1.110223e-16 1 + + + + + + + + + + 6.351387 8.269052 88 6 8.25 88 6 8.25 90 6.698654 8.325983 88 6.351387 8.269052 90 7.03773 8.420127 88 6.698654 8.325983 90 7.36464 8.55038 88 7.03773 8.420127 90 7.36464 8.55038 90 7.67555 8.715214 88 7.67555 8.715214 90 7.966816 8.912698 88 7.966816 8.912698 90 8.235023 9.140515 88 8.477027 9.395995 88 8.235023 9.140515 90 8.689989 9.676142 88 8.477027 9.395995 90 8.871414 9.977673 88 8.689989 9.676142 90 9.019174 10.29705 88 8.871414 9.977673 90 9.131537 10.63053 88 9.019174 10.29705 90 9.131537 10.63053 90 9.207186 10.97421 88 9.207186 10.97421 90 9.245234 11.32405 88 9.245234 11.32405 90 9.245234 11.67595 88 9.245234 11.67595 90 9.207186 12.02579 88 9.207186 12.02579 90 9.131537 12.36947 88 9.131537 12.36947 90 9.019174 12.70295 88 9.019174 12.70295 90 8.871414 13.02233 88 8.871414 13.02233 90 8.689989 13.32386 88 8.689989 13.32386 90 8.477027 13.60401 88 8.477027 13.60401 90 8.235023 13.85949 90 8.235023 13.85949 88 7.966816 14.0873 88 7.966816 14.0873 90 7.67555 14.28479 90 7.67555 14.28479 88 7.36464 14.44962 90 7.36464 14.44962 88 7.03773 14.57987 88 7.03773 14.57987 90 6.698654 14.67402 88 6.698654 14.67402 90 6.351387 14.73095 88 6.351387 14.73095 90 6 14.75 88 6 14.75 90 5.648613 14.73095 88 5.648613 14.73095 90 5.301346 14.67402 88 5.301346 14.67402 90 4.96227 14.57987 88 4.96227 14.57987 90 4.63536 14.44962 88 4.63536 14.44962 90 4.32445 14.28479 88 4.32445 14.28479 90 4.033184 14.0873 88 4.033184 14.0873 90 3.764977 13.85949 88 3.764977 13.85949 90 3.522973 13.60401 88 3.522973 13.60401 90 3.310011 13.32386 88 3.310011 13.32386 90 3.128586 13.02233 88 3.128586 13.02233 90 2.980826 12.70295 88 2.980826 12.70295 90 2.868463 12.36947 88 2.868463 12.36947 90 2.792814 12.02579 88 2.792814 12.02579 90 2.754766 11.67595 88 2.754766 11.67595 90 2.754766 11.32405 88 2.754766 11.32405 90 2.792814 10.97421 88 2.792814 10.97421 90 2.868463 10.63053 90 2.868463 10.63053 88 2.980826 10.29705 88 2.980826 10.29705 90 3.128586 9.977673 90 3.128586 9.977673 88 3.310011 9.676142 90 3.310011 9.676142 88 3.522973 9.395995 88 3.522973 9.395995 90 3.764977 9.140515 90 3.764977 9.140515 88 4.033184 8.912698 90 4.033184 8.912698 88 4.32445 8.715214 90 4.32445 8.715214 88 4.63536 8.55038 90 4.63536 8.55038 88 4.96227 8.420127 90 4.96227 8.420127 88 5.301346 8.325983 90 5.301346 8.325983 88 5.648613 8.269052 90 5.648613 8.269052 88 4.564643 10.58909 86 4.383204 10.97467 88 4.564643 10.58909 88 5.181019 10.01028 86 4.83627 10.26075 86 4.83627 10.26075 88 6.422773 9.853409 86 6 9.8 86 6 9.8 88 5.577227 9.853409 86 5.181019 10.01028 88 6.818981 10.01028 86 6.422773 9.853409 88 5.577227 9.853409 88 7.16373 10.26075 86 6.818981 10.01028 88 7.435357 10.58909 86 7.16373 10.26075 88 7.616796 10.97467 86 7.435357 10.58909 88 7.696645 11.39326 86 7.616796 10.97467 88 7.669888 11.81855 86 7.696645 11.39326 88 7.538206 12.22382 86 7.669888 11.81855 88 7.309873 12.58362 86 7.538206 12.22382 88 6.999235 12.87533 86 7.309873 12.58362 88 6.625812 13.08062 86 6.999235 12.87533 88 6.625812 13.08062 88 6.213066 13.18659 86 6.213066 13.18659 88 5.786934 13.18659 86 5.786934 13.18659 88 5.374188 13.08062 86 5.374188 13.08062 88 5.000765 12.87533 86 4.690127 12.58362 86 5.000765 12.87533 88 4.461794 12.22382 86 4.690127 12.58362 88 4.330112 11.81855 86 4.461794 12.22382 88 4.303355 11.39326 86 4.330112 11.81855 88 4.383204 10.97467 86 4.303355 11.39326 88 6.351387 -14.73095 88 6 -14.75 88 6 -14.75 90 6.698654 -14.67402 88 6.351387 -14.73095 90 7.03773 -14.57987 88 6.698654 -14.67402 90 7.36464 -14.44962 88 7.03773 -14.57987 90 7.36464 -14.44962 90 7.67555 -14.28479 88 7.67555 -14.28479 90 7.966816 -14.0873 88 7.966816 -14.0873 90 8.235023 -13.85949 88 8.477027 -13.60401 88 8.235023 -13.85949 90 8.689989 -13.32386 88 8.477027 -13.60401 90 8.871414 -13.02233 88 8.689989 -13.32386 90 9.019174 -12.70295 88 8.871414 -13.02233 90 9.131537 -12.36947 88 9.019174 -12.70295 90 9.131537 -12.36947 90 9.207186 -12.02579 88 9.207186 -12.02579 90 9.245234 -11.67595 88 9.245234 -11.67595 90 9.245234 -11.32405 88 9.245234 -11.32405 90 9.207186 -10.97421 88 9.207186 -10.97421 90 9.131537 -10.63053 88 9.131537 -10.63053 90 9.019174 -10.29705 88 9.019174 -10.29705 90 8.871414 -9.977673 88 8.871414 -9.977673 90 8.689989 -9.676142 88 8.689989 -9.676142 90 8.477027 -9.395995 88 8.477027 -9.395995 90 8.235023 -9.140515 90 8.235023 -9.140515 88 7.966816 -8.912698 88 7.966816 -8.912698 90 7.67555 -8.715214 90 7.67555 -8.715214 88 7.36464 -8.55038 90 7.36464 -8.55038 88 7.03773 -8.420127 88 7.03773 -8.420127 90 6.698654 -8.325983 88 6.698654 -8.325983 90 6.351387 -8.269052 88 6.351387 -8.269052 90 6 -8.25 88 6 -8.25 90 5.648613 -8.269052 88 5.648613 -8.269052 90 5.301346 -8.325983 88 5.301346 -8.325983 90 4.96227 -8.420127 88 4.96227 -8.420127 90 4.63536 -8.55038 88 4.63536 -8.55038 90 4.32445 -8.715214 88 4.32445 -8.715214 90 4.033184 -8.912698 88 4.033184 -8.912698 90 3.764977 -9.140515 88 3.764977 -9.140515 90 3.522973 -9.395995 88 3.522973 -9.395995 90 3.310011 -9.676142 88 3.310011 -9.676142 90 3.128586 -9.977673 88 3.128586 -9.977673 90 2.980826 -10.29705 88 2.980826 -10.29705 90 2.868463 -10.63053 88 2.868463 -10.63053 90 2.792814 -10.97421 88 2.792814 -10.97421 90 2.754766 -11.32405 88 2.754766 -11.32405 90 2.754766 -11.67595 88 2.754766 -11.67595 90 2.792814 -12.02579 88 2.792814 -12.02579 90 2.868463 -12.36947 90 2.868463 -12.36947 88 2.980826 -12.70295 88 2.980826 -12.70295 90 3.128586 -13.02233 90 3.128586 -13.02233 88 3.310011 -13.32386 90 3.310011 -13.32386 88 3.522973 -13.60401 88 3.522973 -13.60401 90 3.764977 -13.85949 90 3.764977 -13.85949 88 4.033184 -14.0873 90 4.033184 -14.0873 88 4.32445 -14.28479 90 4.32445 -14.28479 88 4.63536 -14.44962 90 4.63536 -14.44962 88 4.96227 -14.57987 90 4.96227 -14.57987 88 5.301346 -14.67402 90 5.301346 -14.67402 88 5.648613 -14.73095 90 5.648613 -14.73095 88 4.83627 -12.73925 86 4.564643 -12.41091 86 4.564643 -12.41091 88 4.383204 -12.02533 88 5.181019 -12.98972 86 4.83627 -12.73925 88 6.422773 -13.14659 86 6 -13.2 86 6 -13.2 88 5.577227 -13.14659 86 5.181019 -12.98972 88 6.818981 -12.98972 86 6.422773 -13.14659 88 5.577227 -13.14659 88 7.16373 -12.73925 86 6.818981 -12.98972 88 7.435357 -12.41091 86 7.16373 -12.73925 88 7.616796 -12.02533 86 7.435357 -12.41091 88 7.696645 -11.60674 86 7.616796 -12.02533 88 7.669888 -11.18145 86 7.696645 -11.60674 88 7.538206 -10.77618 86 7.669888 -11.18145 88 7.309873 -10.41638 86 7.538206 -10.77618 88 6.999235 -10.12467 86 7.309873 -10.41638 88 6.625812 -9.91938 86 6.999235 -10.12467 88 6.625812 -9.91938 88 6.213066 -9.813405 86 6.213066 -9.813405 88 5.786934 -9.813405 86 5.786934 -9.813405 88 5.374188 -9.91938 86 5.374188 -9.91938 88 5.000765 -10.12467 86 4.690127 -10.41638 86 5.000765 -10.12467 88 4.461794 -10.77618 86 4.690127 -10.41638 88 4.330112 -11.18145 86 4.461794 -10.77618 88 4.303355 -11.60674 86 4.330112 -11.18145 88 4.383204 -12.02533 86 4.303355 -11.60674 88 -5.648613 8.269052 88 -6 8.25 88 -6 8.25 90 -5.301346 8.325983 88 -5.648613 8.269052 90 -4.96227 8.420127 88 -5.301346 8.325983 90 -4.63536 8.55038 88 -4.96227 8.420127 90 -4.63536 8.55038 90 -4.32445 8.715214 88 -4.32445 8.715214 90 -4.033184 8.912698 88 -4.033184 8.912698 90 -3.764977 9.140515 88 -3.522973 9.395995 88 -3.764977 9.140515 90 -3.310011 9.676142 88 -3.522973 9.395995 90 -3.128586 9.977673 88 -3.310011 9.676142 90 -2.980826 10.29705 88 -3.128586 9.977673 90 -2.868463 10.63053 88 -2.980826 10.29705 90 -2.868463 10.63053 90 -2.792814 10.97421 88 -2.792814 10.97421 90 -2.754766 11.32405 88 -2.754766 11.32405 90 -2.754766 11.67595 88 -2.754766 11.67595 90 -2.792814 12.02579 88 -2.792814 12.02579 90 -2.868463 12.36947 88 -2.868463 12.36947 90 -2.980826 12.70295 88 -2.980826 12.70295 90 -3.128586 13.02233 88 -3.128586 13.02233 90 -3.310011 13.32386 88 -3.310011 13.32386 90 -3.522973 13.60401 88 -3.522973 13.60401 90 -3.764977 13.85949 90 -3.764977 13.85949 88 -4.033184 14.0873 88 -4.033184 14.0873 90 -4.32445 14.28479 90 -4.32445 14.28479 88 -4.63536 14.44962 90 -4.63536 14.44962 88 -4.96227 14.57987 88 -4.96227 14.57987 90 -5.301346 14.67402 88 -5.301346 14.67402 90 -5.648613 14.73095 88 -5.648613 14.73095 90 -6 14.75 88 -6 14.75 90 -6.351387 14.73095 88 -6.351387 14.73095 90 -6.698654 14.67402 88 -6.698654 14.67402 90 -7.03773 14.57987 88 -7.03773 14.57987 90 -7.36464 14.44962 88 -7.36464 14.44962 90 -7.67555 14.28479 88 -7.67555 14.28479 90 -7.966816 14.0873 88 -7.966816 14.0873 90 -8.235023 13.85949 88 -8.235023 13.85949 90 -8.477027 13.60401 88 -8.477027 13.60401 90 -8.689989 13.32386 88 -8.689989 13.32386 90 -8.871414 13.02233 88 -8.871414 13.02233 90 -9.019174 12.70295 88 -9.019174 12.70295 90 -9.131537 12.36947 88 -9.131537 12.36947 90 -9.207186 12.02579 88 -9.207186 12.02579 90 -9.245234 11.67595 88 -9.245234 11.67595 90 -9.245234 11.32405 88 -9.245234 11.32405 90 -9.207186 10.97421 88 -9.207186 10.97421 90 -9.131537 10.63053 90 -9.131537 10.63053 88 -9.019174 10.29705 88 -9.019174 10.29705 90 -8.871414 9.977673 90 -8.871414 9.977673 88 -8.689989 9.676142 90 -8.689989 9.676142 88 -8.477027 9.395995 88 -8.477027 9.395995 90 -8.235023 9.140515 90 -8.235023 9.140515 88 -7.966816 8.912698 90 -7.966816 8.912698 88 -7.67555 8.715214 90 -7.67555 8.715214 88 -7.36464 8.55038 90 -7.36464 8.55038 88 -7.03773 8.420127 90 -7.03773 8.420127 88 -6.698654 8.325983 90 -6.698654 8.325983 88 -6.351387 8.269052 90 -6.351387 8.269052 88 -7.435357 10.58909 86 -7.616796 10.97467 88 -7.435357 10.58909 88 -6.818981 10.01028 86 -7.16373 10.26075 86 -7.16373 10.26075 88 -5.577227 9.853409 86 -6 9.8 86 -6 9.8 88 -6.422773 9.853409 86 -6.818981 10.01028 88 -5.181019 10.01028 86 -5.577227 9.853409 88 -6.422773 9.853409 88 -4.83627 10.26075 86 -5.181019 10.01028 88 -4.564643 10.58909 86 -4.83627 10.26075 88 -4.383204 10.97467 86 -4.564643 10.58909 88 -4.303355 11.39326 86 -4.383204 10.97467 88 -4.330112 11.81855 86 -4.303355 11.39326 88 -4.461794 12.22382 86 -4.330112 11.81855 88 -4.690127 12.58362 86 -4.461794 12.22382 88 -5.000765 12.87533 86 -4.690127 12.58362 88 -5.374188 13.08062 86 -5.000765 12.87533 88 -5.374188 13.08062 88 -5.786934 13.18659 86 -5.786934 13.18659 88 -6.213066 13.18659 86 -6.213066 13.18659 88 -6.625812 13.08062 86 -6.625812 13.08062 88 -6.999235 12.87533 86 -7.309873 12.58362 86 -6.999235 12.87533 88 -7.538206 12.22382 86 -7.309873 12.58362 88 -7.669888 11.81855 86 -7.538206 12.22382 88 -7.696645 11.39326 86 -7.669888 11.81855 88 -7.616796 10.97467 86 -7.696645 11.39326 88 -5.648613 -14.73095 88 -6 -14.75 88 -6 -14.75 90 -5.301346 -14.67402 88 -5.648613 -14.73095 90 -4.96227 -14.57987 88 -5.301346 -14.67402 90 -4.63536 -14.44962 88 -4.96227 -14.57987 90 -4.63536 -14.44962 90 -4.32445 -14.28479 88 -4.32445 -14.28479 90 -4.033184 -14.0873 88 -4.033184 -14.0873 90 -3.764977 -13.85949 88 -3.522973 -13.60401 88 -3.764977 -13.85949 90 -3.310011 -13.32386 88 -3.522973 -13.60401 90 -3.128586 -13.02233 88 -3.310011 -13.32386 90 -2.980826 -12.70295 88 -3.128586 -13.02233 90 -2.868463 -12.36947 88 -2.980826 -12.70295 90 -2.868463 -12.36947 90 -2.792814 -12.02579 88 -2.792814 -12.02579 90 -2.754766 -11.67595 88 -2.754766 -11.67595 90 -2.754766 -11.32405 88 -2.754766 -11.32405 90 -2.792814 -10.97421 88 -2.792814 -10.97421 90 -2.868463 -10.63053 88 -2.868463 -10.63053 90 -2.980826 -10.29705 88 -2.980826 -10.29705 90 -3.128586 -9.977673 88 -3.128586 -9.977673 90 -3.310011 -9.676142 88 -3.310011 -9.676142 90 -3.522973 -9.395995 88 -3.522973 -9.395995 90 -3.764977 -9.140515 90 -3.764977 -9.140515 88 -4.033184 -8.912698 88 -4.033184 -8.912698 90 -4.32445 -8.715214 90 -4.32445 -8.715214 88 -4.63536 -8.55038 90 -4.63536 -8.55038 88 -4.96227 -8.420127 88 -4.96227 -8.420127 90 -5.301346 -8.325983 88 -5.301346 -8.325983 90 -5.648613 -8.269052 88 -5.648613 -8.269052 90 -6 -8.25 88 -6 -8.25 90 -6.351387 -8.269052 88 -6.351387 -8.269052 90 -6.698654 -8.325983 88 -6.698654 -8.325983 90 -7.03773 -8.420127 88 -7.03773 -8.420127 90 -7.36464 -8.55038 88 -7.36464 -8.55038 90 -7.67555 -8.715214 88 -7.67555 -8.715214 90 -7.966816 -8.912698 88 -7.966816 -8.912698 90 -8.235023 -9.140515 88 -8.235023 -9.140515 90 -8.477027 -9.395995 88 -8.477027 -9.395995 90 -8.689989 -9.676142 88 -8.689989 -9.676142 90 -8.871414 -9.977673 88 -8.871414 -9.977673 90 -9.019174 -10.29705 88 -9.019174 -10.29705 90 -9.131537 -10.63053 88 -9.131537 -10.63053 90 -9.207186 -10.97421 88 -9.207186 -10.97421 90 -9.245234 -11.32405 88 -9.245234 -11.32405 90 -9.245234 -11.67595 88 -9.245234 -11.67595 90 -9.207186 -12.02579 88 -9.207186 -12.02579 90 -9.131537 -12.36947 90 -9.131537 -12.36947 88 -9.019174 -12.70295 88 -9.019174 -12.70295 90 -8.871414 -13.02233 90 -8.871414 -13.02233 88 -8.689989 -13.32386 90 -8.689989 -13.32386 88 -8.477027 -13.60401 88 -8.477027 -13.60401 90 -8.235023 -13.85949 90 -8.235023 -13.85949 88 -7.966816 -14.0873 90 -7.966816 -14.0873 88 -7.67555 -14.28479 90 -7.67555 -14.28479 88 -7.36464 -14.44962 90 -7.36464 -14.44962 88 -7.03773 -14.57987 90 -7.03773 -14.57987 88 -6.698654 -14.67402 90 -6.698654 -14.67402 88 -6.351387 -14.73095 90 -6.351387 -14.73095 88 -7.16373 -12.73925 86 -7.435357 -12.41091 86 -7.435357 -12.41091 88 -7.616796 -12.02533 88 -6.818981 -12.98972 86 -7.16373 -12.73925 88 -5.577227 -13.14659 86 -6 -13.2 86 -6 -13.2 88 -6.422773 -13.14659 86 -6.818981 -12.98972 88 -5.181019 -12.98972 86 -5.577227 -13.14659 88 -6.422773 -13.14659 88 -4.83627 -12.73925 86 -5.181019 -12.98972 88 -4.564643 -12.41091 86 -4.83627 -12.73925 88 -4.383204 -12.02533 86 -4.564643 -12.41091 88 -4.303355 -11.60674 86 -4.383204 -12.02533 88 -4.330112 -11.18145 86 -4.303355 -11.60674 88 -4.461794 -10.77618 86 -4.330112 -11.18145 88 -4.690127 -10.41638 86 -4.461794 -10.77618 88 -5.000765 -10.12467 86 -4.690127 -10.41638 88 -5.374188 -9.91938 86 -5.000765 -10.12467 88 -5.374188 -9.91938 88 -5.786934 -9.813405 86 -5.786934 -9.813405 88 -6.213066 -9.813405 86 -6.213066 -9.813405 88 -6.625812 -9.91938 86 -6.625812 -9.91938 88 -6.999235 -10.12467 86 -7.309873 -10.41638 86 -6.999235 -10.12467 88 -7.538206 -10.77618 86 -7.309873 -10.41638 88 -7.669888 -11.18145 86 -7.538206 -10.77618 88 -7.696645 -11.60674 86 -7.669888 -11.18145 88 -7.616796 -12.02533 86 -7.696645 -11.60674 88 10 0.8282209 88.10904 -10 0.8282209 88.10904 -10 0.2788984 88.01218 10 0.2788984 88.01218 10 -0.2788984 88.01218 -10 -0.2788984 88.01218 10 -0.8282209 88.10904 -10 -0.8282209 88.10904 -10 15.5 86 -10 15.5 90 10 15.5 90 10 15.5 86 -10 7.88539 90 10 7.88539 90 -10 -7.88539 90 10 -7.88539 90 -10 -15.5 90 10 -15.5 90 -10 -15.5 86 10 -15.5 86 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 0 1 4 1 0 2 2 2 4 2 5 3 3 3 6 3 3 4 4 4 6 4 7 5 5 5 8 5 5 6 6 6 8 6 7 7 8 7 9 7 10 8 7 8 11 8 7 9 9 9 11 9 12 10 10 10 13 10 14 11 12 11 13 11 10 12 11 12 13 12 15 13 14 13 16 13 14 14 13 14 16 14 17 15 15 15 18 15 15 16 16 16 18 16 19 17 17 17 20 17 17 18 18 18 20 18 21 19 19 19 22 19 19 20 20 20 22 20 23 21 21 21 24 21 21 22 22 22 24 22 23 23 24 23 25 23 26 24 23 24 27 24 28 25 26 25 27 25 23 26 25 26 27 26 28 27 27 27 29 27 30 28 28 28 31 28 28 29 29 29 31 29 32 30 30 30 33 30 34 31 32 31 33 31 30 32 31 32 33 32 34 33 33 33 35 33 36 34 34 34 37 34 38 35 36 35 37 35 34 36 35 36 37 36 38 37 37 37 39 37 40 38 38 38 41 38 42 39 40 39 41 39 38 40 39 40 41 40 42 41 41 41 43 41 42 42 43 42 44 42 45 43 42 43 44 43 46 44 45 44 44 44 46 45 44 45 47 45 46 46 47 46 48 46 49 47 46 47 48 47 49 48 48 48 50 48 51 49 49 49 50 49 52 50 51 50 53 50 51 51 50 51 53 51 54 52 52 52 55 52 52 53 53 53 55 53 56 54 54 54 55 54 56 55 55 55 57 55 58 56 56 56 59 56 56 57 57 57 59 57 60 58 58 58 61 58 58 59 59 59 61 59 62 60 60 60 63 60 64 61 62 61 63 61 60 62 61 62 63 62 64 63 63 63 65 63 66 64 64 64 67 64 64 65 65 65 67 65 68 66 66 66 69 66 66 67 67 67 69 67 70 68 68 68 71 68 68 69 69 69 71 69 72 70 70 70 73 70 74 71 72 71 73 71 70 72 71 72 73 72 74 73 73 73 75 73 76 74 74 74 77 74 74 75 75 75 77 75 78 76 76 76 79 76 80 77 78 77 79 77 76 78 77 78 79 78 80 79 79 79 81 79 82 80 80 80 83 80 80 81 81 81 83 81 84 82 82 82 85 82 82 83 83 83 85 83 86 84 84 84 87 84 84 85 85 85 87 85 88 86 86 86 89 86 86 87 87 87 89 87 90 88 88 88 91 88 88 89 89 89 91 89 90 90 91 90 92 90 93 91 90 91 92 91 94 92 93 92 92 92 94 93 92 93 95 93 94 94 95 94 96 94 97 95 94 95 96 95 97 96 96 96 98 96 99 97 97 97 98 97 100 98 99 98 98 98 100 99 98 99 101 99 100 100 101 100 102 100 103 101 100 101 102 101 103 102 102 102 104 102 105 103 103 103 104 103 105 104 104 104 106 104 107 105 105 105 106 105 107 106 106 106 108 106 109 107 107 107 108 107 109 108 108 108 110 108 111 109 109 109 110 109 111 110 110 110 112 110 113 111 111 111 112 111 113 112 112 112 114 112 115 113 113 113 114 113 115 114 114 114 2 114 1 115 115 115 2 115 116 116 117 116 118 116 119 117 120 117 121 117 120 118 118 118 121 118 122 119 123 119 124 119 125 120 119 120 126 120 119 121 121 121 126 121 127 122 122 122 128 122 122 123 124 123 128 123 123 124 125 124 129 124 125 125 126 125 129 125 123 126 129 126 124 126 130 127 127 127 131 127 127 128 128 128 131 128 132 129 130 129 133 129 130 130 131 130 133 130 134 131 132 131 135 131 132 132 133 132 135 132 136 133 134 133 137 133 134 134 135 134 137 134 138 135 136 135 139 135 136 136 137 136 139 136 140 137 138 137 141 137 138 138 139 138 141 138 142 139 140 139 143 139 140 140 141 140 143 140 144 141 142 141 145 141 142 142 143 142 145 142 146 143 144 143 147 143 144 144 145 144 147 144 146 145 147 145 148 145 149 146 146 146 148 146 149 147 148 147 150 147 151 148 149 148 150 148 151 149 150 149 152 149 153 150 151 150 152 150 153 151 152 151 154 151 155 152 153 152 154 152 156 153 155 153 157 153 155 154 154 154 157 154 158 155 156 155 159 155 156 156 157 156 159 156 160 157 158 157 161 157 158 158 159 158 161 158 162 159 160 159 163 159 160 160 161 160 163 160 164 161 162 161 165 161 162 162 163 162 165 162 116 163 164 163 117 163 164 164 165 164 117 164 120 165 116 165 118 165 166 166 167 166 168 166 169 167 166 167 170 167 166 168 168 168 170 168 171 169 169 169 172 169 169 170 170 170 172 170 173 171 171 171 174 171 171 172 172 172 174 172 173 173 174 173 175 173 176 174 173 174 177 174 173 175 175 175 177 175 178 176 176 176 179 176 180 177 178 177 179 177 176 178 177 178 179 178 181 179 180 179 182 179 180 180 179 180 182 180 183 181 181 181 184 181 181 182 182 182 184 182 185 183 183 183 186 183 183 184 184 184 186 184 187 185 185 185 188 185 185 186 186 186 188 186 189 187 187 187 190 187 187 188 188 188 190 188 189 189 190 189 191 189 192 190 189 190 193 190 194 191 192 191 193 191 189 192 191 192 193 192 194 193 193 193 195 193 196 194 194 194 197 194 194 195 195 195 197 195 198 196 196 196 199 196 200 197 198 197 199 197 196 198 197 198 199 198 200 199 199 199 201 199 202 200 200 200 203 200 204 201 202 201 203 201 200 202 201 202 203 202 204 203 203 203 205 203 206 204 204 204 207 204 208 205 206 205 207 205 204 206 205 206 207 206 208 207 207 207 209 207 208 208 209 208 210 208 211 209 208 209 210 209 212 210 211 210 210 210 212 211 210 211 213 211 212 212 213 212 214 212 215 213 212 213 214 213 215 214 214 214 216 214 217 215 215 215 216 215 218 216 217 216 219 216 217 217 216 217 219 217 220 218 218 218 221 218 218 219 219 219 221 219 222 220 220 220 221 220 222 221 221 221 223 221 224 222 222 222 225 222 222 223 223 223 225 223 226 224 224 224 227 224 224 225 225 225 227 225 228 226 226 226 229 226 230 227 228 227 229 227 226 228 227 228 229 228 230 229 229 229 231 229 232 230 230 230 233 230 230 231 231 231 233 231 234 232 232 232 235 232 232 233 233 233 235 233 236 234 234 234 237 234 234 235 235 235 237 235 238 236 236 236 239 236 240 237 238 237 239 237 236 238 237 238 239 238 240 239 239 239 241 239 242 240 240 240 243 240 240 241 241 241 243 241 244 242 242 242 245 242 246 243 244 243 245 243 242 244 243 244 245 244 246 245 245 245 247 245 248 246 246 246 249 246 246 247 247 247 249 247 250 248 248 248 251 248 248 249 249 249 251 249 252 250 250 250 253 250 250 251 251 251 253 251 254 252 252 252 255 252 252 253 253 253 255 253 256 254 254 254 257 254 254 255 255 255 257 255 256 256 257 256 258 256 259 257 256 257 258 257 260 258 259 258 258 258 260 259 258 259 261 259 260 260 261 260 262 260 263 261 260 261 262 261 263 262 262 262 264 262 265 263 263 263 264 263 266 264 265 264 264 264 266 265 264 265 267 265 266 266 267 266 268 266 269 267 266 267 268 267 269 268 268 268 270 268 271 269 269 269 270 269 271 270 270 270 272 270 273 271 271 271 272 271 273 272 272 272 274 272 275 273 273 273 274 273 275 274 274 274 276 274 277 275 275 275 276 275 277 276 276 276 278 276 279 277 277 277 278 277 279 278 278 278 280 278 281 279 279 279 280 279 281 280 280 280 168 280 167 281 281 281 168 281 282 282 283 282 284 282 283 283 285 283 284 283 286 284 282 284 287 284 282 285 284 285 287 285 288 286 289 286 290 286 291 287 286 287 292 287 286 288 287 288 292 288 293 289 288 289 294 289 288 290 290 290 294 290 289 291 291 291 295 291 291 292 292 292 295 292 289 293 295 293 290 293 296 294 293 294 297 294 293 295 294 295 297 295 298 296 296 296 299 296 296 297 297 297 299 297 300 298 298 298 301 298 298 299 299 299 301 299 302 300 300 300 303 300 300 301 301 301 303 301 304 302 302 302 305 302 302 303 303 303 305 303 306 304 304 304 307 304 304 305 305 305 307 305 308 306 306 306 309 306 306 307 307 307 309 307 310 308 308 308 311 308 308 309 309 309 311 309 312 310 310 310 313 310 310 311 311 311 313 311 312 312 313 312 314 312 315 313 312 313 314 313 315 314 314 314 316 314 317 315 315 315 316 315 317 316 316 316 318 316 319 317 317 317 318 317 319 318 318 318 320 318 321 319 319 319 320 319 322 320 321 320 323 320 321 321 320 321 323 321 324 322 322 322 325 322 322 323 323 323 325 323 326 324 324 324 327 324 324 325 325 325 327 325 328 326 326 326 329 326 326 327 327 327 329 327 330 328 328 328 331 328 328 329 329 329 331 329 283 330 330 330 285 330 330 331 331 331 285 331 332 332 333 332 334 332 335 333 332 333 336 333 332 334 334 334 336 334 337 335 335 335 338 335 335 336 336 336 338 336 339 337 337 337 340 337 337 338 338 338 340 338 339 339 340 339 341 339 342 340 339 340 343 340 339 341 341 341 343 341 344 342 342 342 345 342 346 343 344 343 345 343 342 344 343 344 345 344 347 345 346 345 348 345 346 346 345 346 348 346 349 347 347 347 350 347 347 348 348 348 350 348 351 349 349 349 352 349 349 350 350 350 352 350 353 351 351 351 354 351 351 352 352 352 354 352 355 353 353 353 356 353 353 354 354 354 356 354 355 355 356 355 357 355 358 356 355 356 359 356 360 357 358 357 359 357 355 358 357 358 359 358 360 359 359 359 361 359 362 360 360 360 363 360 360 361 361 361 363 361 364 362 362 362 365 362 366 363 364 363 365 363 362 364 363 364 365 364 366 365 365 365 367 365 368 366 366 366 369 366 370 367 368 367 369 367 366 368 367 368 369 368 370 369 369 369 371 369 372 370 370 370 373 370 374 371 372 371 373 371 370 372 371 372 373 372 374 373 373 373 375 373 374 374 375 374 376 374 377 375 374 375 376 375 378 376 377 376 376 376 378 377 376 377 379 377 378 378 379 378 380 378 381 379 378 379 380 379 381 380 380 380 382 380 383 381 381 381 382 381 384 382 383 382 385 382 383 383 382 383 385 383 386 384 384 384 387 384 384 385 385 385 387 385 388 386 386 386 387 386 388 387 387 387 389 387 390 388 388 388 391 388 388 389 389 389 391 389 392 390 390 390 393 390 390 391 391 391 393 391 394 392 392 392 395 392 396 393 394 393 395 393 392 394 393 394 395 394 396 395 395 395 397 395 398 396 396 396 399 396 396 397 397 397 399 397 400 398 398 398 401 398 398 399 399 399 401 399 402 400 400 400 403 400 400 401 401 401 403 401 404 402 402 402 405 402 406 403 404 403 405 403 402 404 403 404 405 404 406 405 405 405 407 405 408 406 406 406 409 406 406 407 407 407 409 407 410 408 408 408 411 408 412 409 410 409 411 409 408 410 409 410 411 410 412 411 411 411 413 411 414 412 412 412 415 412 412 413 413 413 415 413 416 414 414 414 417 414 414 415 415 415 417 415 418 416 416 416 419 416 416 417 417 417 419 417 420 418 418 418 421 418 418 419 419 419 421 419 422 420 420 420 423 420 420 421 421 421 423 421 422 422 423 422 424 422 425 423 422 423 424 423 426 424 425 424 424 424 426 425 424 425 427 425 426 426 427 426 428 426 429 427 426 427 428 427 429 428 428 428 430 428 431 429 429 429 430 429 432 430 431 430 430 430 432 431 430 431 433 431 432 432 433 432 434 432 435 433 432 433 434 433 435 434 434 434 436 434 437 435 435 435 436 435 437 436 436 436 438 436 439 437 437 437 438 437 439 438 438 438 440 438 441 439 439 439 440 439 441 440 440 440 442 440 443 441 441 441 442 441 443 442 442 442 444 442 445 443 443 443 444 443 445 444 444 444 446 444 447 445 445 445 446 445 447 446 446 446 334 446 333 447 447 447 334 447 448 448 449 448 450 448 451 449 452 449 453 449 452 450 450 450 453 450 454 451 455 451 456 451 457 452 451 452 458 452 451 453 453 453 458 453 459 454 454 454 460 454 454 455 456 455 460 455 455 456 457 456 461 456 457 457 458 457 461 457 455 458 461 458 456 458 462 459 459 459 463 459 459 460 460 460 463 460 464 461 462 461 465 461 462 462 463 462 465 462 466 463 464 463 467 463 464 464 465 464 467 464 468 465 466 465 469 465 466 466 467 466 469 466 470 467 468 467 471 467 468 468 469 468 471 468 472 469 470 469 473 469 470 470 471 470 473 470 474 471 472 471 475 471 472 472 473 472 475 472 476 473 474 473 477 473 474 474 475 474 477 474 478 475 476 475 479 475 476 476 477 476 479 476 478 477 479 477 480 477 481 478 478 478 480 478 481 479 480 479 482 479 483 480 481 480 482 480 483 481 482 481 484 481 485 482 483 482 484 482 485 483 484 483 486 483 487 484 485 484 486 484 488 485 487 485 489 485 487 486 486 486 489 486 490 487 488 487 491 487 488 488 489 488 491 488 492 489 490 489 493 489 490 490 491 490 493 490 494 491 492 491 495 491 492 492 493 492 495 492 496 493 494 493 497 493 494 494 495 494 497 494 448 495 496 495 449 495 496 496 497 496 449 496 452 497 448 497 450 497 498 498 499 498 500 498 501 499 498 499 502 499 498 500 500 500 502 500 503 501 501 501 504 501 501 502 502 502 504 502 505 503 503 503 506 503 503 504 504 504 506 504 505 505 506 505 507 505 508 506 505 506 509 506 505 507 507 507 509 507 510 508 508 508 511 508 512 509 510 509 511 509 508 510 509 510 511 510 513 511 512 511 514 511 512 512 511 512 514 512 515 513 513 513 516 513 513 514 514 514 516 514 517 515 515 515 518 515 515 516 516 516 518 516 519 517 517 517 520 517 517 518 518 518 520 518 521 519 519 519 522 519 519 520 520 520 522 520 521 521 522 521 523 521 524 522 521 522 525 522 526 523 524 523 525 523 521 524 523 524 525 524 526 525 525 525 527 525 528 526 526 526 529 526 526 527 527 527 529 527 530 528 528 528 531 528 532 529 530 529 531 529 528 530 529 530 531 530 532 531 531 531 533 531 534 532 532 532 535 532 536 533 534 533 535 533 532 534 533 534 535 534 536 535 535 535 537 535 538 536 536 536 539 536 540 537 538 537 539 537 536 538 537 538 539 538 540 539 539 539 541 539 540 540 541 540 542 540 543 541 540 541 542 541 544 542 543 542 542 542 544 543 542 543 545 543 544 544 545 544 546 544 547 545 544 545 546 545 547 546 546 546 548 546 549 547 547 547 548 547 550 548 549 548 551 548 549 549 548 549 551 549 552 550 550 550 553 550 550 551 551 551 553 551 554 552 552 552 553 552 554 553 553 553 555 553 556 554 554 554 557 554 554 555 555 555 557 555 558 556 556 556 559 556 556 557 557 557 559 557 560 558 558 558 561 558 562 559 560 559 561 559 558 560 559 560 561 560 562 561 561 561 563 561 564 562 562 562 565 562 562 563 563 563 565 563 566 564 564 564 567 564 564 565 565 565 567 565 568 566 566 566 569 566 566 567 567 567 569 567 570 568 568 568 571 568 572 569 570 569 571 569 568 570 569 570 571 570 572 571 571 571 573 571 574 572 572 572 575 572 572 573 573 573 575 573 576 574 574 574 577 574 578 575 576 575 577 575 574 576 575 576 577 576 578 577 577 577 579 577 580 578 578 578 581 578 578 579 579 579 581 579 582 580 580 580 583 580 580 581 581 581 583 581 584 582 582 582 585 582 582 583 583 583 585 583 586 584 584 584 587 584 584 585 585 585 587 585 588 586 586 586 589 586 586 587 587 587 589 587 588 588 589 588 590 588 591 589 588 589 590 589 592 590 591 590 590 590 592 591 590 591 593 591 592 592 593 592 594 592 595 593 592 593 594 593 595 594 594 594 596 594 597 595 595 595 596 595 598 596 597 596 596 596 598 597 596 597 599 597 598 598 599 598 600 598 601 599 598 599 600 599 601 600 600 600 602 600 603 601 601 601 602 601 603 602 602 602 604 602 605 603 603 603 604 603 605 604 604 604 606 604 607 605 605 605 606 605 607 606 606 606 608 606 609 607 607 607 608 607 609 608 608 608 610 608 611 609 609 609 610 609 611 610 610 610 612 610 613 611 611 611 612 611 613 612 612 612 500 612 499 613 613 613 500 613 614 614 615 614 616 614 615 615 617 615 616 615 618 616 614 616 619 616 614 617 616 617 619 617 620 618 621 618 622 618 623 619 618 619 624 619 618 620 619 620 624 620 625 621 620 621 626 621 620 622 622 622 626 622 621 623 623 623 627 623 623 624 624 624 627 624 621 625 627 625 622 625 628 626 625 626 629 626 625 627 626 627 629 627 630 628 628 628 631 628 628 629 629 629 631 629 632 630 630 630 633 630 630 631 631 631 633 631 634 632 632 632 635 632 632 633 633 633 635 633 636 634 634 634 637 634 634 635 635 635 637 635 638 636 636 636 639 636 636 637 637 637 639 637 640 638 638 638 641 638 638 639 639 639 641 639 642 640 640 640 643 640 640 641 641 641 643 641 644 642 642 642 645 642 642 643 643 643 645 643 644 644 645 644 646 644 647 645 644 645 646 645 647 646 646 646 648 646 649 647 647 647 648 647 649 648 648 648 650 648 651 649 649 649 650 649 651 650 650 650 652 650 653 651 651 651 652 651 654 652 653 652 655 652 653 653 652 653 655 653 656 654 654 654 657 654 654 655 655 655 657 655 658 656 656 656 659 656 656 657 657 657 659 657 660 658 658 658 661 658 658 659 659 659 661 659 662 660 660 660 663 660 660 661 661 661 663 661 615 662 662 662 617 662 662 663 663 663 617 663 664 664 665 664 666 664 667 665 664 665 666 665 668 666 667 666 669 666 667 667 666 667 669 667 670 668 668 668 671 668 668 669 669 669 671 669 672 670 673 670 674 670 672 671 674 671 675 671 676 672 434 672 433 672 434 673 676 673 436 673 676 674 433 674 430 674 436 675 676 675 438 675 676 676 430 676 428 676 438 677 676 677 440 677 676 678 428 678 427 678 440 679 676 679 442 679 676 680 427 680 424 680 442 681 676 681 444 681 676 682 424 682 423 682 444 683 676 683 446 683 676 684 423 684 421 684 446 685 676 685 334 685 676 686 421 686 419 686 411 687 409 687 673 687 413 688 411 688 673 688 415 689 413 689 673 689 417 690 415 690 673 690 419 691 417 691 673 691 676 692 419 692 673 692 409 693 407 693 673 693 673 694 407 694 405 694 673 695 405 695 403 695 673 696 403 696 401 696 673 697 401 697 399 697 673 698 399 698 397 698 673 699 397 699 395 699 673 700 395 700 393 700 673 701 393 701 391 701 673 702 391 702 389 702 348 703 345 703 102 703 350 704 348 704 102 704 350 705 102 705 101 705 102 706 345 706 104 706 352 707 350 707 98 707 354 708 352 708 98 708 350 709 101 709 98 709 345 710 343 710 106 710 104 711 345 711 106 711 354 712 98 712 96 712 106 713 343 713 108 713 343 714 341 714 108 714 354 715 96 715 95 715 356 716 354 716 95 716 357 717 356 717 95 717 108 718 341 718 110 718 341 719 340 719 110 719 357 720 95 720 92 720 110 721 340 721 112 721 340 722 338 722 112 722 357 723 92 723 91 723 359 724 357 724 91 724 359 725 91 725 89 725 361 726 359 726 89 726 363 727 361 727 89 727 363 728 89 728 87 728 365 729 363 729 87 729 365 730 87 730 85 730 365 731 85 731 83 731 367 732 365 732 83 732 367 733 83 733 81 733 369 734 367 734 81 734 371 735 369 735 81 735 371 736 81 736 79 736 371 737 79 737 77 737 373 738 371 738 77 738 375 739 373 739 75 739 376 740 375 740 75 740 373 741 77 741 75 741 376 742 75 742 73 742 379 743 376 743 73 743 4 744 2 744 677 744 6 745 4 745 677 745 8 746 6 746 677 746 9 747 8 747 677 747 11 748 9 748 677 748 13 749 11 749 677 749 16 750 13 750 677 750 18 751 16 751 677 751 379 752 73 752 71 752 18 753 677 753 20 753 379 754 71 754 69 754 380 755 379 755 69 755 20 756 677 756 22 756 380 757 69 757 67 757 382 758 380 758 67 758 22 759 677 759 24 759 382 760 67 760 65 760 385 761 382 761 65 761 24 762 677 762 25 762 385 763 65 763 63 763 387 764 385 764 63 764 25 765 677 765 27 765 27 766 677 766 29 766 29 767 677 767 31 767 33 768 31 768 674 768 35 769 33 769 674 769 37 770 35 770 674 770 39 771 37 771 674 771 41 772 39 772 674 772 43 773 41 773 674 773 44 774 43 774 674 774 47 775 44 775 674 775 48 776 47 776 674 776 50 777 48 777 674 777 53 778 50 778 674 778 55 779 53 779 674 779 57 780 55 780 674 780 59 781 57 781 674 781 61 782 59 782 674 782 31 783 677 783 674 783 334 784 676 784 677 784 336 785 334 785 677 785 338 786 336 786 677 786 2 787 338 787 677 787 114 788 338 788 2 788 112 789 338 789 114 789 389 790 674 790 673 790 387 791 674 791 389 791 61 792 674 792 387 792 63 793 61 793 387 793 676 794 665 794 677 794 665 795 664 795 677 795 671 796 678 796 670 796 678 797 679 797 670 797 680 798 600 798 599 798 600 799 680 799 602 799 680 800 599 800 596 800 602 801 680 801 604 801 680 802 596 802 594 802 604 803 680 803 606 803 680 804 594 804 593 804 606 805 680 805 608 805 680 806 593 806 590 806 608 807 680 807 610 807 680 808 590 808 589 808 610 809 680 809 612 809 680 810 589 810 587 810 612 811 680 811 500 811 500 812 680 812 502 812 577 813 575 813 678 813 579 814 577 814 678 814 581 815 579 815 678 815 583 816 581 816 678 816 585 817 583 817 678 817 587 818 585 818 678 818 680 819 587 819 678 819 678 820 575 820 573 820 678 821 573 821 571 821 678 822 571 822 569 822 678 823 569 823 567 823 678 824 567 824 565 824 678 825 565 825 563 825 678 826 563 826 561 826 678 827 561 827 559 827 678 828 559 828 557 828 514 829 511 829 268 829 514 830 268 830 267 830 516 831 514 831 267 831 268 832 511 832 270 832 516 833 267 833 264 833 518 834 516 834 264 834 520 835 518 835 264 835 509 836 507 836 272 836 511 837 509 837 272 837 270 838 511 838 272 838 520 839 264 839 262 839 272 840 507 840 274 840 520 841 262 841 261 841 522 842 520 842 261 842 274 843 507 843 276 843 507 844 506 844 276 844 522 845 261 845 258 845 523 846 522 846 258 846 276 847 506 847 278 847 506 848 504 848 278 848 523 849 258 849 257 849 525 850 523 850 257 850 525 851 257 851 255 851 527 852 525 852 255 852 529 853 527 853 255 853 529 854 255 854 253 854 529 855 253 855 251 855 531 856 529 856 251 856 533 857 531 857 251 857 533 858 251 858 249 858 535 859 533 859 249 859 535 860 249 860 247 860 537 861 535 861 245 861 535 862 247 862 245 862 539 863 537 863 245 863 539 864 245 864 243 864 541 865 539 865 241 865 542 866 541 866 241 866 539 867 243 867 241 867 170 868 168 868 681 868 172 869 170 869 681 869 174 870 172 870 681 870 175 871 174 871 681 871 177 872 175 872 681 872 179 873 177 873 681 873 182 874 179 874 681 874 168 875 280 875 681 875 542 876 241 876 239 876 182 877 681 877 184 877 542 878 239 878 237 878 545 879 542 879 237 879 184 880 681 880 186 880 545 881 237 881 235 881 546 882 545 882 235 882 186 883 681 883 188 883 546 884 235 884 233 884 548 885 546 885 233 885 188 886 681 886 190 886 548 887 233 887 231 887 551 888 548 888 231 888 553 889 551 889 231 889 190 890 681 890 191 890 553 891 231 891 229 891 191 892 681 892 193 892 193 893 681 893 195 893 197 894 195 894 679 894 199 895 197 895 679 895 201 896 199 896 679 896 203 897 201 897 679 897 205 898 203 898 679 898 207 899 205 899 679 899 209 900 207 900 679 900 210 901 209 901 679 901 213 902 210 902 679 902 214 903 213 903 679 903 216 904 214 904 679 904 195 905 681 905 679 905 219 906 216 906 679 906 221 907 219 907 679 907 223 908 221 908 679 908 225 909 223 909 679 909 280 910 680 910 681 910 278 911 680 911 280 911 502 912 680 912 278 912 504 913 502 913 278 913 225 914 679 914 678 914 227 915 225 915 678 915 229 916 227 916 678 916 557 917 229 917 678 917 555 918 229 918 557 918 553 919 229 919 555 919 680 920 682 920 683 920 680 921 683 921 681 921 488 922 672 922 487 922 672 923 488 923 490 923 487 924 672 924 485 924 672 925 490 925 492 925 485 926 672 926 483 926 672 927 492 927 494 927 483 928 672 928 481 928 672 929 494 929 496 929 481 930 672 930 478 930 156 931 474 931 155 931 474 932 476 932 155 932 476 933 478 933 155 933 474 934 156 934 158 934 472 935 474 935 158 935 155 936 478 936 153 936 468 937 470 937 160 937 470 938 472 938 160 938 472 939 158 939 160 939 468 940 160 940 162 940 466 941 468 941 162 941 466 942 162 942 164 942 462 943 464 943 116 943 464 944 466 944 116 944 466 945 164 945 116 945 144 946 146 946 675 946 146 947 149 947 675 947 149 948 151 948 675 948 151 949 153 949 675 949 478 950 672 950 675 950 153 951 478 951 675 951 459 952 462 952 120 952 462 953 116 953 120 953 144 954 675 954 142 954 459 955 120 955 119 955 142 956 675 956 140 956 140 957 675 957 138 957 138 958 675 958 136 958 136 959 675 959 134 959 448 960 452 960 654 960 654 961 452 961 653 961 452 962 451 962 653 962 448 963 654 963 656 963 672 964 496 964 656 964 496 965 448 965 656 965 653 966 451 966 651 966 451 967 457 967 651 967 651 968 457 968 649 968 457 969 455 969 649 969 649 970 455 970 647 970 455 971 454 971 647 971 647 972 454 972 644 972 454 973 459 973 644 973 672 974 656 974 682 974 656 975 658 975 682 975 658 976 660 976 682 976 660 977 662 977 682 977 662 978 615 978 682 978 682 979 615 979 614 979 682 980 614 980 618 980 682 981 618 981 623 981 682 982 623 982 621 982 682 983 621 983 620 983 640 984 642 984 322 984 322 985 642 985 321 985 640 986 322 986 324 986 638 987 640 987 324 987 119 988 125 988 319 988 644 989 459 989 319 989 321 990 642 990 319 990 642 991 644 991 319 991 459 992 119 992 319 992 638 993 324 993 326 993 636 994 638 994 326 994 125 995 123 995 317 995 319 996 125 996 317 996 636 997 326 997 328 997 632 998 634 998 328 998 634 999 636 999 328 999 123 1000 122 1000 315 1000 317 1001 123 1001 315 1001 632 1002 328 1002 330 1002 630 1003 632 1003 330 1003 122 1004 127 1004 312 1004 315 1005 122 1005 312 1005 630 1006 330 1006 283 1006 628 1007 630 1007 283 1007 127 1008 130 1008 310 1008 312 1009 127 1009 310 1009 628 1010 283 1010 282 1010 130 1011 132 1011 308 1011 310 1012 130 1012 308 1012 620 1013 625 1013 286 1013 625 1014 628 1014 286 1014 628 1015 282 1015 286 1015 620 1016 286 1016 291 1016 289 1017 288 1017 683 1017 288 1018 293 1018 683 1018 293 1019 296 1019 683 1019 296 1020 298 1020 683 1020 298 1021 300 1021 683 1021 300 1022 302 1022 683 1022 302 1023 304 1023 683 1023 304 1024 306 1024 683 1024 682 1025 620 1025 683 1025 291 1026 289 1026 683 1026 620 1027 291 1027 683 1027 134 1028 675 1028 683 1028 132 1029 134 1029 683 1029 306 1030 132 1030 683 1030 308 1031 132 1031 306 1031 677 1032 675 1032 674 1032 664 1033 675 1033 677 1033 683 1034 668 1034 670 1034 683 1035 670 1035 679 1035 681 1036 683 1036 679 1036 683 1037 675 1037 667 1037 683 1038 667 1038 668 1038 667 1039 675 1039 664 1039 673 1040 672 1040 676 1040 676 1041 672 1041 665 1041 678 1042 671 1042 682 1042 671 1043 669 1043 682 1043 678 1044 682 1044 680 1044 666 1045 672 1045 682 1045 669 1046 666 1046 682 1046 665 1047 672 1047 666 1047 584 1048 586 1048 663 1048 586 1049 588 1049 663 1049 652 1050 650 1050 560 1050 588 1051 617 1051 663 1051 499 1052 498 1052 622 1052 637 1053 635 1053 524 1053 627 1054 613 1054 622 1054 635 1055 521 1055 524 1055 613 1056 499 1056 622 1056 560 1057 650 1057 558 1057 584 1058 663 1058 661 1058 580 1059 582 1059 661 1059 637 1060 524 1060 526 1060 582 1061 584 1061 661 1061 558 1062 650 1062 556 1062 498 1063 501 1063 626 1063 501 1064 503 1064 626 1064 622 1065 498 1065 626 1065 650 1066 648 1066 556 1066 637 1067 526 1067 528 1067 639 1068 637 1068 528 1068 556 1069 648 1069 554 1069 580 1070 661 1070 659 1070 574 1071 576 1071 659 1071 576 1072 578 1072 659 1072 639 1073 528 1073 530 1073 578 1074 580 1074 659 1074 503 1075 505 1075 629 1075 505 1076 508 1076 629 1076 554 1077 648 1077 552 1077 626 1078 503 1078 629 1078 648 1079 646 1079 552 1079 629 1080 508 1080 510 1080 639 1081 530 1081 532 1081 641 1082 639 1082 532 1082 574 1083 659 1083 657 1083 572 1084 574 1084 657 1084 552 1085 646 1085 550 1085 510 1086 512 1086 631 1086 641 1087 532 1087 534 1087 629 1088 510 1088 631 1088 550 1089 646 1089 549 1089 572 1090 657 1090 570 1090 631 1091 512 1091 513 1091 641 1092 534 1092 536 1092 570 1093 657 1093 655 1093 549 1094 646 1094 547 1094 646 1095 645 1095 547 1095 641 1096 536 1096 538 1096 631 1097 513 1097 633 1097 643 1098 641 1098 538 1098 570 1099 655 1099 568 1099 547 1100 645 1100 544 1100 633 1101 513 1101 515 1101 643 1102 538 1102 540 1102 643 1103 540 1103 543 1103 544 1104 645 1104 543 1104 645 1105 643 1105 543 1105 568 1106 655 1106 566 1106 655 1107 652 1107 566 1107 598 1108 601 1108 619 1108 635 1109 633 1109 517 1109 601 1110 603 1110 619 1110 633 1111 515 1111 517 1111 598 1112 619 1112 616 1112 566 1113 652 1113 564 1113 595 1114 597 1114 616 1114 597 1115 598 1115 616 1115 635 1116 517 1116 519 1116 603 1117 605 1117 624 1117 605 1118 607 1118 624 1118 607 1119 609 1119 624 1119 619 1120 603 1120 624 1120 595 1121 616 1121 617 1121 564 1122 652 1122 562 1122 588 1123 591 1123 617 1123 591 1124 592 1124 617 1124 592 1125 595 1125 617 1125 609 1126 611 1126 627 1126 611 1127 613 1127 627 1127 635 1128 519 1128 521 1128 624 1129 609 1129 627 1129 562 1130 652 1130 560 1130 447 1131 333 1131 456 1131 471 1132 358 1132 360 1132 392 1133 484 1133 390 1133 418 1134 497 1134 495 1134 484 1135 482 1135 390 1135 414 1136 416 1136 495 1136 416 1137 418 1137 495 1137 471 1138 360 1138 362 1138 473 1139 471 1139 362 1139 332 1140 335 1140 460 1140 335 1141 337 1141 460 1141 390 1142 482 1142 388 1142 456 1143 332 1143 460 1143 473 1144 362 1144 364 1144 388 1145 482 1145 386 1145 408 1146 410 1146 493 1146 410 1147 412 1147 493 1147 412 1148 414 1148 493 1148 414 1149 495 1149 493 1149 482 1150 480 1150 386 1150 337 1151 339 1151 463 1151 473 1152 364 1152 366 1152 339 1153 342 1153 463 1153 460 1154 337 1154 463 1154 475 1155 473 1155 366 1155 463 1156 342 1156 344 1156 386 1157 480 1157 384 1157 408 1158 493 1158 491 1158 406 1159 408 1159 491 1159 475 1160 366 1160 368 1160 384 1161 480 1161 383 1161 344 1162 346 1162 465 1162 463 1163 344 1163 465 1163 475 1164 368 1164 370 1164 406 1165 491 1165 404 1165 383 1166 480 1166 381 1166 465 1167 346 1167 347 1167 480 1168 479 1168 381 1168 404 1169 491 1169 489 1169 475 1170 370 1170 372 1170 477 1171 475 1171 372 1171 465 1172 347 1172 467 1172 381 1173 479 1173 378 1173 404 1174 489 1174 402 1174 477 1175 372 1175 374 1175 477 1176 374 1176 377 1176 467 1177 347 1177 349 1177 378 1178 479 1178 377 1178 479 1179 477 1179 377 1179 402 1180 489 1180 400 1180 489 1181 486 1181 400 1181 469 1182 467 1182 351 1182 467 1183 349 1183 351 1183 432 1184 435 1184 453 1184 435 1185 437 1185 453 1185 400 1186 486 1186 398 1186 469 1187 351 1187 353 1187 429 1188 431 1188 450 1188 431 1189 432 1189 450 1189 432 1190 453 1190 450 1190 453 1191 437 1191 458 1191 437 1192 439 1192 458 1192 439 1193 441 1193 458 1193 441 1194 443 1194 458 1194 398 1195 486 1195 396 1195 429 1196 450 1196 449 1196 422 1197 425 1197 449 1197 425 1198 426 1198 449 1198 426 1199 429 1199 449 1199 469 1200 353 1200 355 1200 458 1201 443 1201 461 1201 443 1202 445 1202 461 1202 445 1203 447 1203 461 1203 396 1204 486 1204 394 1204 486 1205 484 1205 394 1205 471 1206 469 1206 358 1206 418 1207 420 1207 497 1207 420 1208 422 1208 497 1208 469 1209 355 1209 358 1209 422 1210 449 1210 497 1210 333 1211 332 1211 456 1211 394 1212 484 1212 392 1212 461 1213 447 1213 456 1213 252 1214 254 1214 331 1214 320 1215 318 1215 228 1215 254 1216 256 1216 331 1216 167 1217 166 1217 290 1217 305 1218 303 1218 192 1218 295 1219 281 1219 290 1219 303 1220 189 1220 192 1220 281 1221 167 1221 290 1221 228 1222 318 1222 226 1222 252 1223 331 1223 329 1223 248 1224 250 1224 329 1224 305 1225 192 1225 194 1225 250 1226 252 1226 329 1226 226 1227 318 1227 224 1227 166 1228 169 1228 294 1228 169 1229 171 1229 294 1229 290 1230 166 1230 294 1230 318 1231 316 1231 224 1231 305 1232 194 1232 196 1232 307 1233 305 1233 196 1233 224 1234 316 1234 222 1234 248 1235 329 1235 327 1235 242 1236 244 1236 327 1236 244 1237 246 1237 327 1237 307 1238 196 1238 198 1238 246 1239 248 1239 327 1239 171 1240 173 1240 297 1240 173 1241 176 1241 297 1241 222 1242 316 1242 220 1242 294 1243 171 1243 297 1243 316 1244 314 1244 220 1244 297 1245 176 1245 178 1245 307 1246 198 1246 200 1246 309 1247 307 1247 200 1247 240 1248 242 1248 325 1248 242 1249 327 1249 325 1249 220 1250 314 1250 218 1250 178 1251 180 1251 299 1251 309 1252 200 1252 202 1252 297 1253 178 1253 299 1253 218 1254 314 1254 217 1254 240 1255 325 1255 238 1255 299 1256 180 1256 181 1256 309 1257 202 1257 204 1257 238 1258 325 1258 323 1258 217 1259 314 1259 215 1259 314 1260 313 1260 215 1260 309 1261 204 1261 206 1261 299 1262 181 1262 301 1262 311 1263 309 1263 206 1263 238 1264 323 1264 236 1264 215 1265 313 1265 212 1265 301 1266 181 1266 183 1266 311 1267 206 1267 208 1267 311 1268 208 1268 211 1268 212 1269 313 1269 211 1269 313 1270 311 1270 211 1270 236 1271 323 1271 234 1271 323 1272 320 1272 234 1272 266 1273 269 1273 287 1273 303 1274 301 1274 185 1274 269 1275 271 1275 287 1275 301 1276 183 1276 185 1276 266 1277 287 1277 284 1277 234 1278 320 1278 232 1278 263 1279 265 1279 284 1279 265 1280 266 1280 284 1280 303 1281 185 1281 187 1281 271 1282 273 1282 292 1282 273 1283 275 1283 292 1283 275 1284 277 1284 292 1284 287 1285 271 1285 292 1285 263 1286 284 1286 285 1286 232 1287 320 1287 230 1287 256 1288 259 1288 285 1288 259 1289 260 1289 285 1289 260 1290 263 1290 285 1290 277 1291 279 1291 295 1291 279 1292 281 1292 295 1292 303 1293 187 1293 189 1293 292 1294 277 1294 295 1294 256 1295 285 1295 331 1295 230 1296 320 1296 228 1296 139 1297 26 1297 28 1297 60 1298 152 1298 58 1298 152 1299 150 1299 58 1299 82 1300 84 1300 163 1300 84 1301 86 1301 163 1301 139 1302 28 1302 30 1302 86 1303 165 1303 163 1303 141 1304 139 1304 30 1304 0 1305 3 1305 128 1305 58 1306 150 1306 56 1306 3 1307 5 1307 128 1307 124 1308 0 1308 128 1308 141 1309 30 1309 32 1309 56 1310 150 1310 54 1310 82 1311 163 1311 161 1311 76 1312 78 1312 161 1312 78 1313 80 1313 161 1313 80 1314 82 1314 161 1314 150 1315 148 1315 54 1315 5 1316 7 1316 131 1316 7 1317 10 1317 131 1317 141 1318 32 1318 34 1318 143 1319 141 1319 34 1319 128 1320 5 1320 131 1320 54 1321 148 1321 52 1321 131 1322 10 1322 12 1322 143 1323 34 1323 36 1323 74 1324 76 1324 159 1324 76 1325 161 1325 159 1325 52 1326 148 1326 51 1326 12 1327 14 1327 133 1327 131 1328 12 1328 133 1328 143 1329 36 1329 38 1329 74 1330 159 1330 72 1330 51 1331 148 1331 49 1331 133 1332 14 1332 15 1332 148 1333 147 1333 49 1333 72 1334 159 1334 157 1334 143 1335 38 1335 40 1335 145 1336 143 1336 40 1336 133 1337 15 1337 135 1337 49 1338 147 1338 46 1338 72 1339 157 1339 70 1339 145 1340 40 1340 42 1340 145 1341 42 1341 45 1341 135 1342 15 1342 17 1342 46 1343 147 1343 45 1343 147 1344 145 1344 45 1344 70 1345 157 1345 68 1345 157 1346 154 1346 68 1346 137 1347 135 1347 19 1347 135 1348 17 1348 19 1348 100 1349 103 1349 121 1349 103 1350 105 1350 121 1350 68 1351 154 1351 66 1351 137 1352 19 1352 21 1352 97 1353 99 1353 118 1353 99 1354 100 1354 118 1354 100 1355 121 1355 118 1355 121 1356 105 1356 126 1356 105 1357 107 1357 126 1357 107 1358 109 1358 126 1358 109 1359 111 1359 126 1359 66 1360 154 1360 64 1360 97 1361 118 1361 117 1361 90 1362 93 1362 117 1362 93 1363 94 1363 117 1363 94 1364 97 1364 117 1364 137 1365 21 1365 23 1365 111 1366 113 1366 129 1366 113 1367 115 1367 129 1367 126 1368 111 1368 129 1368 64 1369 154 1369 62 1369 154 1370 152 1370 62 1370 139 1371 137 1371 26 1371 86 1372 88 1372 165 1372 137 1373 23 1373 26 1373 88 1374 90 1374 165 1374 90 1375 117 1375 165 1375 62 1376 152 1376 60 1376 1 1377 0 1377 124 1377 129 1378 115 1378 124 1378 115 1379 1 1379 124 1379

+
+
+
+ + + + 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 8.951173e-15 7.5 1.457168e-15 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 2.75 -3.282097e-15 8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -2.75 3.282097e-15 -8.203121e-16 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -7.866971e-15 -7.5 -9.478891e-10 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 -4.465265e-15 4.930381e-30 16.17611 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5 -5.967449e-15 1.491477e-15 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 5.370704e-15 4.5 8.743006e-16 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -238.125 2.841997e-13 -7.103157e-14 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -1.768796 1.288397e-12 -0.4739474 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 -2 -6.700196e-14 -8.313378e-16 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 8.04121e-15 6.92796 -2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -1.012692e-14 -6.92796 2.872868 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5 5.967449e-15 -1.491477e-15 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 -5.370704e-15 -4.5 -1.278926e-11 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 238.125 -2.841997e-13 7.103157e-14 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 0 -6.196241 -14.94232 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1.106007e-15 -0.7660444 0.6427876 -1.106007e-15 -0.7660444 0.6427876 7.225257e-16 0.7660444 0.6427876 7.225257e-16 0.7660444 0.6427876 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 7.225257e-16 0.7660444 0.6427876 7.225257e-16 0.7660444 0.6427876 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 27 -3.222422e-14 8.053973e-15 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 34 -4.057865e-14 1.014204e-14 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1 1.366731e-15 -2.982953e-16 -1 1.366731e-15 -2.982953e-16 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -3.819167e-15 -3.2 -9.090666e-12 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -4.057865e-14 -34 -9.658833e-11 -1 1.020248e-15 -2.982953e-16 -1 1.020248e-15 -2.982953e-16 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -4.057865e-14 -34 -9.661979e-11 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -3.819167e-15 -3.2 -9.093627e-12 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 -4 4.773959e-15 -1.193181e-15 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 3.2 -3.819167e-15 9.54545e-16 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 3828.328 -4.602242e-09 1670.437 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 -1.849859e-09 -1.824881e-08 5956.806 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 1267.136 6795.737 1.954982e-08 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 922.8398 -6211.925 -1233.637 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 -1.141578e-15 -0.8099003 0.5865675 -1.141578e-15 -0.8099003 0.5865675 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -10.75482 -15372.02 -9903.762 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 1.502885e-11 -15515.12 11236.77 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -6.35 7.57866e-15 -1.894175e-15 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 -1.790235e-14 -15 -4.26216e-11 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.136799e-13 95.25 2.70604e-10 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 1.456354e-07 11133.32 8063.269 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 2001.365 15127.54 -9989.293 7.916374e-16 0.8099003 0.5865675 7.916374e-16 0.8099003 0.5865675 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 -1.849909e-12 -1550 -4.404388e-09 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.475587e-14 37.5 1.065578e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 4.236889e-14 35.5 1.008747e-10 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 2.982953e-16 2.841652e-12 -1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 8466.145 -8.877881e-13 -1.763074e-13 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 8633.608 7.551962e-13 -4.986849e-13 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -2.215493e-14 -24.74874 -24.74874 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 1.19349e-15 1 9.707286e-12 1.19349e-15 1 9.707286e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -2.982953e-16 -2.841631e-12 1 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1.19349e-15 -1 4.024694e-12 -1.19349e-15 -1 4.024694e-12 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 -7.160939e-15 -6 -1.705003e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 1.551537e-14 13 3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 -1.551537e-14 -13 -3.693826e-11 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 -0 0.82107 2.456994 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 0.2027964 -5.733423 -0 0.2027964 -5.733423 -0 1.513456e-11 -5.326182 -0 1.513456e-11 -5.326182 0 -2.864246 -9.009839 0 -2.864246 -9.009839 0 -2.864246 -9.009839 0 -2.864246 -9.009839 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 0 -27.22984 -7.743139e-11 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -5.32124 7.369358 -0 -1.228707 3.477554 -0 -1.228707 3.477554 -0 -1.228707 3.477554 -0 -1.228707 3.477554 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -42.58148 -30.71069 0 -42.58148 -30.71069 0 -1.228298 -2.044823 0 -1.228298 -2.044823 0 -1.228298 -2.044823 0 -1.228298 -2.044823 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -0 0.6149788 2.044823 -0 0.6149788 2.044823 -0 0.6149788 2.044823 -0 0.6149788 2.044823 -0 23.74733 16.17517 -0 23.74733 16.17517 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 0 -1.228298 -2.254209 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 -0 59.57318 1.680256e-10 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 -0 14.73996 4.199308e-11 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 3.273122 -5.733423 0 1.49214e-11 -5.733423 0 1.49214e-11 -5.733423 0 1.49214e-11 -5.733423 0 1.49214e-11 -5.733423 0 1.49214e-11 -5.733423 0 1.49214e-11 -5.733423 0 -0.2060912 -1.637595 0 -0.2060912 -1.637595 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -1.193712e-11 3.477975 0 -1.193712e-11 3.477975 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 -1.379163e-10 48.31984 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 45.64892 1.298961e-10 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 -0 1.379163e-10 -48.52181 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 0 -46.26388 -1.314016e-10 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 -0 30.09242 8.549161e-11 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 8.398615e-11 -30.29522 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -30.30016 -8.609113e-11 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 0 -8.697043e-11 30.30346 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.961709 11.8749 -0 -6.863843e-11 23.34174 -0 -6.863843e-11 23.34174 -0 -6.863843e-11 23.34174 -0 -6.863843e-11 23.34174 -0 -6.863843e-11 23.34174 -0 -6.863843e-11 23.34174 -0 0.2011373 6.343447 -0 0.2011373 6.343447 -0 0.2027964 5.325365 -0 0.2027964 5.325365 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 -0 59.16677 1.679989e-10 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 -0 1.64089 2.456597 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 1.193712e-11 -4.505124 -0 1.193712e-11 -4.505124 -0 2.088996e-11 -6.953472 -0 2.088996e-11 -6.953472 0 -2.457006 -7.57587 0 -2.457006 -7.57587 0 -2.457006 -7.57587 0 -2.457006 -7.57587 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 0 -25.5873 -7.260192e-11 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -0 -3.891396 14.94152 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 0 -20.88432 -5.939915e-11 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 -0 10.64743 3.026912e-11 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 2.457006 -5.527331 0 1.193712e-11 -4.702967 0 1.193712e-11 -4.702967 0 1.193712e-11 -4.702967 0 1.193712e-11 -4.702967 0 1.193712e-11 -4.702967 0 1.193712e-11 -4.702967 0 -0.4088876 -2.258743 0 -0.4088876 -2.258743 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 0 -1.022616 -2.911005e-12 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -2.984279e-12 1.84656 0 -2.984279e-12 1.84656 -0 1.02715 3.680759 -0 1.02715 3.680759 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 -0 12.8967 3.662737e-11 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 2.307821e-15 2.253801 -6.557776 0 8.952838e-12 -3.478792 0 8.952838e-12 -3.478792 0 8.952838e-12 -3.478792 0 8.952838e-12 -3.478792 0 -0.2060912 -1.838312 0 -0.2060912 -1.838312 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -5.968559e-12 2.662676 0 -5.968559e-12 2.662676 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 -1.351452e-10 48.31159 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 45.64892 1.29603e-10 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 -0 1.381295e-10 -48.52593 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 0 -46.26388 -1.314149e-10 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 -0 30.09242 8.547829e-11 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 8.718359e-11 -30.29522 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -30.30016 -8.579804e-11 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 0 -8.377299e-11 30.30346 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -0 -2.457006 2.246381 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -0 -1.811884e-11 6.549539 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 0 -0.2015579 -3.074859 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 -0 59.57606 1.691447e-10 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 0 -2.455767 -2.864643 0 -2.455767 -2.864643 0 -2.455767 -2.864643 0 -2.455767 -2.864643 0 -2.455767 -2.864643 0 -2.455767 -2.864643 0 -2.455767 -2.864643 0 -2.455767 -2.864643 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 -2.982953e-16 -2.841296e-12 1 -2.982953e-16 -2.841296e-12 1 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 -0 59.36997 1.679723e-10 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 -0 2.049777 2.662676 -0 2.049777 2.662676 -0 2.049777 2.662676 -0 2.049777 2.662676 -0 2.049777 2.662676 -0 2.049777 2.662676 -0 2.049777 2.662676 -0 2.049777 2.662676 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 2.982953e-16 2.841296e-12 -1 2.982953e-16 2.841296e-12 -1 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 0 -55.68591 -1.590195e-10 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 -8.190417 6.557776 -0 -8.190417 6.557776 -0 -8.190417 6.557776 -0 -8.190417 6.557776 -0 -8.190417 6.557776 -0 -8.190417 6.557776 -0 -6.142298 11.26075 -0 -6.142298 11.26075 -0 -6.142298 11.26075 -0 -6.142298 11.26075 -0 -6.142298 11.26075 -0 -6.142298 11.26075 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 0 -2.864234 -7.163676 0 -2.864234 -7.163676 0 -1.843266 -6.137356 0 -1.843266 -6.137356 0 -0.2011489 -1.838323 0 -0.2011489 -1.838323 -5.115435e-16 -0.6239309 -0.7814795 -5.115435e-16 -0.6239309 -0.7814795 -0 -4.706261 4.711215 -0 -4.706261 4.711215 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 0.4088876 1.022207 -0 4.510066 8.804169 -0 4.510066 8.804169 -0 3.276826 5.527331 -0 3.276826 5.527331 -0 -0.4121824 3.272713 -0 -0.4121824 3.272713 -0 -8.952838e-12 3.470555 -0 -8.952838e-12 3.470555 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 45.24169 1.290701e-10 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 -0 1.409006e-10 -48.92987 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 0 -46.46999 -1.320544e-10 -1.19349e-15 -1 -2.841407e-12 -1.19349e-15 -1 -2.841407e-12 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 -0 30.09242 8.707701e-11 1.19349e-15 1 2.841407e-12 1.19349e-15 1 2.841407e-12 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 8.718359e-11 -30.70739 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -29.89087 -8.403944e-11 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 0 -8.675727e-11 30.09737 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -1.483294 -8.979746 0 -0.7116937 -2.87674 0 -0.7116937 -2.87674 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -9.579882 -2.473083 0 -17.29012 -4.181973 0 -17.29012 -4.181973 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -1.60997 8.49887 -0 -0.2802836 2.024213 -0 -0.2802836 2.024213 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 21.05333 -4.010676 -0 34.18619 -6.424241 -0 34.18619 -6.424241 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -3.57772 -0.888661 0 -22.37847 -5.347213 0 -22.37847 -5.347213 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 0.04492435 3.950749 -0 3.331237 19.76073 -0 3.331237 19.76073 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.950069 -2.365915 -0 8.618404 -1.915814 -0 8.618404 -1.915814 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 1.392748 -6.406517 -0 10.12836 -57.7159 -0 10.12836 -57.7159 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -1.514623 -8.977798 0 -0.5965612 -2.904493 0 -0.5965612 -2.904493 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -11.60739 -2.609912 0 -17.24291 -4.02315 0 -17.24291 -4.02315 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -1.458735 7.947377 -0 -0.2801551 1.471649 -0 -0.2801551 1.471649 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 21.04211 -4.068663 -0 34.16888 -6.519729 -0 34.16888 -6.519729 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.33805e-15 -2.982953e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 -1 1.059955e-15 -2.429216e-16 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 4.156689e-16 2.841261e-12 -1 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -27 3.222422e-14 -8.053973e-15 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 -34 4.057865e-14 -1.014204e-14 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1 -1.366731e-15 2.982953e-16 1 -1.366731e-15 2.982953e-16 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 3.819167e-15 3.2 2.102022e-15 1 -1.020248e-15 2.982953e-16 1 -1.020248e-15 2.982953e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 3.819167e-15 3.2 -8.585725e-16 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 4 -4.773959e-15 1.193181e-15 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 -3.2 3.819167e-15 -9.54545e-16 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -3828.328 -2.16005e-11 1670.437 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1.272672e-09 -6.832552e-10 5956.806 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -1267.136 -6795.737 2.963816e-10 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 -922.8398 6211.925 -1233.637 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 7.916374e-16 0.8099003 0.5865675 7.916374e-16 0.8099003 0.5865675 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 10.75482 15372.02 -9903.762 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 5.026898e-15 5.142867 3.724704 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 -8.890847e-12 15515.12 11236.77 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 6.35 -7.57866e-15 1.894175e-15 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 -1.136799e-13 -95.25 7.886088e-31 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 1.694185e-07 -11133.32 8063.269 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -2001.365 -15127.54 -9989.293 -1.141578e-15 -0.8099003 0.5865675 -1.141578e-15 -0.8099003 0.5865675 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 1.849909e-12 1550 -7.849251e-14 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 2.982953e-16 -5.064033e-17 -1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -8466.145 1.775576e-12 -3.526149e-13 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -7.249021e-15 -5.142867 3.724704 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -8633.608 7.551962e-13 4.986849e-13 -1.106007e-15 -0.7660444 0.6427876 -1.106007e-15 -0.7660444 0.6427876 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -1.19349e-15 -1 6.865796e-12 -1.19349e-15 -1 6.865796e-12 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1.19349e-15 1 6.866185e-12 1.19349e-15 1 6.866185e-12 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -0 -0.82107 2.456994 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -0.2027964 -5.733423 -0 -0.2027964 -5.733423 -0 0 -5.326182 -0 0 -5.326182 -0 2.864246 -9.009839 -0 2.864246 -9.009839 -0 2.864246 -9.009839 -0 2.864246 -9.009839 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 -0 27.22984 -0 0 5.32124 7.369358 0 5.32124 7.369358 0 5.32124 7.369358 0 5.32124 7.369358 0 5.32124 7.369358 0 5.32124 7.369358 0 5.32124 7.369358 0 5.32124 7.369358 0 1.228707 3.477554 0 1.228707 3.477554 0 1.228707 3.477554 0 1.228707 3.477554 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -0 42.58148 -30.71069 -0 42.58148 -30.71069 -0 1.228298 -2.044823 -0 1.228298 -2.044823 -0 1.228298 -2.044823 -0 1.228298 -2.044823 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -0 -0.6149788 2.044823 -0 -0.6149788 2.044823 -0 -0.6149788 2.044823 -0 -0.6149788 2.044823 -0 -23.74733 16.17517 -0 -23.74733 16.17517 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 -0 1.228298 -2.254209 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -0 -59.57318 -0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 0 -14.73996 0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -3.273122 -5.733423 -0 -0 -5.733423 -0 -0 -5.733423 -0 -0 -5.733423 -0 -0 -5.733423 -0 -0 -5.733423 -0 -0 -5.733423 0 0.2060912 -1.637595 0 0.2060912 -1.637595 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 0 -0 3.477975 0 -0 3.477975 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 0 0 48.31984 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 0 -48.52181 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 6.961709 11.8749 0 0 23.34174 0 0 23.34174 0 0 23.34174 0 0 23.34174 0 0 23.34174 0 0 23.34174 -0 -0.2011373 6.343447 -0 -0.2011373 6.343447 -0 -0.2027964 5.325365 -0 -0.2027964 5.325365 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -0 -59.16677 -0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -0 -1.64089 2.456597 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 0 -4.505124 -0 0 -4.505124 -0 0 -6.953472 -0 0 -6.953472 -0 2.457006 -7.57587 -0 2.457006 -7.57587 -0 2.457006 -7.57587 -0 2.457006 -7.57587 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 -0 25.5873 -0 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 0 3.891396 14.94152 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 -0 20.88432 -0 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 0 -10.64743 0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -2.457006 -5.527331 -0 -0 -4.702967 -0 -0 -4.702967 -0 -0 -4.702967 -0 -0 -4.702967 -0 -0 -4.702967 -0 -0 -4.702967 0 0.4088876 -2.258743 0 0.4088876 -2.258743 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 0 1.022616 0 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 0 -0 1.84656 0 -0 1.84656 0 -1.02715 3.680759 0 -1.02715 3.680759 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 0 -12.8967 0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -3.122346e-15 -2.253801 -6.557776 -0 -0 -3.478792 -0 -0 -3.478792 -0 -0 -3.478792 -0 -0 -3.478792 0 0.2060912 -1.838312 0 0.2060912 -1.838312 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 0 -0 2.662676 0 -0 2.662676 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 0 0 48.31159 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 -45.64892 -0 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 0 -48.52593 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 -0 46.26388 -0 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 -0 -0 -30.29522 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 30.30016 0 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 0 -0 30.30346 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 2.457006 2.246381 0 2.457006 2.246381 0 2.457006 2.246381 0 2.457006 2.246381 0 2.457006 2.246381 0 2.457006 2.246381 0 2.457006 2.246381 0 2.457006 2.246381 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 0 0 6.549539 0 0 6.549539 0 0 6.549539 0 0 6.549539 0 0 6.549539 0 0 6.549539 0 0 6.549539 0 0 6.549539 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 -0 0.2015579 -3.074859 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -0 -59.57606 -0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -0 2.455767 -2.864643 -0 2.455767 -2.864643 -0 2.455767 -2.864643 -0 2.455767 -2.864643 -0 2.455767 -2.864643 -0 2.455767 -2.864643 -0 2.455767 -2.864643 -0 2.455767 -2.864643 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -2.982953e-16 -1.94289e-16 1 -2.982953e-16 -1.94289e-16 1 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -59.36997 -0 -0 -59.36997 -0 -0 -59.36997 -0 -0 -59.36997 -0 -0 -59.36997 -0 -0 -59.36997 -0 -0 -59.36997 -0 -0 -59.36997 -0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -0 -2.049777 2.662676 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 2.982953e-16 1.94289e-16 -1 2.982953e-16 1.94289e-16 -1 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -0 55.68591 -0 -0 55.68591 -0 -0 55.68591 -0 -0 55.68591 -0 -0 55.68591 -0 -0 55.68591 -0 -0 55.68591 -0 -0 55.68591 -0 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 8.190417 6.557776 0 8.190417 6.557776 0 8.190417 6.557776 0 8.190417 6.557776 0 8.190417 6.557776 0 8.190417 6.557776 0 6.142298 11.26075 0 6.142298 11.26075 0 6.142298 11.26075 0 6.142298 11.26075 0 6.142298 11.26075 0 6.142298 11.26075 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -0 2.864234 -7.163676 -0 2.864234 -7.163676 -0 1.843266 -6.137356 -0 1.843266 -6.137356 -0 0.2011489 -1.838323 -0 0.2011489 -1.838323 9.777669e-16 0.6239309 -0.7814795 9.777669e-16 0.6239309 -0.7814795 0 4.706261 4.711215 0 4.706261 4.711215 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -0.4088876 1.022207 -0 -4.510066 8.804169 -0 -4.510066 8.804169 -0 -3.276826 5.527331 -0 -3.276826 5.527331 0 0.4121824 3.272713 0 0.4121824 3.272713 0 0 3.470555 0 0 3.470555 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 -45.24169 -0 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 0 -48.92987 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 -0 46.46999 -0 1.19349e-15 1 1.94289e-16 1.19349e-15 1 1.94289e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 0 -30.09242 0 -1.19349e-15 -1 -1.94289e-16 -1.19349e-15 -1 -1.94289e-16 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 -0 -0 -30.70739 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 29.89087 0 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 0 -0 30.09737 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 1.483294 -8.979746 -0 0.7116937 -2.87674 -0 0.7116937 -2.87674 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 9.579882 -2.473083 -0 17.29012 -4.181973 -0 17.29012 -4.181973 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 1.60997 8.49887 0 0.2802836 2.024213 0 0.2802836 2.024213 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -21.05333 -4.010676 -0 -34.18619 -6.424241 -0 -34.18619 -6.424241 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 3.57772 -0.888661 -0 22.37847 -5.347213 -0 22.37847 -5.347213 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -0.04492435 3.950749 -0 -3.331237 19.76073 -0 -3.331237 19.76073 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.950069 -2.365915 -0 -8.618404 -1.915814 -0 -8.618404 -1.915814 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -1.392748 -6.406517 -0 -10.12836 -57.7159 -0 -10.12836 -57.7159 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 1.514623 -8.977798 -0 0.5965612 -2.904493 -0 0.5965612 -2.904493 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 11.60739 -2.609912 -0 17.24291 -4.02315 -0 17.24291 -4.02315 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 1.458735 7.947377 0 0.2801551 1.471649 0 0.2801551 1.471649 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -21.04211 -4.068663 -0 -34.16888 -6.519729 -0 -34.16888 -6.519729 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -1 1.19349e-15 -2.940514e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 -9.089642e-16 -0.761602 -1.479709e-16 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 4.115465e-16 0.3448262 6.699595e-17 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 0.4827498 -0.8757583 -2.487332e-12 0.4827498 -0.8757583 -2.487332e-12 0.431213 -0.9022502 -2.562633e-12 0.431213 -0.9022502 -2.562633e-12 0.4318246 -0.9019576 -2.561802e-12 0.4318246 -0.9019576 -2.561802e-12 0.2878921 -0.9576629 -2.720171e-12 0.2878921 -0.9576629 -2.720171e-12 0.2885883 -0.9574533 -2.719575e-12 0.2885883 -0.9574533 -2.719575e-12 0.09502878 -0.9954745 -2.827754e-12 0.09502878 -0.9954745 -2.827754e-12 0.03507264 -0.9993848 -2.838915e-12 0.03507264 -0.9993848 -2.838915e-12 0.1957526 -0.9806533 -2.785562e-12 0.1957526 -0.9806533 -2.785562e-12 0.451072 -0.8924876 -2.534883e-12 0.451072 -0.8924876 -2.534883e-12 0.6557701 -0.7549606 -2.144029e-12 0.6557701 -0.7549606 -2.144029e-12 0.7843259 -0.620349 -1.761525e-12 0.7843259 -0.620349 -1.761525e-12 0.8190024 -0.5737901 -1.629235e-12 0.8190024 -0.5737901 -1.629235e-12 0.8493397 -0.5278466 -1.498696e-12 0.8493397 -0.5278466 -1.498696e-12 0.8873992 -0.4610018 -1.308777e-12 0.8873992 -0.4610018 -1.308777e-12 0.907379 -0.4203135 -1.193176e-12 0.907379 -0.4203135 -1.193176e-12 0.9345765 -0.3557623 -1.009782e-12 0.9345765 -0.3557623 -1.009782e-12 0.950459 -0.31085 -8.821857e-13 0.950459 -0.31085 -8.821857e-13 0.9741037 -0.2261019 -6.414213e-13 0.9741037 -0.2261019 -6.414213e-13 0.9811383 -0.1933069 -5.482545e-13 0.9811383 -0.1933069 -5.482545e-13 0.9935276 -0.1135908 -3.217944e-13 0.9935276 -0.1135908 -3.217944e-13 0.9978595 -0.06539494 -1.84881e-13 0.9978595 -0.06539494 -1.84881e-13 1 3.452941e-05 9.85984e-16 1 3.452941e-05 9.85984e-16 0.9978549 0.06546497 1.868519e-13 0.9978549 0.06546497 1.868519e-13 0.9978428 0.06564829 1.873727e-13 0.9978428 0.06564829 1.873727e-13 0.9935399 0.1134838 3.232547e-13 0.9935399 0.1134838 3.232547e-13 0.9935204 0.1136536 3.237372e-13 0.9935204 0.1136536 3.237372e-13 0.981125 0.1933745 5.50189e-13 0.981125 0.1933745 5.50189e-13 0.9740854 0.2261806 6.433747e-13 0.9740854 0.2261806 6.433747e-13 0.9502701 0.3114271 8.855126e-13 0.9502701 0.3114271 8.855126e-13 0.9347713 0.3552502 1.009987e-12 0.9347713 0.3552502 1.009987e-12 0.9073438 0.4203893 1.195003e-12 0.9073438 0.4203893 1.195003e-12 0.8870019 0.4617658 1.312523e-12 0.8870019 0.4617658 1.312523e-12 0.8497315 0.5272157 1.498413e-12 0.8497315 0.5272157 1.498413e-12 0.8184798 0.5745353 1.632805e-12 0.8184798 0.5745353 1.632805e-12 0.8183984 0.5746513 1.633135e-12 0.8183984 0.5746513 1.633135e-12 0.7842831 0.6204032 1.763072e-12 0.7842831 0.6204032 1.763072e-12 0.6612692 0.7501487 2.13153e-12 0.6612692 0.7501487 2.13153e-12 0.4426467 0.8966961 2.547632e-12 0.4426467 0.8966961 2.547632e-12 0.19608 0.9805879 2.785724e-12 0.19608 0.9805879 2.785724e-12 0.03540055 0.9993732 2.838944e-12 0.03540055 0.9993732 2.838944e-12 0.09456214 0.995519 2.828048e-12 0.09456214 0.995519 2.828048e-12 0.2890326 0.9573193 2.719707e-12 0.2890326 0.9573193 2.719707e-12 0.426975 0.9042635 2.569114e-12 0.426975 0.9042635 2.569114e-12 0.4827268 0.875771 2.488226e-12 0.4827268 0.875771 2.488226e-12 0.5083928 0.8611253 2.446644e-12 0.5083928 0.8611253 2.446644e-12 0.5075979 0.8615941 2.447975e-12 0.5075979 0.8615941 2.447975e-12 0.631281 0.7755542 2.203672e-12 0.631281 0.7755542 2.203672e-12 0.7759827 0.6307541 1.792468e-12 0.7759827 0.6307541 1.792468e-12 0.8398029 0.5428914 1.542934e-12 0.8398029 0.5428914 1.542934e-12 0.9381884 0.3461249 9.840678e-13 0.9381884 0.3461249 9.840678e-13 0.9670239 0.2546858 7.24343e-13 0.9670239 0.2546858 7.24343e-13 0.9954788 0.09498378 2.707037e-13 0.9954788 0.09498378 2.707037e-13 1 3.452941e-05 9.85984e-16 1 3.452941e-05 9.85984e-16 0.9982638 0.05890198 1.682088e-13 0.9982638 0.05890198 1.682088e-13 0.9544247 0.2984519 8.486579e-13 0.9544247 0.2984519 8.486579e-13 0.8685881 0.4955348 1.408434e-12 0.8685881 0.4955348 1.408434e-12 0.7925074 0.6098623 1.733135e-12 0.7925074 0.6098623 1.733135e-12 0.6461102 0.7632441 2.168716e-12 0.6461102 0.7632441 2.168716e-12 0.470623 0.8823344 2.506859e-12 0.470623 0.8823344 2.506859e-12 0.3712451 0.9285349 2.638013e-12 0.3712451 0.9285349 2.638013e-12 0.37012 0.9289839 2.639287e-12 0.37012 0.9289839 2.639287e-12 0.1790673 0.9838368 2.794938e-12 0.1790673 0.9838368 2.794938e-12 0.1787022 0.9839032 2.795126e-12 0.1787022 0.9839032 2.795126e-12 0.1415698 0.9899283 2.812209e-12 0.1415698 0.9899283 2.812209e-12 0.1411784 0.9899842 2.812367e-12 0.1411784 0.9899842 2.812367e-12 0.0889271 0.9960381 2.829518e-12 0.0889271 0.9960381 2.829518e-12 0.01786625 0.9998404 2.840256e-12 0.01786625 0.9998404 2.840256e-12 -0.01793665 0.9998391 2.840221e-12 -0.01793665 0.9998391 2.840221e-12 -0.08879519 0.9960499 2.829394e-12 -0.08879519 0.9960499 2.829394e-12 -0.08899424 0.9960321 2.829343e-12 -0.08899424 0.9960321 2.829343e-12 -0.1412259 0.9899774 2.812097e-12 -0.1412259 0.9899774 2.812097e-12 -0.1415807 0.9899267 2.811953e-12 -0.1415807 0.9899267 2.811953e-12 -0.1787735 0.9838903 2.794772e-12 -0.1787735 0.9838903 2.794772e-12 -0.1791386 0.9838238 2.794583e-12 -0.1791386 0.9838238 2.794583e-12 -0.3703637 0.9288868 2.638354e-12 -0.3703637 0.9288868 2.638354e-12 -0.3715791 0.9284013 2.636974e-12 -0.3715791 0.9284013 2.636974e-12 -0.4708645 0.8822055 2.505657e-12 -0.4708645 0.8822055 2.505657e-12 -0.4714512 0.8818921 2.504767e-12 -0.4714512 0.8818921 2.504767e-12 -0.6455519 0.7637164 2.168911e-12 -0.6455519 0.7637164 2.168911e-12 -0.79314 0.6090393 1.72939e-12 -0.79314 0.6090393 1.72939e-12 -0.793503 0.6085663 1.728046e-12 -0.793503 0.6085663 1.728046e-12 -0.8677211 0.4970514 1.4112e-12 -0.8677211 0.4970514 1.4112e-12 -0.9546245 0.297812 8.45145e-13 -0.9546245 0.297812 8.45145e-13 -0.9982968 0.0583394 1.64838e-13 -0.9982968 0.0583394 1.64838e-13 -1 -3.452941e-05 -9.85984e-16 -1 -3.452941e-05 -9.85984e-16 -0.9954947 0.09481677 2.684615e-13 -0.9954947 0.09481677 2.684615e-13 -0.9955467 0.09426984 2.669078e-13 -0.9955467 0.09426984 2.669078e-13 -0.9670369 0.2546362 7.224847e-13 -0.9670369 0.2546362 7.224847e-13 -0.9671606 0.2541661 7.211492e-13 -0.9671606 0.2541661 7.211492e-13 -0.9382123 0.3460601 9.822177e-13 -0.9382123 0.3460601 9.822177e-13 -0.8398875 0.5427605 1.541071e-12 -0.8398875 0.5427605 1.541071e-12 -0.7762487 0.6304269 1.79016e-12 -0.7762487 0.6304269 1.79016e-12 -0.7764522 0.6301762 1.789448e-12 -0.7764522 0.6301762 1.789448e-12 -0.6294032 0.7770789 2.206884e-12 -0.6294032 0.7770789 2.206884e-12 -0.5073774 0.8617239 2.447443e-12 -0.5073774 0.8617239 2.447443e-12 -0.5078909 0.8614214 2.446583e-12 -0.5078909 0.8614214 2.446583e-12 -0.4839382 0.8751022 2.485467e-12 -0.4839382 0.8751022 2.485467e-12 -0.4270374 0.904234 2.568272e-12 -0.4270374 0.904234 2.568272e-12 -0.4276811 0.9039297 2.567407e-12 -0.4276811 0.9039297 2.567407e-12 -0.2876766 0.9577276 2.720355e-12 -0.2876766 0.9577276 2.720355e-12 -0.09459323 0.995516 2.827872e-12 -0.09459323 0.995516 2.827872e-12 -0.03547102 0.9993707 2.838874e-12 -0.03547102 0.9993707 2.838874e-12 -0.1961477 0.9805744 2.785337e-12 -0.1961477 0.9805744 2.785337e-12 -0.4427086 0.8966656 2.546759e-12 -0.4427086 0.8966656 2.546759e-12 -0.6650933 0.7467602 2.120726e-12 -0.6650933 0.7467602 2.120726e-12 -0.6662394 0.7457379 2.117821e-12 -0.6662394 0.7457379 2.117821e-12 -0.784309 0.6203703 1.761586e-12 -0.784309 0.6203703 1.761586e-12 -0.7844753 0.6201601 1.760988e-12 -0.7844753 0.6201601 1.760988e-12 -0.8184867 0.5745254 1.631324e-12 -0.8184867 0.5745254 1.631324e-12 -0.8490412 0.5283266 1.50006e-12 -0.8490412 0.5283266 1.50006e-12 -0.8876875 0.4604465 1.307199e-12 -0.8876875 0.4604465 1.307199e-12 -0.9067746 0.4216158 1.196876e-12 -0.9067746 0.4216158 1.196876e-12 -0.9353116 0.3538251 1.004278e-12 -0.9353116 0.3538251 1.004278e-12 -0.9353773 0.3536514 1.003785e-12 -0.9353773 0.3536514 1.003785e-12 -0.9502571 0.3114666 8.839374e-13 -0.9502571 0.3114666 8.839374e-13 -0.9737724 0.2275244 6.454624e-13 -0.9737724 0.2275244 6.454624e-13 -0.9810985 0.1935092 5.488292e-13 -0.9810985 0.1935092 5.488292e-13 -0.9935523 0.1133748 3.211809e-13 -0.9935523 0.1133748 3.211809e-13 -0.9978472 0.06558171 1.854116e-13 -0.9978472 0.06558171 1.854116e-13 -1 -3.452941e-05 -9.85984e-16 -1 -3.452941e-05 -9.85984e-16 -0.9978427 -0.0656495 -1.873761e-13 -0.9978427 -0.0656495 -1.873761e-13 -0.9935438 -0.1134492 -3.231565e-13 -0.9935438 -0.1134492 -3.231565e-13 -0.9810851 -0.193577 -5.507641e-13 -0.9810851 -0.193577 -5.507641e-13 -0.9737594 -0.2275801 -6.4735e-13 -0.9737594 -0.2275801 -6.4735e-13 -0.9503864 -0.3110718 -8.845036e-13 -0.9503864 -0.3110718 -8.845036e-13 -0.9351609 -0.3542231 -1.00707e-12 -0.9351609 -0.3542231 -1.00707e-12 -0.9350694 -0.3544648 -1.007756e-12 -0.9350694 -0.3544648 -1.007756e-12 -0.9067515 -0.4216653 -1.198627e-12 -0.9067515 -0.4216653 -1.198627e-12 -0.8880195 -0.4598059 -1.306956e-12 -0.8880195 -0.4598059 -1.306956e-12 -0.8485445 -0.5291241 -1.503833e-12 -0.8485445 -0.5291241 -1.503833e-12 -0.819044 -0.5737307 -1.63052e-12 -0.819044 -0.5737307 -1.63052e-12 -0.7842662 -0.6204245 -1.763132e-12 -0.7842662 -0.6204245 -1.763132e-12 -0.6606595 -0.7506857 -2.133055e-12 -0.6606595 -0.7506857 -2.133055e-12 -0.4507082 -0.8926714 -2.536206e-12 -0.4507082 -0.8926714 -2.536206e-12 -0.1958831 -0.9806273 -2.785835e-12 -0.1958831 -0.9806273 -2.785835e-12 -0.03500376 -0.9993872 -2.838984e-12 -0.03500376 -0.9993872 -2.838984e-12 -0.09531851 -0.9954468 -2.827844e-12 -0.09531851 -0.9954468 -2.827844e-12 -0.09492208 -0.9954847 -2.827951e-12 -0.09492208 -0.9954847 -2.827951e-12 -0.2871021 -0.9579 -2.721355e-12 -0.2871021 -0.9579 -2.721355e-12 -0.2864087 -0.9581075 -2.721944e-12 -0.2864087 -0.9581075 -2.721944e-12 -0.4319964 -0.9018753 -2.562335e-12 -0.4319964 -0.9018753 -2.562335e-12 -0.4311507 -0.9022799 -2.563484e-12 -0.4311507 -0.9022799 -2.563484e-12 -0.4838403 -0.8751563 -2.48648e-12 -0.4838403 -0.8751563 -2.48648e-12 -0.4835677 -0.875307 -2.486908e-12 -0.4835677 -0.875307 -2.486908e-12 -0.5042485 -0.8635586 -2.453553e-12 -0.5042485 -0.8635586 -2.453553e-12 -0.503968 -0.8637223 -2.454018e-12 -0.503968 -0.8637223 -2.454018e-12 -0.6323633 -0.774672 -2.201167e-12 -0.6323633 -0.774672 -2.201167e-12 -0.7775401 -0.6288334 -1.787013e-12 -0.7775401 -0.6288334 -1.787013e-12 -0.8397089 -0.5430368 -1.543347e-12 -0.8397089 -0.5430368 -1.543347e-12 -0.9382393 -0.3459871 -9.836762e-13 -0.9382393 -0.3459871 -9.836762e-13 -0.9671561 -0.254183 -7.229148e-13 -0.9671561 -0.254183 -7.229148e-13 -0.9954702 -0.09507407 -2.709602e-13 -0.9954702 -0.09507407 -2.709602e-13 -1 -3.452941e-05 -9.85984e-16 -1 -3.452941e-05 -9.85984e-16 -0.9983048 -0.0582026 -1.662221e-13 -0.9983048 -0.0582026 -1.662221e-13 -0.998262 -0.05893193 -1.682939e-13 -0.998262 -0.05893193 -1.682939e-13 -0.9548196 -0.297186 -8.45062e-13 -0.9548196 -0.297186 -8.45062e-13 -0.9546698 -0.2976669 -8.464282e-13 -0.9546698 -0.2976669 -8.464282e-13 -0.8674888 -0.4974567 -1.413892e-12 -0.8674888 -0.4974567 -1.413892e-12 -0.8673413 -0.4977139 -1.414623e-12 -0.8673413 -0.4977139 -1.414623e-12 -0.7933868 -0.6087178 -1.729885e-12 -0.7933868 -0.6087178 -1.729885e-12 -0.6450619 -0.7641303 -2.171233e-12 -0.6450619 -0.7641303 -2.171233e-12 -0.4713849 -0.8819276 -2.505705e-12 -0.4713849 -0.8819276 -2.505705e-12 -0.3709133 -0.9286675 -2.638389e-12 -0.3709133 -0.9286675 -2.638389e-12 -0.3702759 -0.9289218 -2.639111e-12 -0.3702759 -0.9289218 -2.639111e-12 -0.1791343 -0.9838246 -2.794903e-12 -0.1791343 -0.9838246 -2.794903e-12 -0.141134 -0.9899905 -2.812385e-12 -0.141134 -0.9899905 -2.812385e-12 -0.08889378 -0.9960411 -2.829526e-12 -0.08889378 -0.9960411 -2.829526e-12 -0.08874976 -0.996054 -2.829563e-12 -0.08874976 -0.996054 -2.829563e-12 -0.01799596 -0.9998381 -2.840249e-12 -0.01799596 -0.9998381 -2.840249e-12 0.01806976 -0.9998367 -2.840214e-12 0.01806976 -0.9998367 -2.840214e-12 0.08881854 -0.9960478 -2.829388e-12 0.08881854 -0.9960478 -2.829388e-12 0.141252 -0.9899737 -2.812086e-12 0.141252 -0.9899737 -2.812086e-12 0.1791756 -0.9838171 -2.794564e-12 0.1791756 -0.9838171 -2.794564e-12 0.3707301 -0.9287406 -2.637938e-12 0.3707301 -0.9287406 -2.637938e-12 0.4711619 -0.8820467 -2.505206e-12 0.4711619 -0.8820467 -2.505206e-12 0.6457258 -0.7635693 -2.168493e-12 0.6457258 -0.7635693 -2.168493e-12 0.7928379 -0.6094325 -1.730507e-12 0.7928379 -0.6094325 -1.730507e-12 0.868427 -0.495817 -1.407693e-12 0.868427 -0.495817 -1.407693e-12 0.9545113 -0.2981747 -8.461755e-13 0.9545113 -0.2981747 -8.461755e-13 0.9982653 -0.05887643 -1.663635e-13 0.9982653 -0.05887643 -1.663635e-13 1 3.452941e-05 9.85984e-16 1 3.452941e-05 9.85984e-16 0.9954861 -0.09490707 -2.68718e-13 0.9954861 -0.09490707 -2.68718e-13 0.9670418 -0.2546176 -7.22432e-13 0.9670418 -0.2546176 -7.22432e-13 0.9382123 -0.3460601 -9.822177e-13 0.9382123 -0.3460601 -9.822177e-13 0.8397942 -0.5429048 -1.541481e-12 0.8397942 -0.5429048 -1.541481e-12 0.7760673 -0.6306502 -1.790795e-12 0.7760673 -0.6306502 -1.790795e-12 0.6352847 -0.7722781 -2.193241e-12 0.6352847 -0.7722781 -2.193241e-12 0.5045877 -0.8633605 -2.452094e-12 0.5045877 -0.8633605 -2.452094e-12 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 8.878965e-16 2.840694e-12 -1 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.048929e-15 5.330425e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 1 -1.19349e-15 5.372864e-16 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 -9.963787e-16 -0.7035131 0.2917309 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 4.511247e-16 0.3185256 -0.1320853 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 1 -1.191864e-15 5.412067e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 1 -1.19349e-15 2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 -1 1.19349e-15 -2.982953e-16 + + + + + + + + + + -5.5 -37.17344 58.51767 -4.7 -36.92277 58.94023 -4.7 -37.80053 57.00663 5.5 -37.17344 58.51767 4.7 -37.80053 57.00663 4.7 -36.92277 58.94023 5.5 -36.06841 60.03862 4.7 -35.53825 60.55031 5.5 -34.61985 61.23698 4.7 -33.75794 61.7078 5.5 -32.91877 62.03744 4.7 -31.72457 62.3199 5.5 -31.07207 62.38972 4.7 -29.60114 62.33755 5.5 -23.62782 57.66545 -5.5 -24.53352 59.31291 -5.5 -23.62782 57.66545 5.5 -38.10114 54.90452 4.7 -38.10114 54.90452 5.5 -37.86552 56.76969 5.5 -23.16028 55.84452 -5.5 -23.16028 55.84452 5.5 -23.16028 53.96452 -5.5 -23.16028 53.96452 5.5 -23.62782 52.14358 -5.5 -23.62782 52.14358 5.5 -24.53352 50.49613 -4.7 -38.10114 54.90452 -5.5 -38.10114 54.90452 -5.5 -37.86552 56.76969 -5.5 -24.53352 50.49613 5.5 -25.82046 49.12567 -5.5 -25.82046 49.12567 5.5 -27.4078 48.11831 -5.5 -27.4078 48.11831 5.5 -29.19578 47.53736 -5.5 -29.19578 47.53736 5.5 -31.07207 47.41932 -5.5 -31.07207 47.41932 5.5 -32.91877 47.77159 -5.5 -36.06841 60.03862 -5.5 -32.91877 47.77159 -4.7 -35.53825 60.55031 -5.5 -34.61985 61.23698 5.5 -34.61985 48.57206 4.7 -35.42205 49.15918 5.5 -36.06841 49.77041 -6.91939e-14 -35.42205 49.15918 -5.5 -34.61985 48.57206 4.7 -36.8673 50.7832 5.5 -37.17344 51.29136 -4.7 -33.75794 61.7078 -5.5 -32.91877 62.03744 -4.7 -35.42205 49.15918 5.5 -29.19578 62.27167 -5.5 -36.06841 49.77041 4.7 -37.78607 52.75349 5.5 -37.86552 53.03934 -6.704511e-14 -29.60114 62.33755 -4.7 -31.72457 62.3199 -5.5 -31.07207 62.38972 5.5 -27.4078 61.69072 -4.7 -36.8673 50.7832 -5.5 -37.17344 51.29136 -4.7 -29.60114 62.33755 -5.5 -29.19578 62.27167 -5.5 -27.4078 61.69072 -4.7 -37.78607 52.75349 -5.5 -37.86552 53.03934 5.5 -25.82046 60.68337 -5.5 -25.82046 60.68337 5.5 -24.53352 59.31291 5.5 38.042 53.96452 5.5 38.042 55.84452 4.7 38.06404 54.15945 4.7 38.00747 56.08617 5.5 23.33677 56.76969 5.5 23.10114 54.90452 -5.5 23.10114 54.90452 -4.7 37.4617 57.93483 -5.5 37.57447 57.66545 -4.7 38.00747 56.08617 5.5 24.02884 58.51767 -5.5 23.33677 56.76969 -5.5 38.042 55.84452 5.5 25.13388 60.03862 -5.5 24.02884 58.51767 5.5 37.57447 52.14358 4.7 37.62767 52.28194 5.5 26.58244 61.23698 -5.5 25.13388 60.03862 -4.7 38.06404 54.15945 -5.5 38.042 53.96452 5.5 28.28352 62.03744 -5.5 26.58244 61.23698 5.5 36.66877 50.49613 4.7 36.72718 50.57766 4.7 29.60114 62.33755 5.5 30.13022 62.38972 -4.7 37.62767 52.28194 3.612212e-15 29.60114 62.33755 -5.5 37.57447 52.14358 -5.5 28.28352 62.03744 5.5 35.38182 49.12567 4.7 35.42205 49.15918 4.7 31.52867 62.34694 5.5 32.0065 62.27167 -4.7 36.72718 50.57766 -4.7 29.60114 62.33755 -5.5 36.66877 50.49613 -5.5 30.13022 62.38972 4.7 33.39493 61.86474 1.535781e-14 35.42205 49.15918 5.5 33.79449 48.11831 5.5 33.79449 61.69072 -4.7 35.42205 49.15918 -5.5 35.38182 49.12567 -4.7 31.52867 62.34694 -5.5 32.0065 62.27167 4.7 35.07666 60.9228 5.5 32.0065 47.53736 -5.5 33.79449 48.11831 5.5 35.38182 60.68337 5.5 30.13022 47.41932 -5.5 32.0065 47.53736 -4.7 33.39493 61.86474 -5.5 33.79449 61.69072 -5.5 30.13022 47.41932 4.7 36.46276 59.58334 5.5 28.28352 47.77159 5.5 36.66877 59.31291 -5.5 28.28352 47.77159 5.5 26.58244 48.57206 -4.7 35.07666 60.9228 -5.5 35.38182 60.68337 -5.5 26.58244 48.57206 5.5 25.13388 49.77041 4.7 37.4617 57.93483 -5.5 25.13388 49.77041 5.5 24.02884 51.29136 5.5 37.57447 57.66545 -5.5 24.02884 51.29136 -4.7 36.46276 59.58334 5.5 23.33677 53.03934 -5.5 36.66877 59.31291 -5.5 23.33677 53.03934 -16.17267 -24.25543 -1.064921e-10 -15.4847 -24.29871 -1.064919e-10 -16.17267 -24.25543 29 -15.4847 -24.29871 29 -16.8498 -24.38459 -1.064923e-10 -16.8498 -24.38459 29 -17.47352 -24.6781 -1.064926e-10 -17.47352 -24.6781 29 -18.6636 -27.6839 -1.064935e-10 -18.75 -27 -1.064926e-10 -18.6636 -27.6839 29 -18.75 -27 29 -18.00466 -25.1175 -1.064928e-10 -18.00466 -25.1175 29 -18.40984 -28.32482 -1.064936e-10 -18.40984 -28.32482 29 -18.40984 -25.67518 -1.064931e-10 -18.40984 -25.67518 29 -18.00466 -28.8825 -1.064936e-10 -18.00466 -28.8825 29 -18.6636 -26.3161 -1.064933e-10 -18.6636 -26.3161 29 -17.47352 -29.3219 -1.064935e-10 -17.47352 -29.3219 29 -16.8498 -29.61541 -1.064934e-10 -16.8498 -29.61541 29 -16.17267 -29.74457 -1.064932e-10 -16.17267 -29.74457 29 -15.4847 -29.70129 -1.06493e-10 -15.4847 -29.70129 29 -14.82911 -29.48827 -1.064927e-10 -14.82911 -29.48827 29 -14.24708 -29.11891 -1.064925e-10 -14.24708 -29.11891 29 -13.7752 -28.61641 -1.064922e-10 -13.7752 -28.61641 29 -13.44311 -28.01234 -1.06492e-10 -13.44311 -28.01234 29 -13.27168 -27.34467 29 -13.27168 -27.34467 -1.064918e-10 -13.27168 -26.65533 29 -13.27168 -26.65533 -1.064917e-10 -13.44311 -25.98766 29 -13.44311 -25.98766 -1.064916e-10 -13.7752 -25.38359 -1.064916e-10 -13.7752 -25.38359 29 -14.24708 -24.88109 -1.064917e-10 -14.24708 -24.88109 29 -14.82911 -24.51173 -1.064918e-10 -14.82911 -24.51173 29 -16.17267 29.74457 -1.064921e-10 -15.4847 29.70129 -1.064919e-10 -16.17267 29.74457 29 -15.4847 29.70129 29 -16.8498 29.61541 -1.064923e-10 -16.8498 29.61541 29 -17.47352 29.3219 -1.064926e-10 -17.47352 29.3219 29 -18.6636 26.3161 -1.064935e-10 -18.75 27 -1.064926e-10 -18.6636 26.3161 29 -18.75 27 29 -18.00466 28.8825 -1.064928e-10 -18.00466 28.8825 29 -18.40984 25.67518 -1.064936e-10 -18.40984 25.67518 29 -18.40984 28.32482 -1.064931e-10 -18.40984 28.32482 29 -18.00466 25.1175 -1.064936e-10 -18.00466 25.1175 29 -18.6636 27.6839 -1.064933e-10 -18.6636 27.6839 29 -17.47352 24.6781 -1.064935e-10 -17.47352 24.6781 29 -16.8498 24.38459 -1.064934e-10 -16.8498 24.38459 29 -16.17267 24.25543 -1.064932e-10 -16.17267 24.25543 29 -15.4847 24.29871 -1.06493e-10 -15.4847 24.29871 29 -14.82911 24.51173 -1.064927e-10 -14.82911 24.51173 29 -14.24708 24.88109 -1.064925e-10 -14.24708 24.88109 29 -13.7752 25.38359 -1.064922e-10 -13.7752 25.38359 29 -13.44311 25.98766 -1.06492e-10 -13.44311 25.98766 29 -13.27168 26.65533 29 -13.27168 26.65533 -1.064918e-10 -13.27168 27.34467 29 -13.27168 27.34467 -1.064917e-10 -13.44311 28.01234 29 -13.44311 28.01234 -1.064916e-10 -13.7752 28.61641 -1.064916e-10 -13.7752 28.61641 29 -14.24708 29.11891 -1.064917e-10 -14.24708 29.11891 29 -14.82911 29.48827 -1.064918e-10 -14.82911 29.48827 29 18.00466 25.1175 7.135493e-11 17.47352 24.6781 7.010632e-11 17.47352 24.6781 29 16.8498 24.38459 29 18.6636 27.6839 7.864704e-11 18.75 27 7.670309e-11 18.75 27 29 18.40984 25.67518 7.293959e-11 18.00466 25.1175 29 18.6636 26.3161 7.476073e-11 18.40984 25.67518 29 18.40984 28.32482 8.046802e-11 18.6636 27.6839 29 18.6636 26.3161 29 18.00466 28.8825 8.205244e-11 18.40984 28.32482 29 17.47352 29.3219 8.330074e-11 18.00466 28.8825 29 16.8498 29.61541 8.413448e-11 17.47352 29.3219 29 16.17267 29.74457 8.450129e-11 16.8498 29.61541 29 16.17267 29.74457 29 15.4847 29.70129 8.43781e-11 15.4847 29.70129 29 14.82911 29.48827 8.377266e-11 14.24708 29.11891 8.272302e-11 14.82911 29.48827 29 14.24708 29.11891 29 13.7752 28.61641 8.129512e-11 13.7752 28.61641 29 13.44311 28.01234 7.957869e-11 13.44311 28.01234 29 13.27168 27.34467 7.768157e-11 13.27168 27.34467 29 13.27168 26.65533 29 13.27168 26.65533 7.572298e-11 13.44311 25.98766 7.382596e-11 13.44311 25.98766 29 13.7752 25.38359 7.210973e-11 13.7752 25.38359 29 14.24708 24.88109 7.068211e-11 14.82911 24.51173 6.963282e-11 14.24708 24.88109 29 15.4847 24.29871 6.902777e-11 14.82911 24.51173 29 16.17267 24.25543 6.890499e-11 15.4847 24.29871 29 16.8498 24.38459 6.92722e-11 16.17267 24.25543 29 16.8498 -29.61541 -8.411621e-11 16.17267 -29.74457 -8.448342e-11 16.8498 -29.61541 29 16.17267 -29.74457 29 17.47352 -29.3219 -8.32821e-11 17.47352 -29.3219 29 18.6636 -26.3161 -7.474138e-11 18.75 -27 -7.668532e-11 18.6636 -26.3161 29 18.75 -27 29 18.00466 -28.8825 -8.203348e-11 18.00466 -28.8825 29 18.40984 -25.67518 -7.292039e-11 18.40984 -25.67518 29 18.40984 -28.32482 -8.044882e-11 18.40984 -28.32482 29 18.00466 -25.1175 -7.133597e-11 18.00466 -25.1175 29 18.6636 -27.6839 -7.862768e-11 18.6636 -27.6839 29 17.47352 -24.6781 -7.008768e-11 17.47352 -24.6781 29 16.8498 -24.38459 -6.925393e-11 16.8498 -24.38459 29 16.17267 -24.25543 -6.888713e-11 16.17267 -24.25543 29 15.4847 -24.29871 -6.901031e-11 15.4847 -24.29871 29 14.82911 -24.51173 -6.961575e-11 14.82911 -24.51173 29 14.24708 -24.88109 -7.066539e-11 14.24708 -24.88109 29 13.7752 -25.38359 -7.209329e-11 13.7752 -25.38359 29 13.44311 -25.98766 -7.380972e-11 13.44311 -25.98766 29 13.27168 -26.65533 -7.570684e-11 13.27168 -26.65533 29 13.27168 -27.34467 29 13.27168 -27.34467 -7.766544e-11 13.44311 -28.01234 -7.956245e-11 13.44311 -28.01234 29 13.7752 -28.61641 -8.127869e-11 13.7752 -28.61641 29 14.24708 -29.11891 -8.27063e-11 14.24708 -29.11891 29 14.82911 -29.48827 -8.37556e-11 14.82911 -29.48827 29 15.4847 -29.70129 -8.436064e-11 15.4847 -29.70129 29 10.3 33.21497 38.28691 9.5 33.21497 38.28691 9.5 33.03484 38.18819 10.3 33.03484 38.18819 9.5 32.88764 38.04491 10.3 32.88764 38.04491 9.5 32.78409 37.86752 10.3 32.78409 37.86752 9.5 32.73172 37.6689 10.3 32.73172 37.6689 9.5 32.73433 37.4635 10.3 32.73433 37.4635 9.5 32.79173 37.26628 10.3 32.79173 37.26628 9.5 30.66207 39.98954 9.5 30.74045 39.94175 10.3 30.74045 39.94175 9.5 30.57385 40.01496 10.3 30.66207 39.98954 9.5 30.48205 40.0162 10.3 30.57385 40.01496 9.5 30.39317 39.99317 10.3 30.48205 40.0162 9.5 30.31353 39.94751 10.3 30.39317 39.99317 9.5 30.24875 39.88245 10.3 30.31353 39.94751 9.5 30.20344 39.8026 10.3 30.24875 39.88245 9.5 30.18081 39.71362 10.3 30.20344 39.8026 9.5 30.18246 39.62183 10.3 30.18081 39.71362 9.5 30.20827 39.53372 10.3 30.18246 39.62183 10.3 30.20827 39.53372 9.5 29.70445 38.4691 9.5 29.78503 38.51309 10.3 29.78503 38.51309 9.5 29.63832 38.40541 10.3 29.70445 38.4691 9.5 29.59135 38.32653 10.3 29.63832 38.40541 9.5 29.56686 38.23805 10.3 29.59135 38.32653 9.5 29.56658 38.14624 10.3 29.56686 38.23805 9.5 29.59054 38.05761 10.3 29.56658 38.14624 9.5 29.63704 37.97845 10.3 29.59054 38.05761 9.5 29.70278 37.91436 10.3 29.63704 37.97845 9.5 29.78309 37.86989 10.3 29.70278 37.91436 9.5 29.8723 37.84819 10.3 29.78309 37.86989 10.3 29.8723 37.84819 10.16469 30.5843 40.37424 10.3 30.75448 40.20186 10.3 31.24624 40.33342 9.527993 28.78387 39.52267 10.3 29.56678 38.65529 10.3 29.69873 39.14695 10.3 29.95343 39.5877 9.197723 28.28506 38.31979 8.1 27.90536 39.63231 9.292026 31.05583 41.51136 9.845689 32.4983 40.80742 8.1 32.50417 42.06492 8.1 31.56119 42.19951 8.1 30.61437 42.09536 10.3 31.75529 40.33322 9.200915 29.28299 40.7263 8.294798 29.66292 41.64251 8.1 29.7232 41.75901 8.1 28.94366 41.21161 8.873793 34.83763 37.58617 8.1 35.22074 37.62794 8.1 35.29585 38.5775 8.1 34.91184 36.72688 9.527993 34.21355 37.27111 9.200915 34.71267 38.47474 9.355516 31.32921 35.31359 8.1 30.96309 34.63812 9.285391 31.94181 35.28297 10.3 31.75376 36.46658 9.36566 31.02297 35.35447 10.3 31.24471 36.46678 8.746905 30.15568 35.15815 9.539227 30.84219 35.54637 9.839292 30.49882 35.98565 9.539227 29.94536 35.91826 10.3 30.3123 36.85343 9.36566 29.68182 35.91061 10.3 29.95249 37.21353 8.1 29.2172 35.3621 9.355516 29.43652 36.09844 9.285391 28.98202 36.51033 8.873793 28.56588 40.18692 8.1 28.32476 40.48754 9.197723 33.71474 36.06822 8.1 34.38857 35.93095 8.1 33.68379 35.29017 8.1 32.8418 34.84478 10.3 33.04657 37.2123 10.3 32.68647 36.85249 8.1 31.9155 34.62278 10.3 33.43322 38.14471 10.3 33.30127 37.65305 10.16107 32.41253 36.4181 10.3 32.24552 36.59814 8.1 30.04441 34.88983 10.3 33.43342 38.65376 10.3 30.75305 36.59873 8.294798 35.0926 39.39094 8.1 35.13246 39.51592 8.1 34.74082 40.38421 10.16469 33.54409 39.14688 10.3 33.04751 39.58647 10.3 33.30186 39.14552 8.1 28.53342 36.02525 8.1 28.03605 36.83762 9.292026 34.01563 40.284 8.1 34.14555 41.12783 8.1 33.38405 41.70005 10.3 32.6877 39.94657 10.16107 29.45273 37.64546 10.3 29.69814 37.65448 10.3 32.24695 40.20127 8.1 27.75633 37.74815 8.1 27.71183 38.69964 8.7555 32.84247 41.63739 11 7.232735 56.2859 12 7.232735 56.2859 12 6.1277 57.80685 11 8.681299 55.08754 11 5.2 61.42 12 5.2 61.42 12 5.435626 63.28517 11 6.1277 57.80685 12 5.435626 59.55483 11 5.435626 63.28517 12 6.1277 65.03315 11 5.435626 59.55483 11 6.1277 65.03315 12 7.232735 66.5541 11 7.232735 66.5541 12 8.681299 67.75246 11 8.681299 67.75246 12 10.38237 68.55292 11 10.38237 68.55292 12 12.22907 68.9052 11 12.22907 68.9052 12 14.10536 68.78715 11 14.10536 68.78715 12 15.89334 68.2062 11 15.89334 68.2062 12 17.48068 67.19885 11 17.48068 67.19885 12 18.76763 65.82839 11 18.76763 65.82839 12 19.67332 64.18093 11 19.67332 64.18093 12 20.14086 62.36 11 20.14086 62.36 12 20.14086 60.48 11 20.14086 60.48 12 19.67332 58.65907 11 19.67332 58.65907 12 18.76763 57.01161 11 18.76763 57.01161 12 17.48068 55.64115 11 17.48068 55.64115 12 15.89334 54.6338 11 15.89334 54.6338 12 14.10536 54.05285 11 14.10536 54.05285 12 12.22907 53.9348 11 12.22907 53.9348 12 10.38237 54.28708 11 10.38237 54.28708 12 8.681299 55.08754 11 -13.17093 53.9348 11 -11.29464 54.05285 12 -11.29464 54.05285 11 -15.01763 54.28708 12 -13.17093 53.9348 12 -15.01763 54.28708 11 -16.7187 55.08754 12 -16.7187 55.08754 11 -19.96437 63.28517 12 -20.2 61.42 12 -19.96437 63.28517 11 -20.2 61.42 11 -18.16726 56.2859 12 -18.16726 56.2859 11 -19.2723 65.03315 12 -19.2723 65.03315 11 -19.2723 57.80685 12 -19.2723 57.80685 11 -18.16726 66.5541 12 -18.16726 66.5541 11 -19.96437 59.55483 12 -19.96437 59.55483 11 -16.7187 67.75246 12 -16.7187 67.75246 11 -15.01763 68.55292 12 -15.01763 68.55292 11 -13.17093 68.9052 12 -13.17093 68.9052 11 -11.29464 68.78715 12 -11.29464 68.78715 11 -9.506655 68.2062 12 -9.506655 68.2062 11 -7.91932 67.19885 12 -7.91932 67.19885 11 -6.632373 65.82839 12 -6.632373 65.82839 11 -5.726676 64.18093 12 -5.726676 64.18093 11 -5.25914 62.36 12 -5.25914 62.36 11 -5.25914 60.48 12 -5.25914 60.48 11 -5.726676 58.65907 12 -5.726676 58.65907 11 -6.632373 57.01161 12 -6.632373 57.01161 11 -7.91932 55.64115 12 -7.91932 55.64115 11 -9.506655 54.6338 12 -9.506655 54.6338 -10.3 -30.00109 38.00774 -9.5 -29.87252 37.84754 -9.5 -30.00109 38.00774 -10.3 -29.87252 37.84754 -10.3 -30.08218 38.19647 -9.5 -30.08218 38.19647 -10.3 -30.10988 38.4 -9.5 -30.10988 38.4 -10.3 -30.08218 38.60353 -9.5 -30.08218 38.60353 -10.3 -30.00109 38.79226 -9.5 -30.00109 38.79226 -10.3 -29.87252 38.95246 -9.5 -29.87252 38.95246 -9.5 -32.8829 37.25266 -9.5 -32.79218 37.26679 -10.3 -32.79218 37.26679 -9.5 -32.97412 37.26298 -10.3 -32.8829 37.25266 -9.5 -33.0594 37.29699 -10.3 -32.97412 37.26298 -9.5 -33.13267 37.35231 -10.3 -33.0594 37.29699 -9.5 -33.18875 37.425 -10.3 -33.13267 37.35231 -9.5 -33.22366 37.50991 -10.3 -33.18875 37.425 -9.5 -33.23493 37.60103 -10.3 -33.22366 37.50991 -9.5 -33.22175 37.69188 -10.3 -33.23493 37.60103 -9.5 -33.18507 37.77605 -10.3 -33.22175 37.69188 -9.5 -33.12748 37.84754 -10.3 -33.18507 37.77605 -10.3 -33.12748 37.84754 -9.5 -33.12748 38.95246 -10.3 -33.12748 38.95246 -10.3 -33.18507 39.02395 -9.5 -33.18507 39.02395 -9.5 -33.22175 39.10812 -10.3 -33.22175 39.10812 -9.5 -33.23493 39.19897 -10.3 -33.23493 39.19897 -9.5 -33.22366 39.29009 -10.3 -33.22366 39.29009 -9.5 -33.18875 39.375 -10.3 -33.18875 39.375 -9.5 -33.13267 39.44769 -10.3 -33.13267 39.44769 -9.5 -33.0594 39.50301 -10.3 -33.0594 39.50301 -9.5 -32.97412 39.53702 -10.3 -32.97412 39.53702 -9.5 -32.8829 39.54734 -10.3 -32.8829 39.54734 -9.5 -32.79218 39.53321 -10.3 -32.79218 39.53321 -10.16469 -33.10209 36.9271 -10.3 -32.87886 37.02114 -10.3 -32.475 36.71125 -9.527993 -34.439 38.40336 -10.3 -33.38356 38.9047 -10.3 -33.45 38.4 -10.3 -33.38356 37.8953 -9.197723 -34.439 39.70557 -8.1 -35.2925 38.6386 -9.292026 -33.10209 35.69609 -9.845689 -31.5 35.7938 -8.1 -31.97627 34.62996 -8.1 -32.89887 34.86685 -8.1 -33.73358 35.32574 -10.3 -32.0047 36.51644 -9.200915 -34.439 37.10035 -8.294798 -34.439 36.1085 -8.1 -34.42795 35.97779 -8.1 -34.93834 36.78204 -8.873793 -28.1052 37.87328 -8.1 -27.76731 37.68795 -8.1 -28.06166 36.78204 -8.1 -27.7075 38.6386 -9.527993 -28.561 38.40336 -9.200915 -28.561 37.10035 -9.355516 -30.47552 41.31643 -8.1 -30.55498 42.08062 -9.285391 -29.89791 41.11005 -10.3 -30.525 40.08875 -9.36566 -30.77406 41.39597 -10.3 -30.9953 40.28356 -8.746905 -31.5 41.90953 -9.539227 -31.01456 41.28795 -9.839292 -31.5 41.0137 -9.539227 -31.98544 41.28795 -10.3 -32.0047 40.28356 -9.36566 -32.22594 41.39597 -8.1 -32.44502 42.08062 -10.3 -32.475 40.08875 -9.355516 -32.52448 41.31643 -9.285391 -33.10209 41.11005 -8.873793 -34.8948 37.87328 -8.1 -35.23269 37.68795 -9.197723 -28.561 39.70557 -8.1 -27.88599 39.57426 -8.1 -28.29155 40.43614 -8.1 -28.89872 41.17008 -10.3 -29.61644 38.9047 -10.3 -29.81125 39.375 -8.1 -29.66934 41.72997 -10.3 -29.61644 37.8953 -10.3 -29.55 38.4 -10.16107 -29.89791 39.88119 -10.3 -30.12114 39.77886 -8.1 -31.5 42.2 -10.3 -29.81125 37.425 -10.3 -31.5 40.35 -8.294798 -28.561 36.1085 -8.1 -28.57205 35.97779 -8.1 -29.26642 35.32574 -10.16469 -29.89791 36.9271 -10.3 -30.525 36.71125 -10.3 -30.12114 37.02114 -8.1 -33.33066 41.72997 -8.1 -34.10128 41.17008 -9.292026 -29.89791 35.69609 -8.1 -30.10113 34.86685 -8.1 -31.02373 34.62996 -10.3 -30.9953 36.51644 -10.16107 -33.10209 39.88119 -10.3 -32.87886 39.77886 -10.3 -31.5 36.45 -8.1 -34.70845 40.43614 -8.1 -35.11401 39.57426 -8.7555 -31.5 34.8953 -10.3 33.12748 37.84754 -9.5 33.12748 37.84754 -9.5 32.99891 38.00774 -10.3 32.99891 38.00774 -9.5 32.91782 38.19647 -10.3 32.91782 38.19647 -9.5 32.89012 38.4 -10.3 32.89012 38.4 -9.5 32.91782 38.60353 -10.3 32.91782 38.60353 -9.5 32.99891 38.79226 -10.3 32.99891 38.79226 -9.5 33.12748 38.95246 -10.3 33.12748 38.95246 -9.5 30.1171 37.25266 -9.5 30.20782 37.26679 -10.3 30.20782 37.26679 -9.5 30.02588 37.26298 -10.3 30.1171 37.25266 -9.5 29.9406 37.29699 -10.3 30.02588 37.26298 -9.5 29.86733 37.35231 -10.3 29.9406 37.29699 -9.5 29.81125 37.425 -10.3 29.86733 37.35231 -9.5 29.77634 37.50991 -10.3 29.81125 37.425 -9.5 29.76507 37.60103 -10.3 29.77634 37.50991 -9.5 29.77825 37.69188 -10.3 29.76507 37.60103 -9.5 29.81493 37.77605 -10.3 29.77825 37.69188 -9.5 29.87252 37.84754 -10.3 29.81493 37.77605 -10.3 29.87252 37.84754 -9.5 29.87252 38.95246 -10.3 29.87252 38.95246 -10.3 29.81493 39.02395 -9.5 29.81493 39.02395 -9.5 29.77825 39.10812 -10.3 29.77825 39.10812 -9.5 29.76507 39.19897 -10.3 29.76507 39.19897 -9.5 29.77634 39.29009 -10.3 29.77634 39.29009 -9.5 29.81125 39.375 -10.3 29.81125 39.375 -9.5 29.86733 39.44769 -10.3 29.86733 39.44769 -9.5 29.9406 39.50301 -10.3 29.9406 39.50301 -9.5 30.02588 39.53702 -10.3 30.02588 39.53702 -9.5 30.1171 39.54734 -10.3 30.1171 39.54734 -9.5 30.20782 39.53321 -10.3 30.20782 39.53321 -10.16469 29.89791 36.9271 -10.3 30.12114 37.02114 -10.3 30.525 36.71125 -9.527993 28.561 38.40336 -10.3 29.61644 38.9047 -10.3 29.55 38.4 -10.3 29.61644 37.8953 -9.197723 28.561 39.70557 -8.1 27.7075 38.6386 -9.292026 29.89791 35.69609 -9.845689 31.5 35.7938 -8.1 31.02373 34.62996 -8.1 30.10113 34.86685 -8.1 29.26642 35.32574 -10.3 30.9953 36.51644 -9.200915 28.561 37.10035 -8.294798 28.561 36.1085 -8.1 28.57205 35.97779 -8.1 28.06166 36.78204 -8.873793 34.8948 37.87328 -9.200915 34.439 37.10035 -9.527993 34.439 38.40336 -8.1 35.23269 37.68795 -8.1 34.93834 36.78204 -8.1 35.2925 38.6386 -9.355516 32.52448 41.31643 -8.1 32.44502 42.08062 -9.285391 33.10209 41.11005 -10.3 32.475 40.08875 -9.36566 32.22594 41.39597 -10.3 32.0047 40.28356 -8.746905 31.5 41.90953 -9.539227 31.98544 41.28795 -9.839292 31.5 41.0137 -9.539227 31.01456 41.28795 -10.3 30.9953 40.28356 -9.36566 30.77406 41.39597 -8.1 30.55498 42.08062 -10.3 30.525 40.08875 -9.355516 30.47552 41.31643 -9.285391 29.89791 41.11005 -8.873793 28.1052 37.87328 -8.1 27.76731 37.68795 -9.197723 34.439 39.70557 -8.1 35.11401 39.57426 -8.1 34.70845 40.43614 -8.1 34.10128 41.17008 -10.3 33.38356 38.9047 -10.3 33.18875 39.375 -8.1 33.33066 41.72997 -10.3 33.38356 37.8953 -10.3 33.45 38.4 -10.16107 33.10209 39.88119 -10.3 32.87886 39.77886 -8.1 31.5 42.2 -10.3 33.18875 37.425 -10.3 31.5 40.35 -8.294798 34.439 36.1085 -8.1 34.42795 35.97779 -8.1 33.73358 35.32574 -10.16469 33.10209 36.9271 -10.3 32.475 36.71125 -10.3 32.87886 37.02114 -8.1 29.66934 41.72997 -8.1 28.89872 41.17008 -9.292026 33.10209 35.69609 -8.1 32.89887 34.86685 -8.1 31.97627 34.62996 -10.3 32.0047 36.51644 -10.16107 29.89791 39.88119 -10.3 30.12114 39.77886 -10.3 31.5 36.45 -8.1 28.29155 40.43614 -8.1 27.88599 39.57426 -8.7555 31.5 34.8953 -11 -27 38.4 -11 -27 42.65 -11.04911 -26.30729 41.86903 -20.84292 -28.24345 29 -21 -27 29 -20.88402 -28.07085 35.00918 -21 -27 35.5166 -11.35112 -25.15938 29 -11.03943 -26.37333 29 -11.20125 -25.59825 41.06693 -20.38153 -29.40877 29 -20.56082 -29.04911 34.49017 -11.95492 -24.06107 29 -11.66149 -24.51564 39.82929 -12.81288 -23.14743 29 -12.18363 -23.77072 38.95925 -19.64484 -30.42274 29 -20.06227 -29.91513 34.02551 -19.47607 -30.59402 33.72847 -12.84516 -23.12114 38.17485 -13.8711 -22.47586 29 -13.59342 -22.61803 37.5313 -18.67913 -31.22164 29 -18.95554 -31.03296 33.63365 -18.41987 -31.37541 33.66804 -15.06309 -22.08856 29 -14.25598 -22.31409 37.10485 -17.54508 -31.75528 29 -18.0359 -31.56674 33.76181 -14.98677 -22.10496 36.75743 -16.31395 -22.00987 29 -15.75601 -22.00619 36.50356 -17.65 -31.71991 33.90538 -17.01436 -31.89533 33.91688 -17.54508 -22.24472 29 -16.54423 -22.03009 36.35173 -16.31395 -31.99013 29 -16.37193 -31.98577 33.92602 -17.35 -22.1857 36.3 -18.67913 -22.77836 29 -18.33232 -22.5773 36.3 -15.06309 -31.91144 29 -15.49391 -31.97349 33.92436 -13.8711 -31.52414 29 -14.60591 -31.80081 33.9094 -19.64484 -23.57726 29 -19.21031 -23.16673 36.3 -13.75399 -31.46662 33.90022 -20.38153 -24.59123 29 -19.94469 -23.92764 36.3 -12.81288 -30.85257 29 -12.98593 -30.98792 33.92952 -20.29714 -24.44371 36.26945 -20.84292 -25.75655 29 -20.57984 -24.99366 36.18047 -11.95492 -29.93893 29 -12.33696 -30.40299 34.03584 -11.79124 -29.69927 34.27604 -11.35112 -28.84062 29 -20.88587 -25.93774 35.92442 -11.4066 -28.975 34.67518 -11.03943 -27.62667 29 -11.179 -28.32574 35.21042 -11.05928 -27.76769 35.8863 -11.01136 -27.34599 36.67153 -10.99925 -27.08753 37.52585 -13.8711 31.52414 29 -12.81288 30.85257 29 -13.10236 31.07312 33.92061 -12.32048 30.3851 34.04039 -14.15651 31.64771 33.9024 -20.84292 25.75655 29 -21 27 29 -20.9464 26.26931 35.80909 -21 27 35.5166 -15.06309 31.91144 29 -15.31838 31.95216 33.92191 -20.38153 24.59123 29 -20.7809 25.53608 36.0474 -16.31395 31.99013 29 -16.48123 31.97626 33.92488 -20.44059 24.70184 36.23407 -17.54508 31.75528 29 -17.64974 31.72 33.90537 -19.64484 23.57726 29 -19.94469 23.92764 36.3 -18.67913 31.22164 29 -18.32162 31.42833 33.68665 -18.67913 22.77836 29 -19.21031 23.16673 36.3 -18.84889 31.109 33.6303 -17.54508 22.24472 29 -18.33232 22.5773 36.3 -19.64484 30.42274 29 -19.29887 30.75732 33.6802 -17.35 22.1857 36.3 -19.6973 30.36597 33.81379 -16.31395 22.00987 29 -16.64241 22.04186 36.33997 -19.88798 30.1438 33.91245 -20.38153 29.40877 29 -20.06227 29.91513 34.02551 -15.06309 22.08856 29 -15.9459 22.00031 36.4572 -20.84292 28.24345 29 -20.56347 29.04322 34.49355 -14.98304 22.10574 36.75893 -13.8711 22.47586 29 -20.88454 28.06844 35.01049 -13.98648 22.42346 37.26411 -12.81288 23.14743 29 -12.9607 23.03024 38.0618 -12.03497 23.95537 39.17707 -11.95492 24.06107 29 -11.35112 25.15938 29 -11.03943 26.37333 29 -11.30492 25.28129 40.70667 -10.99907 27.06163 37.66715 -11.03943 27.62667 29 -11.00472 27.2441 36.94254 -11 27 38.4 -11.03099 27.5558 36.2336 -11.0974 27.98209 35.594 -11 27 42.65 -11.35112 28.84062 29 -11.22988 28.49836 35.04755 -11.45039 29.07365 34.61035 -11.95492 29.93893 29 -11.79573 29.70628 34.27298 -8.1 -31.78256 33.90888 -8.1 -30.65678 33.97971 -8.1 -36 38.4 -8.987208 -36 38.4 -8.946625 -35.99763 38.54597 -8.885025 -35.95841 39.01039 -8.1 -35.85862 39.5191 -8.1 -32.89058 34.12025 -8.920232 -35.87017 39.47312 -9.031089 -35.73698 39.91562 -8.1 -35.44338 40.56789 -9.256185 -35.49898 40.46351 -9.564111 -35.16081 41.01696 -8.1 -34.78036 41.48046 -9.961897 -34.66003 41.60378 -8.1 -33.91122 42.19948 -10.34397 -34.05768 42.10247 -8.1 -32.89058 42.67975 -10.69971 -33.2487 42.54641 -10.90939 -32.42348 42.80427 -8.1 -31.78256 42.89112 -10.97748 -31.8931 42.88286 -16.336 -32.57905 34.03125 -11 -31.35102 42.89753 -8.1 -30.65678 42.82029 -8.1 -33.91122 34.60052 -14.99387 -33.3726 34.30813 -11 -30.21583 42.71288 -8.1 -34.78036 35.31954 -12.81235 -34.52384 35.06737 -8.1 -29.58399 42.47172 -8.1 -28.63159 41.86731 -11 -29.16452 42.2465 -8.1 -35.44338 36.23211 -11.30069 -35.21851 35.86596 -10.20217 -35.65795 36.67914 -8.1 -27.85942 41.04503 -11 -28.26578 41.52886 -8.1 -35.85862 37.2809 -9.612331 -35.8597 37.2851 -8.1 -27.31601 40.05656 -11 -27.57829 40.60685 -9.246259 -35.9612 37.81033 -8.1 -27.03548 38.964 -11 -27.14697 39.54068 -8.1 -27.03548 37.836 -8.1 -27.31601 36.74344 -8.1 -27.85942 35.75497 -8.1 -28.63159 34.93269 -8.1 -29.58399 34.32828 -8.1 34.36841 34.93269 -8.1 35.14058 35.75497 -12.29946 34.76983 35.30837 -11.00709 35.34213 36.05765 -8.1 27 38.4 -8.1 27.14138 39.5191 -11 27.14697 39.54068 -8.1 33.41601 34.32828 -14.46358 33.66771 34.45652 -8.1 27.55662 40.56789 -11 27.57829 40.60685 -8.1 32.34322 33.97971 -16.06796 32.74298 34.07507 -8.1 28.21964 41.48046 -11 28.26578 41.52886 -8.1 29.08878 42.19948 -8.1 31.21744 33.90888 -11 29.16452 42.2465 -8.1 30.10942 42.67975 -11 30.21583 42.71288 -8.1 31.21744 42.89112 -11 31.35102 42.89753 -8.1 32.34322 42.82029 -10.93947 32.23225 42.84009 -8.1 30.10942 34.12025 -8.1 33.41601 42.47172 -10.75622 33.07242 42.61638 -8.1 29.08878 34.60052 -10.57138 33.58701 42.38687 -10.34397 34.05768 42.10247 -8.1 34.36841 41.86731 -8.1 28.21964 35.31954 -8.1 35.14058 41.04503 -9.735082 34.95671 41.28117 -9.205609 35.55215 40.35693 -8.1 35.68399 40.05656 -8.1 27.55662 36.23211 -8.956006 35.82341 39.64824 -8.1 35.96452 38.964 -8.1 27.14138 37.2809 -8.8857 35.94007 39.13197 -8.89593 35.97869 38.83753 -8.946625 35.99763 38.54597 -8.959222 35.99895 38.49706 -8.972754 35.99974 38.4484 -8.1 35.96452 37.836 -8.987216 36 38.4 -9.24528 35.96143 37.81206 -9.60969 35.86052 37.28831 -8.1 35.68399 36.74344 -10.19867 35.65921 36.68223 -36.96419 5.209324 31.41179 -36.85704 5.920022 31.41179 -37.13306 5.233124 29.95 -30.41306 11.10223 36.1805 -29.58314 9.755029 36.3 -28.71342 12.07735 36.3 -29.84363 12.55273 36.1805 -30.96999 13.0265 35.80914 -31.5609 11.52125 35.80914 -31.90806 10.52167 35.80914 -35.22818 7.509002 34.02551 -35.78113 8.714207 32.79506 -36.01785 7.677323 32.79506 -34.99665 8.523153 34.02551 -36.36093 5.840336 32.79506 -33.99383 8.278925 35.0093 -33.62474 9.669443 35.0093 -30.74759 10.13901 36.1805 -32.28947 9.285461 35.80914 -33.22755 10.95677 35.0093 -36.46663 5.139204 32.79506 -34.21873 7.293834 35.0093 -37.21116 2.969421 31.41179 -37.40815 2.622986 29.95 -35.56374 5.71229 34.02551 -31.11513 8.947756 36.1805 -30.26537 7.370887 36.3 -32.64391 7.950161 35.80914 -35.66712 5.02653 34.02551 -36.71028 2.929451 32.79506 -32.85987 7.004189 35.80914 -34.54467 5.548606 35.0093 -31.45667 7.66102 36.1805 -34.64509 4.882496 35.0093 -37.32946 -8.771979e-12 31.41179 -37.5 -8.813983e-12 29.95 -31.66478 6.749452 36.1805 -30.75579 4.940032 36.3 -35.90543 2.865224 34.02551 -33.17287 5.328266 35.80914 -33.26931 4.688608 35.80914 -36.82698 -8.772847e-12 32.79506 -34.87657 2.783122 35.0093 -31.9664 5.134481 36.1805 -37.23803 -2.611057 31.41179 -37.40815 -2.622986 29.95 -37.13306 -5.233124 29.95 -32.05933 4.518087 36.1805 -31.05129 2.477868 36.3 -36.01957 -8.77405e-12 34.02551 -33.4916 2.672602 35.80914 -36.73679 -2.575911 32.79506 -34.98744 -8.775473e-12 35.0093 -32.27353 2.575402 36.1805 -36.96419 -5.209324 31.41179 -35.93135 -2.519436 34.02551 -36.85704 -5.920022 31.41179 -36.67608 -7.817627 29.95 -33.59806 -8.777286e-12 35.80914 -36.46663 -5.139204 32.79506 -34.90175 -2.447242 35.0093 -36.36093 -5.840336 32.79506 -36.50928 -7.782073 31.41179 -32.37613 -8.778817e-12 36.1805 -31.15 -3.887411e-11 36.3 -35.66712 -5.02653 34.02551 -36.26933 -8.833105 31.41179 -36.03944 -10.36384 29.95 -33.51577 -2.35006 35.80914 -35.56374 -5.71229 34.02551 -36.01785 -7.677323 32.79506 -34.64509 -4.882496 35.0093 -35.87553 -10.3167 31.41179 -32.29683 -2.26459 36.1805 -31.05129 -2.477868 36.3 -35.78113 -8.714207 32.79506 -34.54467 -5.548606 35.0093 -35.22818 -7.509002 34.02551 -33.26931 -4.688608 35.80914 -35.45176 -11.69021 31.41179 -35.22625 -12.85928 29.95 -35.39263 -10.17783 32.79506 -34.99665 -8.523153 34.02551 -33.17287 -5.328266 35.80914 -34.21873 -7.293834 35.0093 -35.06605 -12.80079 31.41179 -32.05933 -4.518087 36.1805 -30.75579 -4.940032 36.3 -22.28362 29.94877 31.41179 -20.88684 31.14466 29.95 -23.01413 29.60742 29.95 -34.97456 -11.53285 32.79506 -20.79185 31.00302 31.41179 -34.61667 -9.954691 34.02551 -22.90947 29.47277 31.41179 -21.98367 29.54564 32.79506 -33.99383 -8.278925 35.0093 -31.9664 -5.134481 36.1805 -20.51198 30.58571 32.79506 -32.85987 -7.004189 35.80914 -23.56209 28.95369 31.41179 -25.0287 27.92516 29.95 -22.6011 29.07606 32.79506 -34.59404 -12.62849 32.79506 -21.50169 28.89787 34.02551 -34.40951 -14.47322 31.41179 -34.24052 -15.29173 29.95 -34.20777 -11.28 34.02551 -23.24494 28.56396 32.79506 -33.62474 -9.669443 35.0093 -32.64391 -7.950161 35.80914 -24.91487 27.79816 31.41179 -22.10558 28.43858 34.02551 -34.0848 -15.22218 31.41179 -20.88556 28.06981 35.0093 -31.66478 -6.749452 36.1805 -30.26537 -7.370887 36.3 -22.7353 27.93771 34.02551 -33.83559 -12.35162 34.02551 -24.5795 27.42398 32.79506 -33.94634 -14.2784 32.79506 -26.10647 26.68222 31.41179 -26.92066 26.1061 29.95 -33.22755 -10.95677 35.0093 -21.47215 27.62368 35.0093 -31.45667 -7.66102 36.1805 -32.28947 -9.285461 35.80914 -26.79823 25.98737 31.41179 -22.08383 27.13716 35.0093 -33.626 -15.01728 32.79506 -32.86604 -11.99769 35.0093 -24.04061 26.82272 34.02551 -33.14918 -17.16451 31.41179 -33.08706 -17.64927 29.95 -25.75506 26.32306 32.79506 -33.20209 -13.96536 34.02551 -26.43751 25.63757 32.79506 -31.11513 -8.947756 36.1805 -29.58314 -9.755029 36.3 -28.14621 24.52099 31.41179 -31.90806 -10.52167 35.80914 -28.68075 24.15915 29.95 -32.88877 -14.68804 34.02551 -21.20686 26.05952 35.80914 -23.35174 26.05413 35.0093 -32.70297 -16.93346 32.79506 -25.1904 25.74594 34.02551 -31.5609 -11.52125 35.80914 -32.25069 -13.56518 35.0093 -25.85788 25.07548 34.02551 -27.76735 24.19093 32.79506 -30.74759 -10.13901 36.1805 -24.46857 25.0082 35.0093 -31.94635 -14.26716 35.0093 -22.42442 25.0195 35.80914 -31.67876 -19.74701 31.41179 -31.77152 -19.92036 29.95 -25.11693 24.35695 35.0093 -30.41306 -11.10223 36.1805 -28.71342 -12.07735 36.3 -30.00757 22.20436 31.41179 -31.98598 -16.56221 34.02551 -30.30034 22.09387 29.95 -27.15857 23.66056 34.02551 -30.96999 -13.0265 35.80914 -21.60886 24.10956 36.1805 -21.78484 22.26529 36.3 -23.4969 24.0151 35.80914 -30.67773 -13.7006 35.80914 -31.25235 -19.4812 32.79506 -24.11952 23.38971 35.80914 -31.06943 -16.08762 35.0093 -29.84363 -12.55273 36.1805 -29.60366 21.90548 32.79506 -26.38035 22.98257 35.0093 -30.16254 -21.99339 31.41179 -30.30034 -22.09387 29.95 -28.68075 -24.15915 29.95 -22.64234 23.14169 36.1805 -29.56201 -13.20232 36.1805 -27.66172 -14.32312 36.3 -31.62702 19.82977 31.41179 -31.77152 19.92036 29.95 -33.08706 17.64927 29.95 -30.56716 -19.05409 34.02551 -23.24231 22.53905 36.1805 -23.48693 20.46183 36.3 -29.83564 -15.44877 35.80914 -28.95462 21.42522 34.02551 -29.75654 -21.69735 32.79506 -25.33276 22.06991 35.80914 -29.69127 -18.5081 35.0093 -31.20131 19.56285 32.79506 -28.75054 -14.88691 36.1805 -28.12493 20.81128 35.0093 -28.55031 -24.04928 31.41179 -24.41143 21.26725 36.1805 -29.10415 -21.22165 34.02551 -32.93658 17.56901 31.41179 -34.24052 15.29173 29.95 -28.5122 -17.77313 35.80914 -30.51724 19.13394 34.02551 -28.16601 -23.72557 32.79506 -27.00806 19.98485 35.80914 -32.49324 17.33252 32.79506 -28.27018 -20.61355 35.0093 -27.47523 -17.12673 36.1805 -29.64278 18.58567 35.0093 -26.43471 -16.47812 36.3 -26.79823 -25.98737 31.41179 -26.92066 -26.1061 29.95 -26.0258 19.25802 36.1805 -25.04017 18.52869 36.3 -27.54849 -23.2054 34.02551 -34.0848 15.22218 31.41179 -26.10647 -26.68222 31.41179 -25.0287 -27.92516 29.95 -31.78084 16.95251 34.02551 -34.40951 14.47322 31.41179 -35.22625 12.85928 29.95 -27.14754 -19.79497 35.80914 -26.43751 -25.63757 32.79506 -28.46564 17.84761 35.80914 -33.626 15.01728 32.79506 -26.75909 -22.54046 35.0093 -30.87017 16.46674 35.0093 -25.75506 -26.32306 32.79506 -33.94634 14.2784 32.79506 -24.91487 -27.79816 31.41179 -26.16021 -19.07504 36.1805 -35.06605 12.80079 31.41179 -27.43036 17.19851 36.1805 -25.04017 -18.52869 36.3 -26.43471 16.47812 36.3 -25.85788 -25.07548 34.02551 -32.88877 14.68804 34.02551 -35.45176 11.69021 31.41179 -25.69647 -21.64535 35.80914 -36.03944 10.36384 29.95 -23.90127 -28.67434 31.41179 -23.01413 -29.60742 29.95 -29.64429 15.81284 35.80914 -25.1904 -25.74594 34.02551 -33.20209 13.96536 34.02551 -34.59404 12.62849 32.79506 -24.5795 -27.42398 32.79506 -31.94635 14.26716 35.0093 -25.11693 -24.35695 35.0093 -22.91809 -29.46607 31.41179 -35.87553 10.3167 31.41179 -28.56615 15.23773 36.1805 -24.76191 -20.85813 36.1805 -23.48693 -20.46183 36.3 -27.66172 14.32312 36.3 -34.97456 11.53285 32.79506 -23.57954 -28.28837 32.79506 -24.46857 -25.0082 35.0093 -32.25069 13.56518 35.0093 -33.83559 12.35162 34.02551 -24.04061 -26.82272 34.02551 -30.67773 13.7006 35.80914 -22.28203 -29.94995 31.41179 -20.88684 -31.14466 29.95 -20.79185 -31.00302 31.41179 -36.26933 8.833105 31.41179 -36.67608 7.817627 29.95 -24.11952 -23.38971 35.80914 -35.39263 10.17783 32.79506 -22.6096 -29.06944 32.79506 -34.20777 11.28 34.02551 -23.06258 -27.66816 34.02551 -23.35174 -26.05413 35.0093 -32.86604 11.99769 35.0093 -23.4969 -24.0151 35.80914 -36.50928 7.782073 31.41179 -21.9821 -29.54681 32.79506 -20.51198 -30.58571 32.79506 -29.56201 13.20232 36.1805 -23.24231 -22.53905 36.1805 -21.78484 -22.26529 36.3 -22.1139 -28.43211 34.02551 -34.61667 9.954691 34.02551 -22.40173 -26.87534 35.0093 -22.64234 -23.14169 36.1805 -22.42442 -25.0195 35.80914 -21.50016 -28.89901 34.02551 -21.48023 -27.6174 35.0093 -21.51213 -25.8081 35.80914 -21.60886 -24.10956 36.1805 -20.72975 -24.86948 36.1805 -1.457937 -29.13091 -3.37 -1.334882 -29.24646 -4 -1.604686 -29.61782 -4 -1.071654 -28.81134 -3.37 -2 -30.5 -3.37 -1.831192 -30.5 -4 -1.773662 -30.9554 -4 -1.752613 -29.53649 -3.37 -1.773662 -30.0446 -4 -1.937166 -30.99738 -3.37 -1.604686 -31.38218 -4 -1.937166 -30.00262 -3.37 -1.752613 -31.46351 -3.37 -1.334882 -31.75354 -4 -1.457937 -31.86909 -3.37 -0.9812017 -32.04613 -4 -1.071654 -32.18866 -3.37 -0.5658695 -32.24157 -4 -0.618034 -32.40211 -3.37 -0.1149815 -32.32758 -4 -0.125581 -32.49605 -3.37 0.3431312 -32.29876 -4 0.3747626 -32.46457 -3.37 0.7796836 -32.15691 -4 0.8515586 -32.30965 -3.37 1.167246 -31.91096 -4 1.274848 -32.04103 -3.37 1.481465 -31.57635 -4 1.618034 -31.67557 -3.37 1.702599 -31.17411 -4 1.859553 -31.23625 -3.37 1.816753 -30.72951 -4 1.984229 -30.75067 -3.37 1.816753 -30.27049 -4 1.984229 -30.24933 -3.37 1.702599 -29.82589 -4 1.859553 -29.76375 -3.37 1.481465 -29.42365 -4 1.618034 -29.32443 -3.37 1.167246 -29.08904 -4 1.274848 -28.95897 -3.37 0.7796836 -28.84309 -4 0.8515586 -28.69035 -3.37 0.3431312 -28.70124 -4 0.3747626 -28.53543 -3.37 -0.1149815 -28.67242 -4 -0.125581 -28.50395 -3.37 -0.5658695 -28.75843 -4 -0.618034 -28.59789 -3.37 -0.9812017 -28.95387 -4 -0.125581 -28.50395 0.1125 0.3747626 -28.53543 0.1125 -0.618034 -28.59789 0.1125 -1.071654 -28.81134 0.1125 -1.937166 -30.99738 0.1125 -2 -30.5 0.1125 -1.457937 -29.13091 0.1125 -1.752613 -31.46351 0.1125 -1.752613 -29.53649 0.1125 -1.457937 -31.86909 0.1125 -1.937166 -30.00262 0.1125 -1.071654 -32.18866 0.1125 -0.618034 -32.40211 0.1125 -0.125581 -32.49605 0.1125 0.3747626 -32.46457 0.1125 0.8515586 -32.30965 0.1125 1.274848 -32.04103 0.1125 1.618034 -31.67557 0.1125 1.859553 -31.23625 0.1125 1.984229 -30.75067 0.1125 1.984229 -30.24933 0.1125 1.859553 -29.76375 0.1125 1.618034 -29.32443 0.1125 1.274848 -28.95897 0.1125 0.8515586 -28.69035 0.1125 -11 -13.2914 53.94335 -12 -15.13219 54.32532 -12 -13.2914 53.94335 -12 -11.41346 54.03117 -11 -15.13219 54.32532 -11 -11.41346 54.03117 -11 -5.275241 60.3603 -12 -5.77204 58.54713 -12 -5.275241 60.3603 -11 -9.616348 54.58325 -12 -9.616348 54.58325 -11 -5.77204 58.54713 -11 -5.244968 62.24006 -12 -5.244968 62.24006 -11 -8.012997 55.56492 -12 -8.012997 55.56492 -12 -6.704148 56.91448 -11 -5.683121 64.06828 -12 -5.683121 64.06828 -11 -6.704148 56.91448 -11 -6.562171 65.73011 -12 -6.562171 65.73011 -12 -7.826883 67.12112 -11 -7.826883 67.12112 -11 -9.397791 68.1539 -12 -9.397791 68.1539 -11 -11.17619 68.76357 -12 -11.17619 68.76357 -11 -13.05033 68.91181 -12 -13.05033 68.91181 -11 -14.90247 68.58932 -12 -14.90247 68.58932 -11 -16.61621 67.81635 -12 -16.61621 67.81635 -11 -18.08388 66.64148 -12 -18.08388 66.64148 -11 -19.21327 65.13852 -12 -19.21327 65.13852 -12 -19.9334 63.40191 -11 -19.9334 63.40191 -12 -20.19903 61.54077 -11 -20.19903 61.54077 -12 -19.99347 59.67205 -11 -19.99347 59.67205 -11 -19.32963 57.91315 -12 -19.32963 57.91315 -11 -18.24923 56.3746 -12 -18.24923 56.3746 -12 -16.82015 55.15307 -11 -16.82015 55.15307 -11 13.2914 68.89665 -12 15.13219 68.51468 -12 13.2914 68.89665 -11 15.13219 68.51468 -11 11.41346 68.80883 -12 11.41346 68.80883 -11 5.77204 64.29287 -12 5.77204 64.29287 -12 5.275241 62.4797 -12 9.616348 68.25675 -11 5.275241 62.4797 -12 5.244968 60.59994 -11 9.616348 68.25675 -11 8.012997 67.27508 -12 8.012997 67.27508 -12 6.704148 65.92552 -11 5.244968 60.59994 -11 6.704148 65.92552 -11 5.683121 58.77172 -12 5.683121 58.77172 -12 6.562171 57.10989 -11 6.562171 57.10989 -11 7.826883 55.71888 -12 7.826883 55.71888 -12 9.397791 54.6861 -11 9.397791 54.6861 -11 11.17619 54.07643 -12 11.17619 54.07643 -11 13.05033 53.92819 -12 13.05033 53.92819 -11 14.90247 54.25068 -12 14.90247 54.25068 -12 16.61621 55.02365 -11 16.61621 55.02365 -11 18.08388 56.19852 -12 18.08388 56.19852 -11 19.21327 57.70148 -12 19.21327 57.70148 -12 19.9334 59.43809 -11 19.9334 59.43809 -11 20.19903 61.29923 -12 20.19903 61.29923 -11 19.99347 63.16795 -12 19.99347 63.16795 -11 19.32963 64.92685 -12 19.32963 64.92685 -12 18.24923 66.4654 -11 18.24923 66.4654 -11 16.82015 67.68693 -12 16.82015 67.68693 11 27 38.4 11 27 42.65 11.04911 26.30729 41.86903 20.84292 28.24345 29 21 27 29 20.88402 28.07085 35.00918 21 27 35.5166 11.35112 25.15938 29 11.03943 26.37333 29 11.20125 25.59825 41.06693 20.38153 29.40877 29 20.56082 29.04911 34.49017 11.95492 24.06107 29 11.66149 24.51564 39.82929 12.81288 23.14743 29 12.18363 23.77072 38.95925 19.64484 30.42274 29 20.06227 29.91513 34.02551 19.47606 30.59402 33.72847 12.84516 23.12114 38.17485 13.8711 22.47586 29 13.59342 22.61803 37.5313 18.67913 31.22164 29 18.95553 31.03297 33.63365 18.41987 31.37541 33.66804 15.06309 22.08856 29 14.25598 22.31409 37.10485 17.54508 31.75528 29 18.0359 31.56674 33.76181 14.98677 22.10496 36.75743 16.31395 22.00987 29 15.75601 22.00619 36.50356 17.65 31.71991 33.90538 17.01436 31.89533 33.91688 17.54508 22.24472 29 16.54423 22.03009 36.35173 16.31395 31.99013 29 16.37193 31.98577 33.92602 17.35 22.1857 36.3 18.67913 22.77836 29 18.33232 22.5773 36.3 15.06309 31.91144 29 15.49391 31.97349 33.92436 13.8711 31.52414 29 14.60591 31.80081 33.9094 19.64484 23.57726 29 19.21031 23.16673 36.3 13.75399 31.46662 33.90022 20.38153 24.59123 29 19.94469 23.92764 36.3 12.81288 30.85257 29 12.98593 30.98792 33.92952 20.29714 24.44371 36.26945 20.84292 25.75655 29 20.57984 24.99366 36.18047 11.95492 29.93893 29 12.33696 30.40299 34.03584 11.79124 29.69927 34.27604 11.35112 28.84062 29 20.88587 25.93774 35.92442 11.4066 28.975 34.67518 11.03943 27.62667 29 11.179 28.32574 35.21042 11.05928 27.76769 35.8863 11.01136 27.34599 36.67153 10.99925 27.08753 37.52585 13.8711 -31.52414 29 12.81288 -30.85257 29 13.09694 -31.06914 33.92101 12.31418 -30.37841 34.04206 14.15203 -31.64589 33.90231 20.84292 -25.75655 29 21 -27 29 20.9464 -26.26931 35.80909 15.06309 -31.91144 29 21 -27 35.5166 15.31475 -31.95163 33.9218 20.38153 -24.59123 29 20.7809 -25.53608 36.0474 16.31395 -31.99013 29 16.48006 -31.9764 33.9249 20.44059 -24.70184 36.23407 17.54508 -31.75528 29 17.64974 -31.72 33.90537 19.64484 -23.57726 29 19.94469 -23.92764 36.3 18.67913 -31.22164 29 18.32162 -31.42833 33.68665 18.67913 -22.77836 29 19.21031 -23.16673 36.3 18.84889 -31.109 33.6303 17.54508 -22.24472 29 18.33232 -22.5773 36.3 19.64484 -30.42274 29 19.29887 -30.75732 33.6802 17.35 -22.1857 36.3 19.6973 -30.36597 33.81379 16.31395 -22.00987 29 16.64241 -22.04186 36.33997 19.88798 -30.1438 33.91245 20.38153 -29.40877 29 20.06227 -29.91513 34.02551 15.06309 -22.08856 29 15.9459 -22.00031 36.4572 20.84292 -28.24345 29 20.56347 -29.04322 34.49355 14.98304 -22.10574 36.75893 13.8711 -22.47586 29 20.88454 -28.06844 35.01049 13.98648 -22.42346 37.26411 12.81288 -23.14743 29 12.9607 -23.03024 38.0618 12.03497 -23.95537 39.17707 11.95492 -24.06107 29 11.35112 -25.15938 29 11.03943 -26.37333 29 11.30492 -25.28129 40.70667 10.9991 -27.05938 37.68065 11.03943 -27.62667 29 11.00434 -27.23539 36.96818 11 -27 38.4 11.02974 -27.54453 36.25425 11.09494 -27.96974 35.60954 11 -27 42.65 11.35112 -28.84062 29 11.22604 -28.48611 35.05856 11.44556 -29.06295 34.61729 11.95492 -29.93893 29 11.79134 -29.69948 34.27591 8.1 31.78256 33.90888 8.1 30.65678 33.97971 8.1 36 38.4 8.987208 36 38.4 8.946625 35.99763 38.54597 8.885025 35.95841 39.01039 8.1 35.85862 39.5191 8.1 32.89058 34.12025 8.920232 35.87017 39.47312 9.031089 35.73698 39.91562 8.1 35.44338 40.56789 9.256185 35.49898 40.46351 9.564111 35.16081 41.01696 8.1 34.78036 41.48046 9.961897 34.66003 41.60378 8.1 33.91122 42.19948 10.34397 34.05768 42.10247 8.1 32.89058 42.67975 10.69971 33.2487 42.54641 10.90939 32.42348 42.80427 8.1 31.78256 42.89112 10.97748 31.8931 42.88286 16.336 32.57905 34.03125 11 31.35102 42.89753 8.1 30.65678 42.82029 8.1 33.91122 34.60052 14.99387 33.3726 34.30813 11 30.21583 42.71288 8.1 34.78036 35.31954 12.81235 34.52384 35.06737 8.1 29.58399 42.47172 8.1 28.63159 41.86731 11 29.16452 42.2465 8.1 35.44338 36.23211 11.30069 35.21851 35.86596 10.20217 35.65795 36.67914 8.1 27.85942 41.04503 11 28.26578 41.52886 8.1 35.85862 37.2809 9.612331 35.8597 37.2851 8.1 27.31601 40.05656 11 27.57829 40.60685 9.246259 35.9612 37.81033 8.1 27.03548 38.964 11 27.14697 39.54068 8.1 27.03548 37.836 8.1 27.31601 36.74344 8.1 27.85942 35.75497 8.1 28.63159 34.93269 8.1 29.58399 34.32828 8.1 -34.36841 34.93269 8.1 -35.14058 35.75497 12.29946 -34.76983 35.30837 11.00709 -35.34213 36.05765 8.1 -27 38.4 8.1 -27.14138 39.5191 11 -27.14697 39.54068 8.1 -33.41601 34.32828 14.46358 -33.66771 34.45652 8.1 -27.55662 40.56789 11 -27.57829 40.60685 8.1 -32.34322 33.97971 16.06796 -32.74298 34.07507 8.1 -28.21964 41.48046 11 -28.26578 41.52886 8.1 -29.08878 42.19948 8.1 -31.21744 33.90888 11 -29.16452 42.2465 8.1 -30.10942 42.67975 11 -30.21583 42.71288 8.1 -31.21744 42.89112 11 -31.35102 42.89753 8.1 -32.34322 42.82029 10.93947 -32.23225 42.84009 8.1 -30.10942 34.12025 8.1 -33.41601 42.47172 10.75622 -33.07242 42.61638 8.1 -29.08878 34.60052 10.57138 -33.58701 42.38687 10.34397 -34.05768 42.10247 8.1 -34.36841 41.86731 8.1 -28.21964 35.31954 8.1 -35.14058 41.04503 9.735082 -34.95671 41.28117 9.205609 -35.55215 40.35693 8.1 -35.68399 40.05656 8.1 -27.55662 36.23211 8.956006 -35.82341 39.64824 8.1 -35.96452 38.964 8.1 -27.14138 37.2809 8.8857 -35.94007 39.13197 8.89593 -35.97869 38.83753 8.946625 -35.99763 38.54597 8.959222 -35.99895 38.49706 8.972754 -35.99974 38.4484 8.1 -35.96452 37.836 8.987216 -36 38.4 9.24528 -35.96143 37.81206 9.60969 -35.86052 37.28831 8.1 -35.68399 36.74344 10.19867 -35.65921 36.68223 36.96419 -5.209324 31.41179 36.85704 -5.920022 31.41179 37.13306 -5.233124 29.95 30.41306 -11.10223 36.1805 29.58314 -9.755029 36.3 28.71342 -12.07735 36.3 29.84363 -12.55273 36.1805 30.96999 -13.0265 35.80914 31.5609 -11.52125 35.80914 35.22818 -7.509002 34.02551 34.99665 -8.523153 34.02551 36.01785 -7.677323 32.79506 36.36093 -5.840336 32.79506 33.99383 -8.278925 35.0093 34.61667 -9.954691 34.02551 33.62474 -9.669443 35.0093 30.74759 -10.13901 36.1805 31.90806 -10.52167 35.80914 32.28947 -9.285461 35.80914 33.22755 -10.95677 35.0093 36.46663 -5.139204 32.79506 34.21873 -7.293834 35.0093 37.21116 -2.969421 31.41179 37.40815 -2.622986 29.95 35.56374 -5.71229 34.02551 31.11513 -8.947756 36.1805 30.26537 -7.370887 36.3 32.64391 -7.950161 35.80914 35.66712 -5.02653 34.02551 36.71028 -2.929451 32.79506 32.85987 -7.004189 35.80914 34.54467 -5.548606 35.0093 31.45667 -7.66102 36.1805 34.64509 -4.882496 35.0093 37.32946 -8.930759e-11 31.41179 37.5 -8.507862e-11 29.95 31.66478 -6.749452 36.1805 30.75579 -4.940032 36.3 35.90543 -2.865224 34.02551 33.17287 -5.328266 35.80914 33.26931 -4.688608 35.80914 36.82698 -9.323727e-11 32.79506 34.87657 -2.783122 35.0093 31.9664 -5.134481 36.1805 37.23803 2.611057 31.41179 37.40815 2.622986 29.95 32.05933 -4.518087 36.1805 31.05129 -2.477868 36.3 36.01957 -9.673237e-11 34.02551 33.4916 -2.672602 35.80914 36.73679 2.575911 32.79506 34.98744 -9.952639e-11 35.0093 32.27353 -2.575402 36.1805 36.96419 5.209324 31.41179 37.13306 5.233124 29.95 35.93135 2.519436 34.02551 36.85704 5.920022 31.41179 36.67608 7.817627 29.95 33.59806 -1.017973e-10 35.80914 36.46663 5.139204 32.79506 34.90175 2.447242 35.0093 36.36093 5.840336 32.79506 36.50928 7.782073 31.41179 32.37613 -1.02851e-10 36.1805 31.15 -7.29846e-11 36.3 35.66712 5.02653 34.02551 36.26933 8.833105 31.41179 36.03944 10.36384 29.95 33.51577 2.35006 35.80914 35.56374 5.71229 34.02551 36.01785 7.677323 32.79506 34.64509 4.882496 35.0093 35.87553 10.3167 31.41179 32.29683 2.26459 36.1805 31.05129 2.477868 36.3 35.78113 8.714207 32.79506 34.54467 5.548606 35.0093 35.22818 7.509002 34.02551 33.26931 4.688608 35.80914 35.45176 11.69021 31.41179 35.22625 12.85928 29.95 35.39263 10.17783 32.79506 34.99665 8.523153 34.02551 33.17287 5.328266 35.80914 34.21873 7.293834 35.0093 35.06605 12.80079 31.41179 32.05933 4.518087 36.1805 30.75579 4.940032 36.3 22.28362 -29.94877 31.41179 20.88684 -31.14466 29.95 23.01413 -29.60742 29.95 20.79185 -31.00302 31.41179 34.97456 11.53285 32.79506 34.61667 9.954691 34.02551 22.90947 -29.47277 31.41179 21.98367 -29.54564 32.79506 33.99383 8.278925 35.0093 20.51198 -30.58571 32.79506 31.9664 5.134481 36.1805 32.85987 7.004189 35.80914 23.56209 -28.95369 31.41179 25.0287 -27.92516 29.95 22.6011 -29.07606 32.79506 34.59404 12.62849 32.79506 21.50169 -28.89787 34.02551 34.40951 14.47322 31.41179 34.24052 15.29173 29.95 34.20777 11.28 34.02551 23.24494 -28.56396 32.79506 33.62474 9.669443 35.0093 32.64391 7.950161 35.80914 24.91487 -27.79816 31.41179 22.10558 -28.43858 34.02551 20.88556 -28.06981 35.0093 34.0848 15.22218 31.41179 31.66478 6.749452 36.1805 30.26537 7.370887 36.3 22.7353 -27.93771 34.02551 33.83559 12.35162 34.02551 24.5795 -27.42398 32.79506 33.94634 14.2784 32.79506 26.10647 -26.68222 31.41179 26.92066 -26.1061 29.95 33.22755 10.95677 35.0093 21.47215 -27.62368 35.0093 31.45667 7.66102 36.1805 32.28947 9.285461 35.80914 26.79823 -25.98737 31.41179 22.08383 -27.13716 35.0093 33.626 15.01728 32.79506 32.86604 11.99769 35.0093 24.04061 -26.82272 34.02551 33.14918 17.16451 31.41179 33.08706 17.64927 29.95 25.75506 -26.32306 32.79506 33.20209 13.96536 34.02551 26.43751 -25.63757 32.79506 28.14621 -24.52099 31.41179 31.11513 8.947756 36.1805 29.58314 9.755029 36.3 28.68075 -24.15915 29.95 31.90806 10.52167 35.80914 21.20686 -26.05952 35.80914 32.88877 14.68804 34.02551 23.35174 -26.05413 35.0093 32.70297 16.93346 32.79506 25.1904 -25.74594 34.02551 31.5609 11.52125 35.80914 25.85788 -25.07548 34.02551 32.25069 13.56518 35.0093 27.76735 -24.19093 32.79506 30.74759 10.13901 36.1805 31.94635 14.26716 35.0093 24.46857 -25.0082 35.0093 22.42442 -25.0195 35.80914 31.67876 19.74701 31.41179 31.77152 19.92036 29.95 30.41306 11.10223 36.1805 28.71342 12.07735 36.3 25.11693 -24.35695 35.0093 31.98598 16.56221 34.02551 30.00757 -22.20436 31.41179 30.30034 -22.09387 29.95 27.15857 -23.66056 34.02551 30.96999 13.0265 35.80914 30.67773 13.7006 35.80914 21.60886 -24.10956 36.1805 21.78484 -22.26529 36.3 23.4969 -24.0151 35.80914 31.25235 19.4812 32.79506 24.11952 -23.38971 35.80914 31.06943 16.08762 35.0093 29.84363 12.55273 36.1805 29.60366 -21.90548 32.79506 26.38035 -22.98257 35.0093 30.16254 21.99339 31.41179 30.30034 22.09387 29.95 28.68075 24.15915 29.95 22.64234 -23.14169 36.1805 29.56201 13.20232 36.1805 27.66172 14.32312 36.3 31.62702 -19.82977 31.41179 31.77152 -19.92036 29.95 30.56716 19.05409 34.02551 23.24231 -22.53905 36.1805 23.48693 -20.46183 36.3 28.95462 -21.42522 34.02551 29.83564 15.44877 35.80914 29.75654 21.69735 32.79506 25.33276 -22.06991 35.80914 31.20131 -19.56285 32.79506 29.69127 18.5081 35.0093 28.75054 14.88691 36.1805 26.43471 16.47812 36.3 28.55031 24.04928 31.41179 28.12493 -20.81128 35.0093 24.41143 -21.26725 36.1805 25.04017 -18.52869 36.3 32.93658 -17.56901 31.41179 33.08706 -17.64927 29.95 34.24052 -15.29173 29.95 29.10415 21.22165 34.02551 28.5122 17.77313 35.80914 30.51724 -19.13394 34.02551 28.16601 23.72557 32.79506 27.00806 -19.98485 35.80914 28.27018 20.61355 35.0093 32.49324 -17.33252 32.79506 27.47523 17.12673 36.1805 29.64278 -18.58567 35.0093 26.79823 25.98737 31.41179 26.92066 26.1061 29.95 26.0258 -19.25802 36.1805 27.54849 23.2054 34.02551 34.0848 -15.22218 31.41179 31.78084 -16.95251 34.02551 26.10647 26.68222 31.41179 25.0287 27.92516 29.95 34.40951 -14.47322 31.41179 35.22625 -12.85928 29.95 27.14754 19.79497 35.80914 28.46564 -17.84761 35.80914 26.43751 25.63757 32.79506 33.626 -15.01728 32.79506 26.75909 22.54046 35.0093 30.87017 -16.46674 35.0093 33.94634 -14.2784 32.79506 25.75506 26.32306 32.79506 24.91487 27.79816 31.41179 35.06605 -12.80079 31.41179 26.16021 19.07504 36.1805 27.43036 -17.19851 36.1805 26.43471 -16.47812 36.3 25.04017 18.52869 36.3 32.88877 -14.68804 34.02551 25.85788 25.07548 34.02551 25.69647 21.64535 35.80914 35.45176 -11.69021 31.41179 36.03944 -10.36384 29.95 23.90127 28.67434 31.41179 23.01413 29.60742 29.95 29.64429 -15.81284 35.80914 25.1904 25.74594 34.02551 33.20209 -13.96536 34.02551 34.59404 -12.62849 32.79506 24.5795 27.42398 32.79506 31.94635 -14.26716 35.0093 25.11693 24.35695 35.0093 35.87553 -10.3167 31.41179 22.91809 29.46607 31.41179 28.56615 -15.23773 36.1805 27.66172 -14.32312 36.3 24.76191 20.85813 36.1805 23.48693 20.46183 36.3 34.97456 -11.53285 32.79506 23.57954 28.28837 32.79506 32.25069 -13.56518 35.0093 33.83559 -12.35162 34.02551 24.46857 25.0082 35.0093 24.04061 26.82272 34.02551 30.67773 -13.7006 35.80914 22.28203 29.94995 31.41179 20.88684 31.14466 29.95 20.79185 31.00302 31.41179 36.26933 -8.833105 31.41179 36.67608 -7.817627 29.95 24.11952 23.38971 35.80914 35.39263 -10.17783 32.79506 22.6096 29.06944 32.79506 34.20777 -11.28 34.02551 23.06258 27.66816 34.02551 32.86604 -11.99769 35.0093 23.35174 26.05413 35.0093 23.4969 24.0151 35.80914 36.50928 -7.782073 31.41179 21.9821 29.54681 32.79506 20.51198 30.58571 32.79506 29.56201 -13.20232 36.1805 23.24231 22.53905 36.1805 35.78113 -8.714207 32.79506 21.78484 22.26529 36.3 22.1139 28.43211 34.02551 22.40173 26.87534 35.0093 22.64234 23.14169 36.1805 22.42442 25.0195 35.80914 21.50016 28.89901 34.02551 21.48023 27.6174 35.0093 21.51213 25.8081 35.80914 21.60886 24.10956 36.1805 20.72975 24.86948 36.1805 10.3 -29.96516 38.18819 9.5 -29.78503 38.28691 9.5 -29.96516 38.18819 10.3 -29.78503 38.28691 10.3 -30.11236 38.04491 9.5 -30.11236 38.04491 10.3 -30.21591 37.86752 9.5 -30.21591 37.86752 10.3 -30.26828 37.6689 9.5 -30.26828 37.6689 10.3 -30.26567 37.4635 9.5 -30.26567 37.4635 10.3 -30.20827 37.26628 9.5 -30.20827 37.26628 9.5 -32.25955 39.94175 10.3 -32.25955 39.94175 10.3 -32.33793 39.98954 9.5 -32.33793 39.98954 9.5 -32.42615 40.01496 10.3 -32.42615 40.01496 9.5 -32.51795 40.0162 9.5 -32.60683 39.99317 10.3 -32.51795 40.0162 9.5 -32.68647 39.94751 10.3 -32.60683 39.99317 9.5 -32.75125 39.88245 10.3 -32.68647 39.94751 9.5 -32.79656 39.8026 10.3 -32.75125 39.88245 9.5 -32.81919 39.71362 10.3 -32.79656 39.8026 10.3 -32.81919 39.71362 9.5 -32.81754 39.62183 10.3 -32.81754 39.62183 9.5 -32.79173 39.53372 10.3 -32.79173 39.53372 9.5 -33.29555 38.4691 9.5 -33.21497 38.51309 10.3 -33.21497 38.51309 9.5 -33.36168 38.40541 10.3 -33.29555 38.4691 9.5 -33.40865 38.32653 10.3 -33.36168 38.40541 9.5 -33.43314 38.23805 10.3 -33.40865 38.32653 9.5 -33.43342 38.14624 10.3 -33.43314 38.23805 9.5 -33.40946 38.05761 10.3 -33.43342 38.14624 9.5 -33.36296 37.97845 10.3 -33.40946 38.05761 9.5 -33.29722 37.91436 10.3 -33.36296 37.97845 9.5 -33.21691 37.86989 10.3 -33.29722 37.91436 9.5 -33.1277 37.84819 10.3 -33.21691 37.86989 10.3 -33.1277 37.84819 10.16469 -32.4157 40.37424 10.3 -32.24552 40.20186 10.3 -31.75376 40.33342 9.527993 -34.21613 39.52267 10.3 -33.43322 38.65529 10.3 -33.30127 39.14695 10.3 -33.04657 39.5877 8.1 -35.09464 39.63231 9.197723 -34.71494 38.31979 9.292026 -31.94417 41.51136 9.845689 -30.5017 40.80742 8.1 -30.49583 42.06492 8.1 -31.43881 42.19951 8.1 -32.38563 42.09536 10.3 -31.24471 40.33322 9.200915 -33.71701 40.7263 8.294798 -33.33708 41.64251 8.1 -33.2768 41.75901 8.1 -34.05634 41.21161 8.873793 -28.16237 37.58617 9.200915 -28.28733 38.47474 9.527993 -28.78645 37.27111 8.1 -27.77926 37.62794 8.1 -27.70415 38.5775 8.1 -28.08816 36.72688 9.355516 -31.67079 35.31359 8.1 -32.03691 34.63812 9.285391 -31.05819 35.28297 10.3 -31.24624 36.46658 9.36566 -31.97703 35.35447 10.3 -31.75529 36.46678 8.746905 -32.84432 35.15815 9.539227 -32.15781 35.54637 9.839292 -32.50118 35.98565 9.539227 -33.05464 35.91826 10.3 -32.6877 36.85343 9.36566 -33.31818 35.91061 8.1 -33.7828 35.3621 10.3 -33.04751 37.21353 9.355516 -33.56348 36.09844 9.285391 -34.01798 36.51033 8.873793 -34.43412 40.18692 8.1 -34.67524 40.48754 9.197723 -29.28526 36.06822 8.1 -28.61143 35.93095 8.1 -29.31621 35.29017 8.1 -30.1582 34.84478 10.3 -29.95343 37.2123 10.3 -30.31353 36.85249 8.1 -31.0845 34.62278 10.3 -29.56678 38.14471 10.3 -29.69873 37.65305 10.16107 -30.58747 36.4181 10.3 -30.75448 36.59814 8.1 -32.95559 34.88983 10.3 -29.56658 38.65376 10.3 -32.24695 36.59873 8.294798 -27.9074 39.39094 8.1 -27.86754 39.51592 8.1 -28.25918 40.38421 10.16469 -29.45591 39.14688 10.3 -29.95249 39.58647 10.3 -29.69814 39.14552 8.1 -34.46658 36.02525 8.1 -34.96395 36.83762 9.292026 -28.98437 40.284 8.1 -28.85445 41.12783 8.1 -29.61595 41.70005 10.3 -30.3123 39.94657 10.16107 -33.54727 37.64546 10.3 -33.30186 37.65448 10.3 -30.75305 40.20127 8.1 -35.24367 37.74815 8.1 -35.28817 38.69964 8.7555 -30.15753 41.63739 -7.008551e-14 -29.60114 72.53012 4.7 -29.60114 72.53012 4.7 -36.09627 48.35568 -7.062625e-14 -36.09627 48.35568 -4.7 36.09627 48.35568 1.55348e-14 36.09627 48.35568 -4.7 29.60114 72.53012 5.718177e-16 29.60114 72.53012 -4.7 -29.60114 72.53012 4.7 36.09627 48.35568 4.7 29.60114 72.53012 10.3 -33.03484 38.61181 10.3 -32.73172 39.1311 10.3 -32.73433 39.3365 10.3 -32.78409 38.93248 10.3 -32.88764 38.75509 10.3 -32.43552 36.79045 10.3 -32.45762 36.87956 10.3 -32.3907 36.71033 10.3 -32.32632 36.64487 10.3 -32.45542 36.97134 10.3 -32.45085 37.1767 10.3 -32.50134 37.37581 10.3 -32.60319 37.55418 10.3 -32.74901 37.69885 10.3 -32.92819 37.79929 10.3 -31.30613 39.93721 10.3 -31.16403 40.08553 10.3 -30.93359 40.22415 10.3 -30.84179 40.22483 10.3 -31.02196 40.19926 10.3 -31.10064 40.15194 10.3 -31.4827 39.83225 10.3 -31.6809 39.7783 10.3 -31.88631 39.77928 10.3 -32.08398 39.83511 10.3 -30.48205 36.7838 10.3 -30.39317 36.80683 10.3 -30.57385 36.78504 10.3 -30.66207 36.81046 10.3 -30.74045 36.85825 10.3 -30.91602 36.96489 10.3 -32.06641 36.57585 10.3 -31.97804 36.60074 10.3 -31.89936 36.64806 10.3 -32.15821 36.57517 10.3 -31.83597 36.71447 10.3 -31.11369 37.02072 10.3 -31.69387 36.86279 10.3 -31.3191 37.0217 10.3 -31.5173 36.96775 10.3 -29.63704 38.82155 10.3 -29.59054 38.74239 10.3 -29.70278 38.88564 10.3 -29.78309 38.93011 10.3 -29.8723 38.95181 10.3 -30.07181 39.00071 10.3 -30.25099 39.10115 10.3 -30.39681 39.24582 10.3 -30.49866 39.42419 10.3 -30.54915 39.6233 10.3 -30.54458 39.82866 10.3 -30.54238 39.92044 10.3 -30.56448 40.00955 10.3 -30.6093 40.08967 10.3 -30.67368 40.15513 10.3 -30.20344 36.9974 10.3 -30.24875 36.91755 10.3 -30.18081 37.08638 10.3 -30.18246 37.17817 10.3 -29.70445 38.3309 10.3 -29.63832 38.39459 10.3 -29.59135 38.47347 10.3 -29.56686 38.56195 9.5 -30.74045 36.85825 9.5 -30.91602 36.96489 9.5 -31.11369 37.02072 9.5 -31.3191 37.0217 9.5 -31.5173 36.96775 9.5 -31.69387 36.86279 9.5 -31.83597 36.71447 9.5 -32.45542 36.97134 9.5 -32.45762 36.87956 9.5 -32.43552 36.79045 9.5 -32.3907 36.71033 9.5 -32.32632 36.64487 9.5 -32.24695 36.59873 9.5 -32.15821 36.57517 9.5 -32.06641 36.57585 9.5 -31.97804 36.60074 9.5 -31.89936 36.64806 9.5 -32.45085 37.1767 9.5 -32.50134 37.37581 9.5 -32.60319 37.55418 9.5 -32.74901 37.69885 9.5 -32.92819 37.79929 9.5 -33.03484 38.61181 9.5 -32.88764 38.75509 9.5 -32.78409 38.93248 9.5 -32.73172 39.1311 9.5 -32.73433 39.3365 9.5 -32.08398 39.83511 9.5 -31.88631 39.77928 9.5 -31.6809 39.7783 9.5 -31.4827 39.83225 9.5 -31.30613 39.93721 9.5 -31.16403 40.08553 9.5 -30.54458 39.82866 9.5 -30.54238 39.92044 9.5 -30.56448 40.00955 9.5 -30.6093 40.08967 9.5 -30.67368 40.15513 9.5 -30.75305 40.20127 9.5 -30.84179 40.22483 9.5 -30.93359 40.22415 9.5 -31.02196 40.19926 9.5 -31.10064 40.15194 9.5 -30.54915 39.6233 9.5 -30.49866 39.42419 9.5 -30.39681 39.24582 9.5 -30.25099 39.10115 9.5 -30.07181 39.00071 9.5 -29.8723 38.95181 9.5 -29.70445 38.3309 9.5 -29.63832 38.39459 9.5 -29.59135 38.47347 9.5 -29.56686 38.56195 9.5 -29.56658 38.65376 9.5 -29.59054 38.74239 9.5 -29.63704 38.82155 9.5 -29.70278 38.88564 9.5 -29.78309 38.93011 9.5 -30.66207 36.81046 9.5 -30.57385 36.78504 9.5 -30.48205 36.7838 9.5 -30.39317 36.80683 9.5 -30.31353 36.85249 9.5 -30.24875 36.91755 9.5 -30.20344 36.9974 9.5 -30.18081 37.08638 9.5 -30.18246 37.17817 11 -9.01009 46.71978 11 -10.62308 46.71379 11 -15.38012 44.23933 11 -8.903471 46.71379 11 -15.42865 44.19123 11 2.234535 49.35464 11 1.355493 49.07923 11 1.524639 48.83763 11 2.319894 48.66878 11 1.223303 49.91769 11 5.004933 46.62518 11 4.505128 46.66782 11 -0.5706236 46.70016 11 15.03952 50.94199 11 13.84275 51.98878 11 13.80027 51.91764 11 14.76929 50.4652 11 -32.2316 46.09107 11 12.04771 52.03643 11 12.6418 52.03643 11 2.292251 49.93373 11 1.349275 50.13315 11 1.428616 50.37554 11 -16.27571 82.70425 11 -17.43426 81.99289 11 19.15231 47.36241 11 18.80403 47.12334 11 18.80403 47.10273 11 19.47959 46.80256 11 -35.82207 53.42255 11 -35.5347 52.68959 11 -35.14755 52.00316 11 -18.31393 53.43137 11 -18.20382 53.44885 11 -18.39999 53.39455 11 -18.46687 53.34434 11 -36.06751 54.7221 11 -18.51851 53.28531 11 -36.00545 56.04527 11 -11.67398 49.81876 11 -13.77395 49.80643 11 -11.67398 49.06805 11 -13.81279 49.91159 11 -35.63901 57.32134 11 -10.52074 48.8224 11 -10.70499 48.8224 11 -10.70499 48.54939 11 2.458582 50.46516 11 15.44418 51.3913 11 13.84275 52.03643 11 1.410646 51.02176 11 1.456202 50.63766 11 -18.06358 53.43935 11 -15.06883 52.89102 11 -20.29222 43.69748 11 -20.2444 43.62347 11 -33.49735 49.12617 11 -1.573732 52.01609 11 -1.116487 52.03654 11 -0.3932489 52.05017 11 -18.56204 53.21318 11 -18.59593 53.13236 11 -18.62248 53.03967 11 19.43838 47.6439 11 20.0664 46.59094 11 -34.99099 58.47556 11 -7.879891 46.71379 11 -20.32483 43.78713 11 19.65009 47.92848 11 20.30532 46.53641 11 -20.33946 43.90685 11 16.00571 51.77509 11 19.86757 48.28766 11 20.33953 46.5091 11 2.725316 50.94196 11 1.304471 51.29966 11 3.125905 51.39129 11 -20.32407 44.06704 11 1.170825 51.50017 11 1.014047 51.65839 11 -19.85242 46.52868 11 -14.905 52.84808 11 -14.70226 52.76014 11 -19.8256 46.62131 11 -15.02002 83.2253 11 -19.79146 46.70204 11 3.682835 51.77509 11 -9.365799 49.12354 11 -9.558548 49.02709 11 -9.558548 49.01352 11 -8.32341 47.2939 11 20.04246 48.79085 11 0.8466284 51.77884 11 0.6761113 51.86827 11 -11.68114 51.47136 11 -13.84941 49.97016 11 9.441224 46.71384 11 5.722457 46.71052 11 -14.12028 51.02069 11 -14.11849 50.94537 11 6.360619 46.95316 11 -14.13166 51.09453 11 6.902458 47.33309 11 -14.15226 51.17456 11 7.331015 47.83027 11 9.441224 46.75478 11 20.11421 49.39559 11 19.71852 45.84714 11 19.70711 45.84196 11 -11.75588 51.98191 11 9.461975 46.77236 11 9.452023 46.7623 11 -11.73123 51.96098 11 9.476524 46.79576 11 -11.7388 51.97083 11 -11.74701 51.97767 11 -13.6982 83.54316 11 -11.75588 52.0228 11 9.497902 46.86727 11 7.62933 48.42465 11 -14.4717 52.46633 11 -7.136884 47.51607 11 -8.065786 46.95516 11 -7.879891 46.75474 11 -6.638835 47.0899 11 16.66594 52.01916 11 17.40509 52.1047 11 -7.517261 48.04916 11 -6.043005 46.79102 11 -18.17537 47.40455 11 -19.29222 46.92658 11 -18.13217 47.35618 11 -12.3429 83.65 11 -14.50842 52.56242 11 -14.56178 52.64229 11 -14.62774 52.70763 11 -18.07696 47.31538 11 -7.760074 48.66881 11 -8.95391 49.46032 11 -9.162745 49.26603 11 -18.20656 47.46047 11 -18.00974 47.28214 11 -5.574908 46.66783 11 18.1973 51.99758 11 18.70624 51.79706 11 17.81227 52.07737 11 -18.22712 47.53146 11 10.65592 46.75478 11 10.63744 46.76023 11 10.64589 46.75657 11 10.63029 46.76539 11 10.62356 46.77249 11 10.61723 46.7817 11 10.6094 46.79755 11 -17.93956 47.25884 11 -17.85979 47.24157 11 19.15227 51.50433 11 19.52539 51.1292 11 -7.845433 49.35464 11 -8.757596 49.7553 11 -18.23222 47.62898 11 32.2316 46.09107 11 -5.075062 46.62518 11 -15.50385 44.14666 11 10.56042 47.37252 11 -18.20906 47.76791 11 20.11421 49.40246 11 -19.43247 46.93656 11 19.8156 50.68151 11 -16.46385 46.48913 11 -7.787712 49.93373 11 -8.636507 50.08538 11 -8.589499 50.48743 11 9.536713 49.06805 11 7.753258 48.89753 11 7.79594 49.40246 11 7.710291 50.11694 11 7.79594 49.40933 11 33.49735 49.12617 11 20.02867 50.11091 11 8.042286 51.07425 11 7.496577 50.68711 11 7.204918 51.13447 11 8.096969 51.07425 11 -19.00505 50.13432 11 -19.62885 46.88292 11 -19.54267 46.91945 11 -11.25772 52.0433 11 -10.61622 52.05704 11 35.14755 52.00316 11 -18.94447 50.07494 11 -10.07119 52.02798 11 -18.87492 50.0283 11 -7.62137 50.46516 11 -8.634429 50.89977 11 -19.05353 50.20794 11 -19.6959 46.83292 11 36.04179 54.44847 11 35.73706 53.17158 11 8.187616 51.13396 11 8.136571 51.10751 11 -18.77367 49.98338 11 -17.96681 49.07728 11 12.63493 46.71384 11 10.65592 46.71384 11 -7.354623 50.94196 11 -8.755567 51.23382 11 36.04524 55.75832 11 12.63493 46.7615 11 -19.08679 50.29726 11 -19.74772 46.77405 11 35.75042 57.0327 11 12.66259 46.79361 11 12.64954 46.77535 11 35.42227 57.78101 11 -6.954023 51.39129 11 -8.932435 51.49659 11 12.68078 46.83682 11 -9.144554 51.69509 11 -19.10208 50.41675 11 34.99099 58.47556 11 8.348072 51.17226 11 -18.50863 49.93465 11 -17.92702 49.20715 11 12.3429 83.65 11 -9.592636 51.92732 11 -9.371447 51.83633 11 -19.08726 50.5769 11 8.560671 51.18346 11 8.042286 52.03643 11 -18.36472 49.93662 11 -1.580602 46.73423 11 -4.357447 46.71052 11 13.6982 83.54316 11 -3.719255 46.95316 11 -3.177428 47.33309 11 -17.87378 49.3102 11 6.829173 51.50914 11 6.378987 51.80112 11 15.02002 83.2253 11 -1.580602 46.7753 11 -2.748906 47.83027 11 -17.79945 49.40006 11 16.27571 82.70425 11 -1.565959 46.78306 11 -1.57306 46.77839 11 19.34854 80.07381 11 -17.72224 49.46017 11 -1.556974 46.79231 11 17.43426 81.99289 11 18.46704 81.1088 11 -1.545538 46.81208 11 -1.52792 46.87476 11 -19.70487 43.42007 11 -19.89833 43.43955 11 -20.01494 43.47105 11 -17.61079 49.51495 11 -20.11554 43.51655 11 -20.18448 43.56364 11 13.81278 46.80799 11 13.82971 46.77663 11 13.84962 46.75478 11 -19.60329 43.42499 11 -6.397092 51.77509 11 -15.62221 44.11142 11 19.68346 45.83691 11 19.67191 45.83805 11 19.64336 45.84714 11 9.536713 51.18346 11 13.84962 46.71384 11 -1.143691 46.71373 11 -17.38509 49.57474 11 19.69683 45.83859 11 -19.34854 80.07381 11 -13.89491 46.64154 11 -15.67964 46.07643 11 -15.63412 45.94819 11 -15.74978 46.18112 11 -15.84006 46.26525 11 -15.94598 46.33187 11 -16.20123 46.42867 11 -15.33503 44.6508 11 -14.43773 50.63433 11 -9.121789 46.74116 11 -10.69594 47.22339 11 13.76147 47.35807 11 -15.31925 44.56966 11 -2.450633 48.42465 11 -13.65315 46.67369 11 -15.31177 44.49497 11 -15.31325 44.41896 11 12.73056 49.06118 11 10.55342 49.06805 11 12.73056 49.81861 11 -13.4858 46.73191 11 -18.46704 81.1088 11 11.53606 51.18346 11 10.55342 51.18346 11 15.53841 47.23689 11 15.12227 47.6566 11 -1.491845 49.0682 11 -2.284055 49.40933 11 -2.284055 49.40246 11 16.04199 46.91378 11 -2.326728 48.89753 11 -5.741424 52.01916 11 -5.00664 52.1047 11 14.80763 48.15748 11 12.00017 51.07425 11 11.79018 51.16488 11 11.88885 51.13897 11 11.95009 51.11078 11 12.04771 51.07425 11 16.61898 46.7027 11 -11.75588 46.71379 11 -15.32513 44.35101 11 -15.34742 44.29114 11 -13.36509 46.80333 11 -1.491845 49.81876 11 -2.369705 50.11698 11 14.60855 48.72411 11 13.75414 49.06805 11 -13.28598 46.87574 11 -13.22357 46.96494 11 4.338523 52.01916 11 5.073355 52.1047 11 5.480006 52.07809 11 5.864006 52.0004 11 -11.75588 46.75474 11 -13.18399 47.0651 11 -13.16665 47.17426 11 16.96339 46.63984 11 -11.74114 46.766 11 -11.74827 46.75948 11 -11.73049 46.7813 11 -11.71661 46.81782 11 -13.1691 47.2813 11 14.53906 49.34106 11 -13.1897 47.40162 11 13.75414 49.81861 11 0.0870264 52.01946 11 0.5212408 51.92732 11 -1.497825 51.40291 11 -2.583426 50.68717 11 -2.8751 51.13455 11 12.72303 51.45101 11 14.55427 49.64114 11 14.59897 49.93021 11 -4.600068 52.07811 11 -4.216145 52.00046 11 12.67038 51.95319 11 12.6418 51.98878 11 12.65701 51.97397 11 -1.573732 51.97515 11 -3.250872 51.50923 11 -1.539686 51.92611 11 -1.5497 51.94829 11 -10.62308 46.75474 11 -10.64048 46.77064 11 -10.63213 46.76121 11 -1.561022 51.96418 11 -10.64818 46.78344 11 -3.701101 51.8012 11 18.76308 46.24982 11 17.96469 46.69345 11 17.67136 46.63865 11 -14.35449 50.1125 11 -14.25508 50.12399 11 17.32348 46.61831 11 -14.31176 50.6717 11 -14.16763 50.12433 11 0.8519737 49.59632 11 0.6168664 49.50481 11 0.6168664 49.49122 11 0.8894699 49.41 11 -14.23271 50.71741 11 -14.06383 50.10878 11 2.943108 47.51601 11 1.464363 47.47879 11 1.24717 47.21115 11 1.601253 47.76686 11 3.441191 47.08984 11 0.9784854 47.0072 11 -14.18255 50.76606 11 -13.97979 50.07804 11 2.562714 48.04911 11 1.655545 47.98326 11 1.67452 48.21503 11 -14.14962 50.81806 11 -13.90699 50.03077 11 1.67452 48.2219 11 1.055828 49.73635 11 -14.12827 50.87783 11 1.139724 49.27135 11 4.037075 46.79097 11 0.6680309 46.86031 11 0.283201 46.76081 11 1.635027 48.55053 11 13.81713 51.9588 11 13.82921 51.976 12.91153 -23.71271 0.3125 13.26619 -23.51613 0.3125 13.26619 -23.51613 -6.679102e-11 12.91153 -23.71271 -6.737097e-11 12.55395 -23.90394 0.3125 12.55395 -23.90394 -6.791442e-11 12.19355 -24.08978 0.3125 12.19355 -24.08978 -6.838974e-11 12.55395 23.90394 0.3125 12.19355 24.08978 0.3125 12.19355 24.08978 6.851408e-11 12.55395 23.90394 6.792191e-11 12.91153 23.71271 0.3125 12.91153 23.71271 6.737867e-11 13.26619 23.51613 0.3125 13.26619 23.51613 6.691536e-11 23.59237 -23 -6.529888e-11 15.23155 -23 -6.529888e-11 23.59237 -23 0.3125 15.23155 -23 0.3125 26.04353 -21.85714 0.3125 27.65918 -19.77296 0.3125 26.04353 -21.85714 -6.210144e-11 26.04353 21.85714 0.3125 26.04353 21.85714 6.210144e-11 27.65918 19.77296 5.618909e-11 27.65918 19.77296 0.3125 29.10843 17.56983 0.3125 29.10843 17.56983 4.992978e-11 30.38259 15.26101 0.3125 30.38259 15.26101 4.337011e-11 31.47397 12.86038 0.3125 31.47397 12.86038 3.654954e-11 32.37601 10.38239 0.3125 32.37601 10.38239 2.95091e-11 33.08329 7.841941 0.3125 33.08329 7.841941 2.229114e-11 33.59155 5.254317 0.3125 33.59155 5.254317 1.493909e-11 33.89773 2.635084 0.3125 33.89773 2.635084 7.497165e-12 34 3.563918e-11 0.3125 34 4.892547e-11 1.014204e-14 33.89773 -2.635084 0.3125 33.89773 -2.635084 -7.476942e-12 33.59155 -5.254317 0.3125 33.59155 -5.254317 -1.491905e-11 33.08329 -7.841941 0.3125 33.08329 -7.841941 -2.22714e-11 32.37601 -10.38239 0.3125 32.37601 -10.38239 -2.948978e-11 31.47397 -12.86038 0.3125 31.47397 -12.86038 -3.653076e-11 30.38259 -15.26101 -4.335198e-11 30.38259 -15.26101 0.3125 29.10843 -17.56983 -4.991241e-11 29.10843 -17.56983 0.3125 27.65918 -19.77296 -5.617259e-11 15.23155 23 6.540546e-11 23.59237 23 6.540546e-11 15.23155 23 0.3125 23.59237 23 0.3125 10 30.03997 8.540724e-11 10 27.65863 7.860379e-11 10 30.03997 0.3125 10 27.65863 0.3125 7.506494 33.16101 0.3125 7.506494 33.16101 9.42002e-11 8.312352 32.86004 9.341904e-11 8.312352 32.86004 0.3125 9.00892 32.35529 0.3125 9.00892 32.35529 9.198531e-11 9.545863 31.68321 0.3125 9.545863 31.68321 9.007623e-11 9.884377 30.89239 0.3125 9.884377 30.89239 8.782974e-11 -5.0274 33.62626 0.3125 -7.506494 33.16101 0.3125 -7.506494 33.16101 -1.064926e-10 -2.520636 33.90644 0.3125 -5.0274 33.62626 -1.065031e-10 -2.520636 33.90644 -1.065024e-10 -1.121301e-11 34 0.3125 2.74572e-14 34 -1.064926e-10 2.520636 33.90644 0.3125 5.0274 33.62626 0.3125 2.520636 33.90644 9.632328e-11 5.0274 33.62626 9.552809e-11 10 -30.03997 -8.530066e-11 10 -27.65863 0.3125 10 -27.65863 -7.858603e-11 10 -30.03997 0.3125 5.0274 -33.62626 0.3125 7.506494 -33.16101 0.3125 7.506494 -33.16101 -9.42002e-11 2.520636 -33.90644 0.3125 5.0274 -33.62626 -9.55562e-11 1.117736e-11 -34 0.3125 2.520636 -33.90644 -9.635315e-11 -2.520636 -33.90644 0.3125 -5.37001e-14 -34 -1.064926e-10 -5.0274 -33.62626 0.3125 -2.520636 -33.90644 -1.065156e-10 -7.506494 -33.16101 0.3125 -5.0274 -33.62626 -1.065162e-10 -7.506494 -33.16101 -1.064926e-10 9.884377 -30.89239 -8.772211e-11 9.884377 -30.89239 0.3125 9.545863 -31.68321 0.3125 9.545863 -31.68321 -8.996953e-11 9.00892 -32.35529 0.3125 9.00892 -32.35529 -9.187955e-11 8.312352 -32.86004 0.3125 8.312352 -32.86004 -9.331416e-11 10.1509 -26.57031 -7.549491e-11 10.1509 -26.57031 0.3125 10.59223 -25.56409 -7.263584e-11 10.59223 -25.56409 0.3125 11.29068 -24.71592 -7.022571e-11 11.29068 -24.71592 0.3125 11.29068 24.71592 0.3125 11.29068 24.71592 7.024186e-11 10.59223 25.56409 0.3125 10.59223 25.56409 7.265157e-11 10.1509 26.57031 0.3125 10.1509 26.57031 7.551038e-11 13.88848 -23.23222 0.3125 13.88848 -23.23222 -6.598034e-11 14.55005 -23.05848 0.3125 14.55005 -23.05848 -6.548651e-11 14.55005 23.05848 0.3125 14.55005 23.05848 6.550387e-11 13.88848 23.23222 0.3125 13.88848 23.23222 6.599731e-11 25.35064 -22.47367 -6.378232e-11 25.35064 -22.47367 0.3125 24.51005 -22.86559 0.3125 24.51005 -22.86559 -6.489615e-11 24.51005 22.86559 6.502105e-11 24.51005 22.86559 0.3125 25.35064 22.47367 0.3125 25.35064 22.47367 6.390772e-11 18.44751 32.64873 30.11269 18.5233 32.53801 30.96866 18.62957 32.47702 30.95636 17.9071 31.76841 33.6249 17.68052 31.85678 33.71479 17.89612 31.72348 33.69126 18.88765 32.39609 30.05905 17.68993 31.90195 33.64888 12.16534 35.26796 34.03051 12.24377 35.03496 34.71066 12.48251 34.94841 34.54961 19.94549 31.56131 31.40724 19.28318 31.97543 31.43449 19.91413 31.4803 31.73418 11.9117 35.35552 34.20209 18.94259 32.29464 30.92408 18.9909 32.33567 30.04803 11.75397 35.4769 33.97173 11.27784 35.63234 34.31908 11.44768 35.51034 34.54016 16.29064 33.53596 32.21545 16.17866 33.59105 32.24496 16.37639 33.24773 32.86218 19.041 32.23646 30.91514 17.1423 32.7902 32.81056 16.38746 33.19 32.97388 16.40174 33.0997 33.13968 19.29164 32.08643 30.89498 19.97641 31.66272 30.85883 17.1448 32.7021 32.98105 12.19776 35.25662 34.00921 12.51303 34.93721 34.52963 17.31178 32.6095 32.95157 17.31083 32.57058 33.02439 15.33164 34.16461 31.67359 15.07258 34.28012 31.76149 15.46018 34.01169 32.15107 13.98518 34.04204 34.40166 18.04903 31.61371 33.69397 17.89318 31.7117 33.7084 12.01416 35.38891 33.79538 17.14143 32.80771 32.77532 12.04741 35.37751 33.77348 16.38419 33.20797 32.93961 16.37752 33.24222 32.87305 14.1534 33.96859 34.32095 18.05226 31.62545 33.67674 17.7314 32.12879 33.29179 17.29957 32.3806 33.35418 14.22746 33.9359 34.28649 10.16114 36.09711 33.59953 10.9834 35.80555 33.94782 10.48159 36.00536 33.34497 10.68203 35.89688 34.18591 10.16778 36.04633 34.62682 13.88591 34.2476 34.12023 12.67265 34.73305 34.80992 17.27396 32.15118 33.70625 17.13941 32.84105 32.70686 17.13904 32.84641 32.69569 11.47939 35.64916 33.58487 11.00864 35.84773 32.95673 18.06439 31.67019 33.61007 16.12574 33.69787 31.95314 13.86299 34.29008 34.05818 12.56507 34.87426 34.61958 12.64094 34.77632 34.75316 17.31192 32.69708 32.78008 17.31159 32.71448 32.74463 14.05987 34.17355 34.03646 17.3106 32.7476 32.67577 16.24034 33.64219 31.92239 13.8076 34.38616 33.91211 14.03818 34.2159 33.97373 17.3104 32.75292 32.66453 17.95685 31.99384 33.26531 13.79591 34.40534 33.88193 12.54918 34.89383 34.59198 14.13644 34.1406 34.00068 18.33473 31.43077 33.67295 11.75032 35.56051 33.40051 18.33851 31.44242 33.65558 17.75685 32.31612 32.95711 13.77298 34.44196 33.82332 12.51812 34.93119 34.53838 11.78493 35.54902 33.37762 11.29634 35.75812 32.75938 12.84061 35.23306 31.85105 14.1153 34.18288 33.93766 18.35273 31.48682 33.58836 18.42381 31.38704 33.65063 13.76921 34.44786 33.81375 13.98568 34.31166 33.82607 17.76084 32.35443 32.8832 13.97459 34.33078 33.79556 18.12014 31.89458 33.24872 18.43866 31.43134 33.58325 14.06408 34.2785 33.78931 14.81382 34.44998 30.99491 13.81818 34.86127 31.38887 14.349 34.59039 32.03432 13.9528 34.36727 33.7363 17.76806 32.44053 32.7091 14.75064 33.69882 34.06089 17.9897 32.17973 32.92818 8.931295 36.03801 38.37135 13.94922 34.37314 33.72663 8.922149 36.04413 38.36668 16.02197 33.84511 31.46324 8.295024 36.38458 38.23017 17.76917 32.45762 32.67311 8.370193 36.36723 38.08897 8.11537 36.48834 37.96317 7.600209 36.67519 37.90335 14.05324 34.29759 33.75865 17.99529 32.21772 32.85371 14.03196 34.33402 33.69912 8.716983 36.28505 37.4974 14.02846 34.33989 33.6894 9.603993 35.86583 37.27927 7.681185 36.65829 37.75192 6.873794 36.86463 37.57098 17.77097 32.49013 32.60319 14.93216 33.614 33.98967 9.753383 35.82095 37.09422 17.77122 32.49536 32.59178 14.67731 33.9015 33.76618 9.74521 35.82708 37.0882 18.67515 31.22159 33.63964 8.472202 36.40672 37.35564 17.09661 33.12523 32.03034 14.66 33.94332 33.70118 9.842284 35.7962 36.97853 16.1408 33.78838 31.43043 15.94083 33.94318 30.63291 9.834214 35.80233 36.97238 13.53075 34.76013 33.24459 18.4195 31.70925 33.22386 9.099397 36.19025 36.9329 18.15835 32.07941 32.90985 14.86493 33.81593 33.69203 8.054548 36.57791 37.1176 18.69185 31.26559 33.57179 10.1811 35.67526 36.66132 14.61769 34.03787 33.54817 15.08731 34.33108 30.89918 18.75418 31.16886 33.63728 10.19516 35.67116 36.64488 14.60868 34.05673 33.51656 10.13384 35.7133 36.62136 18.00618 32.30301 32.6783 14.84894 33.85759 33.62638 10.12611 35.71943 36.61484 18.16509 32.11714 32.83499 10.148 35.70921 36.60481 13.72157 34.68416 33.15123 18.50872 31.65317 33.21784 9.25026 36.15165 36.72983 18.77146 31.21276 33.56929 14.59094 34.09273 33.45515 18.00805 32.31993 32.64204 10.14029 35.71534 36.59827 14.58801 34.09852 33.44513 13.80556 34.65032 33.1113 8.86554 36.3124 36.77599 17.27764 33.02948 31.9952 9.345315 36.12698 36.60674 18.0113 32.35211 32.57158 13.41407 34.87783 32.98677 9.02067 36.27395 36.56748 15.78105 32.97757 34.04225 9.118402 36.24936 36.44111 18.01178 32.35727 32.56008 14.80971 33.95173 33.47184 17.06497 33.22687 31.72882 8.465863 36.48468 36.51251 9.656907 36.0442 36.22679 18.17865 32.20183 32.65864 14.80133 33.97051 33.43991 18.18106 32.21863 32.62218 15.53389 33.32319 33.77799 9.672041 36.0401 36.20918 14.7848 34.00634 33.37789 8.628015 36.44658 36.29487 18.46753 31.89206 32.88189 14.78207 34.01211 33.36776 11.0585 35.32775 36.00314 18.9743 31.0766 33.56531 9.438704 36.16679 36.05101 13.60962 34.80127 32.89057 18.18536 32.25056 32.55135 8.730151 36.4222 36.16297 13.69568 34.76717 32.84942 9.454258 36.1627 36.03293 18.18601 32.25568 32.53979 18.77159 31.48562 33.20375 15.74964 33.21525 33.71086 15.48678 33.52246 33.47118 10.95514 35.42721 35.89066 18.47637 31.92933 32.80633 13.20668 35.04403 32.55383 10.93361 35.44708 35.86742 17.25014 33.13001 31.69186 15.47514 33.56352 33.40349 11.23305 35.27112 35.84042 18.55967 31.83537 32.87496 10.89163 35.48502 35.82229 18.85425 31.43221 33.20045 16.33599 32.62395 33.97183 18.56914 31.87249 32.79919 16.33597 32.63616 33.95561 10.88475 35.49113 35.81492 14.39838 34.40458 32.84879 11.2589 35.26265 35.81694 18.49482 32.01289 32.62831 17.76434 32.76553 31.91204 16.33556 32.68272 33.89285 11.13279 35.37047 35.72524 16.43067 32.57184 33.9494 18.49822 32.02944 32.5915 16.43083 32.58402 33.93312 11.1119 35.39031 35.70144 13.40995 34.96648 32.45288 11.1591 35.36197 35.70136 18.58904 31.95571 32.62069 15.70971 33.41351 33.40094 11.1383 35.38182 35.67748 18.50444 32.0609 32.52 15.44603 33.65623 33.24414 11.07115 35.42821 35.65522 18.50541 32.06595 32.50832 11.06447 35.43431 35.64768 15.43973 33.67471 33.21121 19.06487 31.29457 33.19445 16.43111 32.6305 33.87011 11.09773 35.41971 35.63111 18.59274 31.97218 32.58378 13.49939 34.93192 32.40968 13.05586 35.15386 31.74243 11.09109 35.42581 35.62354 18.83116 31.66596 32.85826 15.69963 33.45434 33.33256 16.99549 33.36493 31.22271 16.84118 33.50559 30.40271 9.064784 36.34018 35.75583 14.60389 34.31652 32.76541 9.08103 36.33611 35.73697 9.363251 36.31225 34.30366 8.455833 36.53423 35.2565 15.4272 33.70996 33.14726 18.59953 32.0035 32.51207 7.972366 36.64275 35.85237 8.081411 36.61886 35.71149 15.42512 33.71563 33.13682 18.60059 32.00853 32.50037 11.73604 35.07176 35.49254 14.30302 34.51938 32.57863 18.84249 31.70266 32.7819 15.67413 33.5465 33.17159 11.69737 35.11548 35.44076 18.91654 31.61196 32.85415 15.66856 33.56486 33.13832 10.46579 35.8154 35.37671 16.32536 32.91752 33.55324 18.01835 32.62396 31.87509 11.60526 35.21445 35.3189 18.92845 31.64852 32.77761 15.65746 33.59988 33.0737 19.49995 30.63861 33.65892 11.58604 35.23423 35.29372 17.74792 32.86294 31.60396 15.65561 33.60551 33.06315 14.51351 34.43053 32.49252 11.99154 34.9824 35.29111 19.50596 30.64988 33.64104 11.54853 35.27198 35.24482 16.42457 32.86477 33.52915 17.18733 33.2661 31.18272 11.54239 35.27807 35.23684 18.86667 31.78483 32.60199 16.30452 33.11292 33.23547 19.52881 30.69278 33.57179 10.65722 35.7583 35.19893 18.87124 31.80109 32.56478 17.10651 32.13589 33.87868 10.68556 35.74975 35.17328 14.1304 34.68059 32.12501 18.2023 32.51977 31.85106 11.95478 35.02602 35.23788 19.13408 31.47277 32.84613 16.29855 33.15309 33.16534 10.26978 35.93809 35.17821 11.86715 35.12474 35.11259 18.95397 31.73035 32.59726 17.11257 32.1839 33.81285 18.87971 31.83197 32.4925 16.40701 33.05965 33.21009 11.84885 35.14447 35.08671 18.88104 31.83693 32.4807 17.11402 32.1959 33.79614 18.95882 31.74654 32.55996 15.28456 34.01408 32.51555 10.46637 35.88093 34.99567 19.14746 31.50897 32.76913 11.81312 35.18214 35.03643 18.00768 32.71964 31.56461 17.11929 32.24169 33.73148 11.80726 35.1882 35.02823 18.96782 31.77728 32.4875 17.25861 32.04576 33.85424 10.49547 35.87236 34.96932 18.96924 31.78222 32.47567 12.41274 34.83012 34.98458 19.17642 31.58994 32.58768 16.28263 33.24367 33.00023 9.932347 36.11209 34.84488 13.15054 35.11855 31.69591 18.19576 32.61417 31.53888 19.18196 31.60594 32.55015 12.37912 34.87353 34.92911 17.26583 32.0936 33.78806 16.27902 33.2617 32.9661 19.64071 30.90648 33.19569 11.16594 35.60098 34.76209 18.53944 32.32511 31.81289 17.26757 32.10556 33.77126 12.29879 34.9718 34.79857 19.1923 31.63632 32.47725 16.2717 33.29607 32.89982 10.13743 36.0549 34.65432 17.70289 32.99348 31.08691 12.28198 34.99143 34.77159 19.19394 31.64119 32.46534 18.6399 32.26618 31.80297 16.27047 33.3016 32.889 12.64319 34.74417 34.8292 17.04311 33.40333 30.35792 9.581624 36.25524 34.10009 17.97184 32.84714 31.04356 15.52841 33.90164 32.43546 18.54047 32.41709 31.49765 12.24915 35.02892 34.71921 15.21053 34.12524 32.23408 19.72886 31.08026 32.84207 12.61126 34.78746 34.77258 18.93587 32.09003 31.77761 18.64317 32.35742 31.48683 19.74629 31.11543 32.76386 17.139 32.47204 33.38135 10.98867 35.72328 34.54705 18.16654 32.7394 31.01499 19.02894 32.03385 31.77082 17.66767 31.79754 33.7989 12.53489 34.88544 34.63933 19.78461 31.19389 32.57952 19.79206 31.20936 32.54139 12.5189 34.90501 34.6118 17.678 31.84493 33.73181 19.80608 31.2387 32.46731 18.94572 32.17903 31.45888 19.80831 31.2434 32.45521 17.14499 32.66296 33.05344 12.48764 34.94239 34.55834 19.26603 31.88903 31.75606 19.04085 32.12213 31.45128 17.88123 31.66455 33.77593 17.86817 32.96936 30.20001 16.06086 -32.87874 33.89466 16.35129 -32.63098 33.94763 16.0662 -32.7853 34.02007 12.01583 -35.11575 34.8727 12.25565 -35.03066 34.70255 12.05576 -35.07216 34.93231 16.33603 -32.974 33.4475 17.16236 -32.6901 32.98222 17.15921 -32.52606 33.27338 16.35013 -32.72388 33.8207 12.18016 -35.26277 34.0208 12.72338 -35.0679 33.6828 13.00812 -34.75091 34.22368 12.49651 -34.94323 34.54057 12.52553 -35.29406 32.92152 13.23094 -35.03485 32.54158 12.75906 -35.12495 33.33761 17.74765 -32.86308 31.60386 18.01517 -32.71545 31.56333 17.76408 -32.76567 31.91195 15.79167 -32.93037 34.09742 12.86634 -35.22368 31.83795 13.51876 -34.92442 32.40038 12.86629 -35.22369 31.83787 13.17104 -35.11088 31.68591 13.17108 -35.11086 31.68598 12.34595 -35.35748 33.02645 12.58645 -35.18772 33.43783 17.29303 -33.02128 31.9923 17.77096 -32.49544 32.5918 17.32496 -32.74488 32.66207 17.15703 -32.83661 32.6924 15.7823 -33.02432 33.97355 11.92427 -35.35123 34.19338 17.97959 -32.84287 31.04214 18.52816 -32.42419 31.49865 18.51056 -32.54528 30.96981 17.87635 -32.96495 30.19847 12.02936 -35.3837 33.78539 16.31559 -33.14211 33.16538 17.16234 -32.69243 32.97785 11.76687 -35.47259 33.96277 11.66939 -35.43724 34.37455 16.31523 -33.1445 33.16115 17.16011 -32.78048 32.80725 11.40459 -35.2127 35.69253 12.15961 -34.95137 35.08985 11.40212 -35.21531 35.68951 12.15748 -34.95397 35.08657 16.03483 -33.13056 33.52606 11.76614 -35.55525 33.39006 17.11563 -33.11524 32.02654 11.30484 -35.31453 35.57181 12.07334 -35.05248 34.95872 16.29957 -33.23503 32.99593 17.1593 -32.79797 32.772 12.11885 -35.48779 32.24608 12.1188 -35.48781 32.246 17.26588 -33.12171 31.68881 11.92837 -35.55227 32.35855 11.28456 -35.33434 35.5475 15.57272 -33.13158 34.03798 16.29601 -33.25305 32.96179 11.2478 -35.26452 35.83224 17.70261 -32.99363 31.0868 11.24526 -35.26713 35.82929 17.06027 -33.39457 30.35427 15.54099 -33.14765 34.04813 11.50535 -35.55896 34.14894 11.23857 -35.37825 35.49262 16.28759 -33.29288 32.88471 11.92842 -35.55226 32.35863 11.31313 -35.7528 32.74819 16.00573 -33.30003 33.24749 11.14521 -35.36647 35.71392 11.49282 -35.64482 33.57551 11.12437 -35.38631 35.69009 16.00524 -33.30245 33.24331 15.74476 -33.27772 33.60956 11.07471 -35.32076 35.99309 11.07209 -35.32338 35.99021 17.08441 -33.21676 31.72483 15.98463 -33.39382 33.08019 11.0771 -35.43026 35.63629 11.00461 -35.34503 36.05489 15.98007 -33.41201 33.04649 10.96897 -35.42283 35.87751 15.52652 -33.38612 33.67759 10.9475 -35.44269 35.85423 11.22044 -35.73177 33.77006 15.96938 -33.45225 32.9704 10.9003 -35.44452 35.94326 15.49347 -33.40236 33.68829 10.89881 -35.48669 35.80169 15.70729 -33.44845 33.33454 10.87858 -35.46439 35.92021 10.82933 -35.5084 35.86816 10.84253 -35.70195 35.03403 15.70667 -33.45088 33.33041 19.92248 -30.19867 33.8299 17.20363 -33.25764 31.17941 19.96448 -30.26559 33.72528 11.31318 -35.75278 32.74826 11.02291 -35.84335 32.94671 19.98848 -30.30389 33.66334 10.6706 -35.75427 35.18677 15.68129 -33.54302 33.16939 20.04104 -30.38793 33.52177 17.01564 -33.35462 31.2184 19.73668 -30.43338 33.70967 19.75916 -30.47197 33.64802 10.65665 -35.82448 34.82633 15.67574 -33.56137 33.13612 11.02296 -35.84333 32.94678 15.48273 -33.55776 33.40533 19.80827 -30.55668 33.50715 10.4807 -35.81099 35.36258 15.48202 -33.56021 33.40125 20.17902 -30.60993 33.10335 19.31464 -30.78895 33.63073 10.48011 -35.87689 34.98318 15.44872 -33.57414 33.41645 10.40668 -35.8328 35.43323 19.93657 -30.78085 33.09098 15.448 -33.57659 33.41238 9.792868 -36.19876 33.91121 10.73359 -35.93105 33.15494 20.2682 -30.75477 32.78536 15.66286 -33.60198 33.06101 20.26944 -30.7568 32.78058 10.28509 -35.93368 35.1637 19.35712 -30.87492 33.49129 16.19676 -33.58219 32.24015 10.33587 -35.99837 34.47753 20.31594 -30.83293 32.59384 20.32505 -30.8479 32.55522 15.45303 -33.6529 33.24185 10.20907 -35.95551 35.23625 15.44674 -33.67137 33.20892 10.17813 -35.6761 36.66485 20.01882 -30.92751 32.77484 15.41846 -33.66936 33.25323 20.01996 -30.92957 32.77009 10.12317 -35.72023 36.61843 15.41206 -33.68785 33.22036 15.4322 -33.71224 33.13458 10.15176 -36.05086 34.64128 20.34501 -30.88078 32.46798 20.06256 -31.00683 32.58448 9.948323 -36.10768 34.82973 15.39727 -33.72876 33.14613 9.913025 -35.78018 36.87275 20.07087 -31.02204 32.54609 9.869002 -36.1295 34.90546 16.14426 -33.68891 31.94813 15.86027 -33.7451 32.33413 9.844598 -35.7994 36.95923 19.46671 -31.10312 33.07968 9.753716 -35.82469 37.07713 20.08905 -31.05546 32.4594 15.79989 -33.85355 32.04589 9.792916 -36.19875 33.91126 18.88445 -31.19622 33.49247 15.53607 -33.89807 32.43303 19.53556 -31.25315 32.76726 9.653706 -36.04505 36.23055 16.86241 -33.49491 30.39798 16.8624 -33.49491 30.39793 9.596942 -36.25119 34.08622 9.596891 -36.25121 34.08617 16.04118 -33.83598 31.4579 9.601631 -35.86644 37.2827 19.53651 -31.25527 32.76257 15.29203 -34.01066 32.51302 9.435414 -36.16764 36.05487 20.48016 -31.10749 31.73702 15.25507 -34.02753 32.52556 9.429393 -36.10493 36.5008 19.57155 -31.33463 32.57922 15.46802 -34.00809 32.14855 19.57833 -31.35029 32.54131 9.380323 -36.30784 34.28754 9.380265 -36.30786 34.28748 14.37116 -33.92775 34.11723 18.97452 -31.42842 33.08593 9.35633 -36.1241 36.59271 15.68404 -34.00365 31.56196 19.59307 -31.38473 32.45568 9.295839 -36.32957 34.36843 9.25927 -36.14932 36.718 18.32926 -31.45202 33.65142 14.21541 -33.99671 34.18745 20.21025 -31.28714 31.73307 9.204839 -36.22737 36.33234 15.21818 -34.1218 32.23146 18.35716 -31.54055 33.51552 9.129725 -36.24649 36.4267 15.18034 -34.13882 32.24445 20.52381 -31.18345 31.40558 9.061347 -36.34102 35.75986 19.02936 -31.58179 32.7776 14.29362 -34.10371 33.86109 9.096797 -36.19091 36.93648 19.0301 -31.58396 32.77297 9.029933 -36.27163 36.55535 19.05722 -31.6654 32.5921 8.820471 -36.40038 36.04945 14.29241 -34.10622 33.85725 13.97453 -34.10152 34.30159 8.862866 -36.31306 36.77967 20.24805 -31.36555 31.40375 17.89286 -31.68201 33.74477 8.741984 -36.41935 36.14794 14.2441 -34.2015 33.70735 19.06238 -31.68149 32.55471 14.13328 -34.17318 33.93371 8.637697 -36.44428 36.28221 8.963754 -36.00593 38.44385 17.9031 -31.72266 33.68597 15.33976 -34.16094 31.67092 8.715856 -36.28533 37.49918 19.07352 -31.71694 32.47026 14.132 -34.1757 33.9299 8.922201 -36.04409 38.36677 14.23386 -34.22051 33.67639 8.940558 -36.01178 38.48776 18.42552 -31.77697 33.11503 8.177812 -36.59745 35.59023 8.434901 -36.53906 35.281 14.21044 -34.26261 33.60648 17.65625 -31.74801 33.86739 8.898536 -36.05002 38.41096 17.92472 -31.81222 33.55178 8.463068 -36.48533 36.51635 14.08105 -34.27129 33.78141 8.875139 -36.05586 38.4552 8.295024 -36.38458 38.23017 19.68711 -31.62561 31.73857 15.83584 -33.9923 30.6632 15.83581 -33.99231 30.6631 8.471043 -36.407 37.35747 20.57404 -31.27589 30.84971 8.17788 -36.59744 35.59028 17.67217 -31.81915 33.76861 17.68095 -31.86002 33.71021 14.07028 -34.29037 33.75073 8.094106 -36.61606 35.69548 8.094038 -36.61607 35.69542 15.08052 -34.27662 31.75872 7.982773 -36.64049 35.83889 7.982696 -36.6405 35.83884 18.46474 -31.93383 32.81153 15.04125 -34.29393 31.77247 8.370164 -36.36724 38.08903 13.88527 -34.27876 34.05166 18.46525 -31.93605 32.80698 8.344831 -36.3731 38.13602 13.88388 -34.28129 34.04792 8.319782 -36.37888 38.18307 8.053336 -36.57818 37.11951 17.69931 -31.95009 33.57697 6.873794 -36.86463 37.57098 20.2891 -31.46234 30.85139 14.04565 -34.33261 33.68149 8.115341 -36.48835 37.96322 13.82884 -34.37733 33.90166 19.71352 -31.70856 31.41347 8.089268 -36.49416 38.01149 18.48352 -32.01965 32.62901 13.81723 -34.3965 33.87145 8.063488 -36.4999 38.05981 7.600209 -36.67519 37.90335 17.97531 -32.05189 33.15657 7.681155 -36.65829 37.75197 15.09589 -34.32731 30.89626 15.45919 -34.16524 30.77733 7.653866 -36.66401 37.80238 13.79071 -34.43896 33.80325 7.626882 -36.66965 37.85284 18.48689 -32.03621 32.59223 13.38526 -34.34856 34.61084 18.49399 -32.0727 32.50915 17.27491 -32.05973 33.82242 13.99838 -34.57174 33.02221 15.09592 -34.3273 30.89635 14.8222 -34.44637 30.99189 19.13899 -31.96689 31.76319 13.2355 -34.40925 34.69667 17.28108 -32.10098 33.76478 13.82374 -34.64297 33.10272 17.74064 -32.19139 33.18463 13.2784 -34.52751 34.3709 17.12534 -32.14824 33.84634 13.27676 -34.53007 34.36731 18.00172 -32.21144 32.85726 18.00204 -32.2137 32.85277 13.89325 -34.68796 32.75757 17.29356 -32.19195 33.6333 14.82224 -34.44635 30.99198 14.78073 -34.46418 31.00684 17.13053 -32.18963 33.789 14.78076 -34.46417 31.00693 19.73661 -31.81342 30.8681 13.21162 -34.62712 34.22691 19.15334 -32.05432 31.44268 18.01304 -32.29897 32.67731 13.12414 -34.58861 34.45944 13.12243 -34.59117 34.45588 13.19793 -34.6465 34.19792 17.14081 -32.28093 33.65822 18.01493 -32.31587 32.64105 13.55351 -34.75113 33.23326 13.71431 -34.75977 32.84058 17.76037 -32.35228 32.88758 13.16676 -34.68942 34.13246 17.7606 -32.35456 32.88313 13.0547 -34.68845 34.31707 18.01871 -32.35317 32.55916 13.04049 -34.70788 34.2884 17.31824 -32.43606 33.24636 12.75274 -34.59923 34.99514 17.7678 -32.44066 32.70903 18.5274 -32.3321 31.81381 13.4374 -34.86876 32.97509 17.76891 -32.45774 32.67305 13.70469 -34.85162 32.31319 12.52558 -34.68566 35.14786 12.62675 -34.77978 34.76714 19.15735 -32.16714 30.90493 17.32592 -32.59926 32.95355 12.62482 -34.78236 34.76372 17.32597 -32.60158 32.94915 12.89174 -35.00553 33.58538 12.54868 -34.88032 34.63032 16.35117 -32.58891 34.0033 12.53275 -34.89989 34.60277 17.32633 -32.68911 32.77758 12.39265 -34.86673 34.92451 17.32605 -32.70649 32.74213 12.39062 -34.86931 34.92116 18.02567 -32.61981 31.87389 12.31049 -34.96756 34.79048 12.29373 -34.98719 34.76349 13.36788 -35.03641 31.59203 8.143141 36.42881 41.1847 8.235429 36.31401 40.66961 8.042648 36.43278 40.62669 8.50871 36.15827 39.31418 8.346051 36.30036 38.7782 8.134133 36.37761 39.17392 8.709401 36.07933 38.93391 8.756689 35.93955 40.79388 8.780775 35.91575 40.69223 8.480863 36.14799 40.72654 7.445809 36.70415 39.9509 6.873828 36.8854 39.22163 6.672621 36.97583 39.76436 8.39043 36.26324 41.22835 7.510005 36.86149 41.54566 9.159487 35.68567 41.77916 7.631104 36.61039 39.45048 9.16416 35.58019 40.79699 8.420713 36.19717 39.5024 8.041297 36.41577 39.36996 9.141259 35.60424 40.89465 8.689862 36.03798 39.38348 8.668504 36.05551 41.28127 6.416271 37.19124 40.94993 5.565613 37.4639 41.42602 5.599721 37.35731 40.87351 9.304437 35.44226 40.83758 5.706419 37.23954 40.2039 6.518999 37.07571 40.33298 9.281994 35.46642 40.93385 8.344539 36.23381 39.67962 7.96101 36.45179 39.55465 9.056556 35.72161 41.36295 8.604249 36.07717 39.56801 9.198689 35.58444 41.39551 7.78297 36.54682 40.03742 9.48393 35.28046 41.46596 7.330597 36.78209 40.35605 6.548787 37.05256 40.20413 7.302625 36.80534 40.47475 8.530104 36.11407 39.74173 8.837693 35.90967 39.65309 7.313271 36.74643 38.35218 6.185412 37.02307 38.77246 7.671731 36.62531 40.42812 7.071028 36.81662 38.79463 8.175181 36.33016 40.14255 6.965163 36.85182 39.01436 8.766166 35.94684 39.82246 7.644605 36.64864 40.54259 5.737931 37.21638 40.06397 5.73753 37.21643 40.0639 8.365044 36.21098 40.19535 8.033104 36.46219 38.64669 7.204221 36.91978 41.04346 8.068742 36.40932 40.517 7.811742 36.53763 39.05614 8.606668 36.04441 40.26453 8.261002 36.29048 40.56216 7.714842 36.57502 39.25915 7.548296 36.76298 41.0911 8.878073 35.83531 40.34516 8.505751 36.12434 40.62187 7.948985 36.54734 41.15247 7.715334 -36.57493 39.25861 7.814499 -36.52794 39.94223 7.478564 -36.68547 39.85221 6.708054 -36.95764 39.65727 6.965708 -36.85174 39.01379 8.320232 -36.25174 40.57684 8.24753 -36.32637 40.91301 8.182392 -36.34016 40.54399 8.539524 -36.12305 40.97449 7.737088 -36.56624 39.21152 6.989462 -36.84354 38.9628 8.205238 -36.31106 40.05131 8.068458 -36.4094 40.5174 7.671428 -36.62538 40.42855 8.317321 -36.24157 40.08354 8.610051 -36.04799 40.64857 8.041767 -36.41568 39.36944 8.062614 -36.40682 39.32397 7.971685 -36.48208 38.7544 7.246027 -36.76484 38.46847 8.452892 -36.15284 40.12313 9.01962 -35.72891 41.08542 9.159487 -35.68567 41.77916 6.4644 -37.12658 40.61018 7.510005 -36.86149 41.54566 5.565613 -37.4639 41.42602 8.125615 -36.43366 38.49273 5.737252 -37.21641 40.06445 7.4146 -36.72014 38.18612 8.421155 -36.19707 39.50189 6.54843 -37.05262 40.20461 8.737831 -35.94842 40.20866 7.250899 -36.85605 40.73019 8.440922 -36.18805 39.45825 6.185705 -37.02297 38.77176 9.239464 -35.51892 41.14108 7.330278 -36.78216 40.35649 8.287265 -36.32076 38.88234 8.529923 -36.12714 39.54065 7.594236 -36.69942 40.78892 9.086283 -35.6529 40.77544 8.549375 -36.11808 39.49752 8.661449 -36.03791 39.58804 8.434579 -36.27107 38.62928 7.993956 -36.48374 40.86277 8.680517 -36.02881 39.54551 9.304211 -35.44234 40.83794 8.653744 -36.10019 39.03403 8.108695 -36.41462 40.88516 8.937757 -35.83259 39.68952 8.758753 -36.0298 39.07817 8.793199 -36.04935 38.79066 26.45124 22.92013 6.513075e-11 28.01894 20.97472 5.960374e-11 24.74874 24.74874 7.032587e-11 22.92013 26.45124 7.516262e-11 -5.489359e-14 -35 -1.064926e-10 2.496871 -34.91082 -9.919124e-11 4.981019 -34.64375 -9.843166e-11 7.439785 -34.20014 -9.71705e-11 9.860639 -33.58225 -9.541418e-11 12.23125 -32.79324 -9.317165e-11 14.53953 -31.83712 -9.045434e-11 16.77371 -30.71876 -8.72761e-11 18.92243 -29.44387 -8.365311e-11 20.97472 -28.01894 -7.960385e-11 22.92013 -26.45124 -7.514895e-11 24.74874 -24.74874 -7.03111e-11 26.45124 -22.92013 -6.511497e-11 28.01894 -20.97472 -5.958702e-11 29.44387 -18.92243 -5.375544e-11 30.71876 -16.77371 -4.764992e-11 31.83712 -14.53953 -4.13016e-11 32.79324 -12.23125 -3.474281e-11 33.58225 -9.860639 -2.800698e-11 34.20014 -7.439785 -2.112843e-11 34.64375 -4.981019 -1.414222e-11 34.91082 -2.496871 -7.083937e-12 35 -7.625663e-15 1.044034e-14 2.496871 34.91082 9.919272e-11 2.865069e-14 35 -1.064926e-10 34.91082 2.496871 7.104764e-12 4.981019 34.64375 9.843463e-11 34.64375 4.981019 1.416288e-11 7.439785 34.20014 9.717494e-11 34.20014 7.439785 2.114883e-11 9.860639 33.58225 9.542006e-11 33.58225 9.860639 2.802701e-11 32.79324 12.23125 3.476237e-11 12.23125 32.79324 9.317895e-11 14.53953 31.83712 9.046301e-11 31.83712 14.53953 4.132059e-11 16.77371 30.71876 8.72861e-11 30.71876 16.77371 4.766825e-11 18.92243 29.44387 8.36644e-11 29.44387 18.92243 5.3773e-11 20.97472 28.01894 7.961636e-11 -6.73484e-14 -24.49141 83.79851 -6.941066e-14 -27.12985 80.15549 4.65 -24.49141 83.79851 4.65 -27.12985 80.15549 4.596995 -37.21717 37.57098 4.7 -38.77383 45.30918 5.422756 -39.31499 46.66567 5.415564 -39.41542 46.85608 5.346814 -40.41449 48.5252 5.131311 -40.43612 48.51565 4.915705 -40.45687 48.5065 4.7 -40.47674 48.49773 2.302843 -37.42923 37.57098 4.7 -37.5 40.98409 -6.908456e-14 -37.5 37.57098 5.533431 -37.24727 40.06445 4.938838 -37.33076 40.06445 4.34329 -37.40473 40.06445 5.488543 -38.42993 44.71625 5.023723 -37.97237 43.1821 4.7 -38.0138 43.1821 5.476336 -38.58978 45.11266 5.112014 -38.63973 45.11266 4.7 -41.33279 50.03776 5.2734 -41.71543 51.12278 4.7 -41.95374 51.68732 5.165181 -42.35172 53.93165 4.7 -42.39614 54.01949 4.7 -42.37198 56.39598 5.022377 -42.29809 56.83467 4.7 -41.80102 58.97309 4.870651 -41.66931 59.32511 4.7 -40.53239 61.6143 4.7 -27.17165 80.09744 4.7 -40.1337 62.20015 6.333713 -39.94978 62.06695 6.293501 -24.31617 83.6716 7.825 -23.80239 83.2995 7.853824 -39.43129 61.69143 9.140128 -22.98509 82.70757 9.157771 -38.61321 61.09893 10.14926 -21.91997 81.93616 10.15758 -37.55073 60.32944 10.78363 -20.67961 81.03783 10.78578 -36.31555 59.43486 4.716712 -40.27031 62.00741 4.7 -40.27044 62.0075 4.733315 -40.40315 61.81206 4.7 -40.40344 61.81225 4.749802 -40.53215 61.61415 6.347452 -40.08084 61.87574 6.361091 -40.20814 61.68211 6.611975 -40.01546 61.83031 4.889425 -41.49375 59.76872 6.374626 -40.33163 61.48611 6.625007 -40.14151 61.63771 6.637937 -40.26377 61.44278 4.919738 -41.66761 59.32447 7.863661 -39.5535 61.50929 7.873422 -39.67213 61.32495 7.883104 -39.78713 61.13845 6.48887 -41.24687 59.66553 8.384959 -39.27319 61.31451 6.747034 -41.16921 59.63306 8.393195 -39.38786 61.13553 6.513586 -41.41094 59.2289 5.057359 -42.25795 57.07625 8.401364 -39.499 60.95447 6.770625 -41.33134 59.19926 5.070764 -42.29447 56.83415 9.163643 -38.72387 60.93278 9.169469 -38.83127 60.76465 9.175247 -38.93536 60.59458 7.964668 -40.63635 59.41032 7.982276 -40.78776 58.99686 9.795276 -38.11198 60.50758 8.470153 -40.31909 59.2777 6.625404 -41.95997 57.02711 9.79907 -38.21173 60.35183 6.636261 -41.9929 56.7907 9.802833 -38.30841 60.19427 6.877308 -41.87279 57.01274 8.484995 -40.46515 58.87674 6.887663 -41.90512 56.77805 10.16021 -37.64767 60.18493 5.19754 -42.37838 54.28098 10.16282 -37.74178 60.03868 5.212927 -42.34761 53.93206 10.16541 -37.83301 59.89073 9.223891 -39.70313 59.02021 9.234384 -39.83978 58.64388 8.061768 -41.28969 56.91659 10.69446 -36.65406 59.49447 8.069472 -41.31917 56.69363 9.834524 -39.02195 58.73547 10.69537 -36.73632 59.3687 10.78641 -36.39708 59.3159 10.69627 -36.8161 59.24143 8.551978 -40.94841 56.86032 6.738659 -42.04951 54.30397 9.841362 -39.14906 58.3867 10.78703 -36.4763 59.19544 8.558468 -40.97667 56.64428 10.78765 -36.55315 59.07353 6.751052 -42.01657 53.96493 6.985284 -41.95806 54.31036 10.18722 -38.50694 58.52019 5.30674 -41.84869 51.53282 6.997094 -41.925 53.97402 10.19193 -38.62717 58.19237 5.32063 -41.71094 51.12436 9.281725 -40.2915 56.752 9.28631 -40.31786 56.54937 10.70387 -37.40734 58.06053 8.142007 -41.35816 54.35229 5.356153 -41.23479 49.98167 9.87222 -39.56993 56.63302 8.15077 -41.32548 54.03355 10.79289 -37.12316 57.94174 10.70551 -37.51331 57.77763 9.875209 -39.59458 56.44516 8.619544 -41.01172 54.37651 6.826446 -41.51416 51.63771 10.79402 -37.22548 57.67045 8.62692 -40.97976 54.06788 7.068924 -41.42434 51.66588 10.21319 -39.02626 56.54337 6.837586 -41.37795 51.24211 10.21525 -39.04978 56.36667 7.079535 -41.2889 51.2736 9.329458 -40.34947 54.4228 9.334667 -40.31936 54.13346 6.866046 -40.90976 50.13608 7.135223 -40.02381 48.78318 10.71294 -37.86797 56.35238 7.106639 -40.82375 50.17694 8.204015 -40.84328 51.84808 10.71366 -37.88925 56.19946 9.903347 -39.62597 54.47337 10.79914 -37.56882 56.30305 8.211872 -40.71391 51.47692 10.79964 -37.58955 56.15628 9.906745 -39.59832 54.20506 8.671726 -40.51104 51.95226 10.23466 -39.08239 54.51137 8.678336 -40.38554 51.59304 10.237 -39.05674 54.25883 8.231934 -40.27074 50.43966 8.712994 -39.21982 49.31408 9.366309 -39.87922 52.15037 9.370976 -39.76149 51.81371 8.695211 -39.95592 50.58922 10.72046 -37.9263 54.59218 10.72128 -37.90514 54.37318 9.927386 -39.19182 52.36592 10.80433 -37.62789 54.61303 10.8049 -37.60791 54.4027 9.930432 -39.08289 52.05367 9.38289 -39.3586 50.87298 9.946398 -38.07069 50.0729 10.25124 -38.67645 52.52752 10.25335 -38.57426 52.23353 9.938206 -38.70992 51.18115 10.72628 -37.58185 52.87075 10.25871 -38.22404 51.41198 10.7309 -36.6738 50.99532 10.80835 -37.29943 52.9593 10.72702 -37.49415 52.61547 10.80886 -37.21549 52.71401 10.72891 -37.19271 51.90193 10.81017 -36.92667 52.02832 10.79828 12.3429 85.2378 10.54915 12.3429 86 10.54915 -12.3429 86 10.79828 -12.3429 85.2378 10.94937 -12.3429 84.45028 10.94937 12.3429 84.45028 -2.136871e-14 15.5 89.66399 4.65 15.5 89.66399 4.65 17.26093 89.17085 -4.65 17.26093 89.17085 4.65 18.94876 88.4671 -4.65 15.5 89.66399 -4.65 18.94876 88.4671 4.65 20.53841 87.56319 -4.65 20.53841 87.56319 4.65 22.00626 86.47256 -4.65 22.00626 86.47256 4.65 23.33048 85.21142 -8.887913e-15 24.49141 83.79851 4.65 24.49141 83.79851 -4.65 23.33048 85.21142 -4.65 24.49141 83.79851 4.65 -23.33048 85.21142 -4.65 -23.33048 85.21142 4.65 -22.00626 86.47256 -4.65 -24.49141 83.79851 -4.65 -22.00626 86.47256 4.65 -20.53841 87.56319 -4.65 -20.53841 87.56319 4.65 -18.94876 88.4671 -4.65 -18.94876 88.4671 4.65 -17.26093 89.17085 -5.836689e-14 -15.5 89.66399 4.65 -15.5 89.66399 -4.65 -17.26093 89.17085 -4.65 -15.5 89.66399 10.14926 -19.30305 84.55965 9.500547 -19.30806 85.67714 9.500547 -19.8464 85.30594 10.78363 -17.96693 83.62128 9.500547 -15.85975 87.25344 9.500204 -15.5 87.35071 8.38072 -16.14676 88.25344 10.78363 -16.87606 84.24157 10.14926 -18.80369 84.90398 5.851377 -20.47575 87.46714 5.851377 -18.89825 88.36413 7.01276 -18.74796 88.05774 10.14926 -19.96085 84.0442 9.500547 -20.55555 84.75025 10.78363 -13.77969 85.19273 10.50512 -13.89348 86 9.500547 -21.36849 84.00298 8.38072 -22.10506 84.73771 8.38072 -21.22578 85.54596 9.500547 -16.52261 87.04346 10.78363 -18.40162 83.32154 8.38072 -16.86371 88.02632 10.14926 -15.60508 86.36613 10.35224 -15.5 86 10.14926 -20.71491 83.35105 5.851377 -21.10434 87.03369 10.78363 -18.97422 82.87285 10.78363 -19.63062 82.26947 8.38072 -18.41523 87.37941 7.01276 -17.11143 88.74011 7.01276 -20.28929 87.18131 10.78363 -14.50941 85.06292 10.14926 -16.21994 86.17135 5.851377 -21.93237 86.38484 7.01276 -20.90348 86.75781 10.78363 -15.18258 84.89406 9.500547 -17.95706 86.44535 8.38072 -19.87649 86.5485 7.01276 -21.71252 86.12383 10.78363 -15.71781 84.72451 5.851377 -22.8816 85.51231 10.14926 -17.55052 85.61656 8.38072 -20.45876 86.147 5.851377 -16.44934 89.30769 7.012756 -15.5 89.19724 5.851376 -15.5 89.54666 7.01276 -22.63998 85.2713 5.851377 -17.22332 89.06251 7.01276 -16.35519 88.97966 8.380615 -15.5 88.42206 7.370585 16.31205 88.82935 7.370585 17.06016 88.59237 6.056279 17.20923 89.02189 6.056279 15.59982 89.48057 7.370449 15.5 89.03676 6.056279 16.43748 89.26636 8.580819 16.81407 87.88329 8.580819 18.54315 87.14608 7.370585 21.61178 86.00423 6.056279 23.21498 85.10408 6.056279 21.90468 86.35196 10.78363 17.96693 83.62128 7.370585 22.88195 84.79457 10.78363 18.40162 83.32154 10.35224 19.07885 84.25172 6.056279 21.07904 86.99894 10.35224 18.59558 84.58495 6.056279 20.45226 87.43113 10.35224 17.54608 85.19285 9.55653 19.27135 85.62087 9.55653 18.10842 86.29447 9.55653 21.63176 83.63269 10.14926 21.91997 81.93616 9.140128 22.98509 82.70757 8.580819 16.10499 88.10791 8.580562 15.5 88.26628 9.556171 15.5 87.28134 8.580819 22.33215 84.28361 9.55653 16.50058 86.97998 7.370585 20.81143 86.63139 10.78363 17.02295 84.16806 8.580819 21.12824 85.43016 9.55653 15.84121 87.18885 9.993405 15.5 86.66095 10.35224 16.09506 85.8115 10.35224 15.5 86 7.370585 20.20385 87.05034 10.78363 15.71781 84.72451 6.056279 19.09112 88.21954 10.78363 15.18258 84.89406 10.35224 20.72576 82.79069 10.78363 20.67961 81.03783 10.78363 14.60165 85.04262 10.50512 13.89348 86 10.78363 13.95571 85.16637 8.580819 20.36965 86.0246 9.55653 20.51226 84.69885 8.580819 19.79376 86.42169 10.78363 19.88295 82.00742 7.370585 18.88441 87.8146 9.55653 19.80685 85.25161 10.35224 19.71546 83.75287 6.293501 24.31617 83.6716 10.78363 18.97422 82.87285 7.825 23.80239 83.2995 6.056257 15.5 89.50257 4.875115 41.69372 59.25862 4.7 41.67559 59.32489 4.7 40.53239 61.6143 4.7 42.31436 56.84536 5.028336 42.31231 56.72544 5.157455 42.36853 54.10743 4.7 42.38771 53.92855 5.259239 41.85508 51.5373 4.7 41.76324 51.09728 5.309008 41.24217 49.98382 4.7 40.47674 48.49773 4.915705 40.45687 48.5065 5.131311 40.43612 48.51565 5.346814 40.41449 48.5252 10.78703 36.47623 59.1954 10.78765 36.55301 59.07345 10.69537 36.73625 59.36866 10.78641 36.39707 59.31589 10.78578 36.31555 59.43486 10.69446 36.65404 59.49446 10.79418 37.23973 57.62986 10.79025 36.85456 58.53489 5.356067 41.23769 49.98594 5.324698 41.66682 51.00179 5.306539 41.85061 51.53867 6.865974 40.91259 50.14022 7.135223 40.02381 48.78318 7.10657 40.82656 50.18105 6.840846 41.3344 51.12343 7.08264 41.24562 51.15591 6.826285 41.51607 51.64338 5.222804 42.32175 53.70254 7.068771 41.42623 51.6715 8.231883 40.2734 50.44354 8.712994 39.21982 49.31408 5.20524 42.36452 54.10777 8.695168 39.9585 50.59298 8.214171 40.67259 51.36559 8.203902 40.84509 51.8534 6.759003 41.98952 53.742 8.680269 40.34548 51.48529 9.382859 39.36102 50.87651 9.946398 38.07069 50.0729 7.004671 41.89791 53.75288 6.744862 42.03452 54.13564 8.67163 40.5128 51.95741 5.090424 42.33972 56.47032 6.991195 41.943 54.14337 5.076717 42.30916 56.72499 9.372341 39.72391 51.71273 9.938186 38.71216 51.18442 9.366241 39.88087 52.1552 8.156391 41.29895 53.82403 10.2587 38.22614 51.41506 10.7309 36.6738 50.99532 9.931322 39.04812 51.96001 8.146394 41.34321 54.19403 6.652175 42.03306 56.43564 8.631651 40.95387 53.86501 9.927342 39.19334 52.37039 6.641082 42.00602 56.68415 6.902839 41.94448 56.42561 8.623236 40.99708 54.22327 10.25396 38.54162 52.14535 4.930674 41.72688 59.16005 6.89226 41.91799 56.67228 4.924179 41.69187 59.25794 10.7289 37.19453 51.9046 10.25121 38.67788 52.53173 9.338009 40.295 53.94327 10.81016 36.92841 52.03088 9.332066 40.33568 54.27913 8.080759 41.35475 56.35891 10.72724 37.46612 52.53889 8.072891 41.33085 56.59317 4.819061 41.03944 60.73759 9.908924 39.57591 54.02869 10.80901 37.18865 52.64042 10.72627 37.58307 52.87441 6.522494 41.46672 59.06745 8.567974 41.0107 56.31999 9.905048 39.61332 54.34014 6.517204 41.43378 59.16356 10.80834 37.30061 52.96282 8.561348 40.98785 56.54695 6.779127 41.38643 59.03887 10.2385 39.03589 54.09283 6.774078 41.35389 59.13435 4.749799 40.53193 61.61401 4.7 40.40334 61.81218 4.733314 40.40305 61.81199 4.7 40.27041 62.00748 10.23583 39.07067 54.38598 4.716712 40.27028 62.00739 4.7 40.1337 62.20015 6.333713 39.94978 62.06695 9.293028 40.34957 56.24521 9.288346 40.32828 56.45807 6.431381 40.81579 60.61987 7.988619 40.83915 58.84406 10.72181 37.88775 54.2292 6.692145 40.74292 60.58152 7.984852 40.8088 58.93501 9.879589 39.62429 56.16317 10.72087 37.91667 54.48345 10.80526 37.59142 54.2644 9.876536 39.60434 56.36052 6.374624 40.33142 61.48598 8.490342 40.5147 58.72857 10.80461 37.61882 54.5086 8.487167 40.48544 58.81676 6.36109 40.20804 61.68204 6.637935 40.26356 61.44265 10.21827 39.0782 56.1014 6.347452 40.08081 61.87572 6.625006 40.14141 61.63765 10.21617 39.0591 56.28705 6.611975 40.01543 61.83029 7.853824 39.43129 61.69143 7.92366 40.23715 60.3153 9.238163 39.88613 58.50483 9.235919 39.85876 58.5876 8.435574 39.93373 60.1556 7.883103 39.78693 61.13832 10.71472 37.91523 55.96985 7.873422 39.67203 61.32488 10.71398 37.89774 56.13055 9.843825 39.19219 58.25782 10.80037 37.61492 55.93588 7.863661 39.55347 61.50928 9.842362 39.16672 58.33453 10.79986 37.59782 56.09014 8.401363 39.4988 60.95435 9.199441 39.34243 59.84437 8.393195 39.38776 61.13547 10.19363 38.66798 58.07122 8.384959 39.27317 61.31449 9.157771 38.61321 61.09893 10.19262 38.64388 58.14334 9.175247 38.93517 60.59447 9.818594 38.68663 59.49919 9.169469 38.83118 60.76459 9.163643 38.72384 60.93277 10.7061 37.54934 57.67304 10.17625 38.19007 59.23783 10.70575 37.52806 57.7353 9.802833 38.30824 60.19417 10.79443 37.26028 57.57015 9.79907 38.21165 60.35177 9.795276 38.11196 60.50757 10.15758 37.55073 60.32944 10.16541 37.83285 59.89063 10.16282 37.7417 60.03863 10.16021 37.64765 60.18492 10.70005 37.12889 58.67928 10.69627 36.81597 59.24134 -4.652263e-15 27.12985 80.15549 4.65 27.12985 80.15549 4.596995 37.21717 37.57098 4.7 39.34414 46.54005 5.463154 38.76458 45.52038 2.302843 37.42923 37.57098 2.042717e-14 37.5 37.57098 4.7 37.5 40.98409 4.343282 37.40466 40.06392 4.938829 37.33069 40.06392 5.533421 37.2472 40.06392 5.521684 38.00549 43.51834 5.037032 38.07297 43.51828 4.7 38.44082 44.46861 5.134477 38.80952 45.52036 3.07097e-14 37.5 3.1 13.10491 -35.13561 3.1 15.57806 -34.1112 3.1 2.675219 37.40445 3.1 10.56497 -35.98099 3.1 7.971198 -36.64301 3.1 5.336806 -37.1183 3.1 5.336806 37.1183 3.1 2.675219 -37.40445 3.1 -5.880203e-14 -37.5 3.1 -2.302843 -37.42923 37.57098 7.971198 36.64301 3.1 -13.10491 35.13561 3.1 -14.78073 34.46418 31.00684 -13.17104 35.11088 31.68591 -12.86629 35.22369 31.83787 -12.1188 35.48781 32.246 -15.57806 34.1112 3.1 -2.675219 -37.40445 3.1 -4.596995 -37.21717 37.57098 -10.56497 35.98099 3.1 -11.92837 35.55227 32.35855 -11.31313 35.7528 32.74819 -11.02291 35.84335 32.94671 -9.792868 36.19876 33.91121 10.56497 35.98099 3.1 -7.971198 36.64301 3.1 -9.596891 36.25121 34.08617 -9.380265 36.30786 34.28748 -8.177812 36.59745 35.59023 -8.094038 36.61607 35.69542 -7.982696 36.6405 35.83884 -5.336806 37.1183 3.1 -6.873794 36.86463 37.57098 -4.596995 37.21717 37.57098 -5.336806 -37.1183 3.1 -6.873794 -36.86463 37.57098 -7.972366 -36.64275 35.85237 13.10491 35.13561 3.1 -2.675219 37.40445 3.1 -2.302843 37.42923 37.57098 -7.971198 -36.64301 3.1 -8.081411 -36.61886 35.71149 -8.455833 -36.53423 35.2565 -9.363251 -36.31225 34.30366 -9.581624 -36.25524 34.10009 15.57806 34.1112 3.1 17.97184 32.91296 3.1 -10.56497 -35.98099 3.1 -10.16114 -36.09711 33.59953 -10.48159 -36.00536 33.34497 -11.00864 -35.84773 32.95673 20.27403 31.54701 3.1 -11.29634 -35.75812 32.75938 -12.84061 -35.23306 31.85105 22.47291 30.0203 3.1 24.55728 28.34061 3.1 -13.10491 -35.13561 3.1 -13.05586 -35.15386 31.74243 -13.15054 -35.11855 31.69591 -13.81818 -34.86127 31.38887 26.5165 26.5165 3.1 -14.81382 -34.44998 30.99491 28.34061 24.55728 3.1 30.0203 22.47291 3.1 -15.57806 -34.1112 3.1 -15.08731 -34.33108 30.89918 -15.94083 -33.94318 30.63291 -16.84118 -33.50559 30.40271 31.54701 20.27403 3.1 -17.97184 -32.91296 3.1 -18.44751 -32.64873 30.11269 -18.88765 -32.39609 30.05905 -18.9909 -32.33567 30.04803 32.91296 17.97184 3.1 -17.04311 -33.40333 30.35792 -17.86817 -32.96936 30.20001 -20.27403 -31.54701 3.1 34.1112 15.57806 3.1 -22.47291 -30.0203 3.1 35.13561 13.10491 3.1 -24.55728 -28.34061 3.1 35.98099 10.56497 3.1 -26.5165 -26.5165 3.1 36.64301 7.971198 3.1 -28.34061 -24.55728 3.1 37.1183 5.336806 3.1 -30.0203 -22.47291 3.1 37.40445 2.675219 3.1 37.5 -8.848422e-12 3.1 -31.54701 -20.27403 3.1 37.40445 -2.675219 3.1 -32.91296 -17.97184 3.1 37.1183 -5.336806 3.1 -34.1112 -15.57806 3.1 36.64301 -7.971198 3.1 -35.13561 -13.10491 3.1 35.98099 -10.56497 3.1 -35.98099 -10.56497 3.1 35.13561 -13.10491 3.1 -36.64301 -7.971198 3.1 34.1112 -15.57806 3.1 32.91296 -17.97184 3.1 -37.1183 -5.336806 3.1 31.54701 -20.27403 3.1 -37.40445 -2.675219 3.1 30.0203 -22.47291 3.1 -37.5 -8.783474e-12 3.1 28.34061 -24.55728 3.1 -37.40445 2.675219 3.1 26.5165 -26.5165 3.1 -37.1183 5.336806 3.1 24.55728 -28.34061 3.1 -36.64301 7.971198 3.1 22.47291 -30.0203 3.1 -35.98099 10.56497 3.1 -35.13561 13.10491 3.1 -34.1112 15.57806 3.1 -32.91296 17.97184 3.1 -31.54701 20.27403 3.1 20.27403 -31.54701 3.1 -30.0203 22.47291 3.1 -28.34061 24.55728 3.1 -26.5165 26.5165 3.1 -24.55728 28.34061 3.1 -22.47291 30.0203 3.1 17.97184 -32.91296 3.1 -20.27403 31.54701 3.1 -17.87635 32.96495 30.19847 -17.97184 32.91296 3.1 -17.06027 33.39457 30.35427 -16.8624 33.49491 30.39793 -15.83581 33.99231 30.6631 -15.09589 34.32731 30.89626 -14.8222 34.44637 30.99189 2.532541 35.40955 0.5 2.832272e-14 35.5 3.1 2.532541 35.40955 3.1 2.909829e-14 35.5 0.5 5.052177 35.13866 0.5 5.052177 35.13866 3.1 7.546068 34.68871 0.5 7.546068 34.68871 3.1 10.00151 34.062 0.5 10.00151 34.062 3.1 12.40598 33.26172 0.5 12.40598 33.26172 3.1 14.74723 32.29194 0.5 14.74723 32.29194 3.1 17.01334 31.1576 0.5 17.01334 31.1576 3.1 19.19275 29.8645 0.5 19.19275 29.8645 3.1 21.27436 28.41921 0.5 21.27436 28.41921 3.1 23.24756 26.82911 0.5 23.24756 26.82911 3.1 25.10229 25.10229 0.5 25.10229 25.10229 3.1 26.82911 23.24756 0.5 26.82911 23.24756 3.1 28.41921 21.27436 0.5 28.41921 21.27436 3.1 29.8645 19.19275 0.5 29.8645 19.19275 3.1 31.1576 17.01334 3.1 31.1576 17.01334 0.5 32.29194 14.74723 3.1 32.29194 14.74723 0.5 33.26172 12.40598 3.1 33.26172 12.40598 0.5 34.062 10.00151 3.1 34.062 10.00151 0.5 34.68871 7.546068 3.1 34.68871 7.546068 0.5 35.13866 5.052177 3.1 35.13866 5.052177 0.5 35.40955 2.532541 3.1 35.40955 2.532541 0.5 35.5 -8.846601e-12 3.1 35.5 -1.574111e-12 0.5 35.40955 -2.532541 3.1 35.40955 -2.532541 0.5 35.13866 -5.052177 3.1 35.13866 -5.052177 0.5 34.68871 -7.546068 3.1 34.68871 -7.546068 0.5 34.062 -10.00151 3.1 34.062 -10.00151 0.5 33.26172 -12.40598 3.1 33.26172 -12.40598 0.5 32.29194 -14.74723 3.1 32.29194 -14.74723 0.5 31.1576 -17.01334 3.1 31.1576 -17.01334 0.5 29.8645 -19.19275 3.1 29.8645 -19.19275 0.5 28.41921 -21.27436 3.1 28.41921 -21.27436 0.5 26.82911 -23.24756 3.1 26.82911 -23.24756 0.5 25.10229 -25.10229 3.1 25.10229 -25.10229 0.5 23.24756 -26.82911 3.1 23.24756 -26.82911 0.5 21.27436 -28.41921 3.1 21.27436 -28.41921 0.5 19.19275 -29.8645 3.1 19.19275 -29.8645 0.5 17.01334 -31.1576 3.1 17.01334 -31.1576 0.5 14.74723 -32.29194 3.1 14.74723 -32.29194 0.5 12.40598 -33.26172 3.1 12.40598 -33.26172 0.5 10.00151 -34.062 3.1 10.00151 -34.062 0.5 7.546068 -34.68871 3.1 7.546068 -34.68871 0.5 5.052177 -35.13866 3.1 5.052177 -35.13866 0.5 2.532541 -35.40955 3.1 2.532541 -35.40955 0.5 -5.641505e-14 -35.5 3.1 -1.257607e-13 -35.5 0.5 -2.532541 -35.40955 3.1 -2.532541 -35.40955 0.5 -5.052177 -35.13866 3.1 -5.052177 -35.13866 0.5 -7.546068 -34.68871 3.1 -7.546068 -34.68871 0.5 -10.00151 -34.062 3.1 -10.00151 -34.062 0.5 -12.40598 -33.26172 3.1 -12.40598 -33.26172 0.5 -14.74723 -32.29194 3.1 -14.74723 -32.29194 0.5 -17.01334 -31.1576 3.1 -17.01334 -31.1576 0.5 -19.19275 -29.8645 3.1 -19.19275 -29.8645 0.5 -21.27436 -28.41921 3.1 -21.27436 -28.41921 0.5 -23.24756 -26.82911 3.1 -23.24756 -26.82911 0.5 -25.10229 -25.10229 3.1 -25.10229 -25.10229 0.5 -26.82911 -23.24756 3.1 -26.82911 -23.24756 0.5 -28.41921 -21.27436 3.1 -28.41921 -21.27436 0.5 -29.8645 -19.19275 3.1 -29.8645 -19.19275 0.5 -31.1576 -17.01334 3.1 -31.1576 -17.01334 0.5 -32.29194 -14.74723 3.1 -32.29194 -14.74723 0.5 -33.26172 -12.40598 3.1 -33.26172 -12.40598 0.5 -34.062 -10.00151 3.1 -34.062 -10.00151 0.5 -34.68871 -7.546068 3.1 -34.68871 -7.546068 0.5 -35.13866 -5.052177 3.1 -35.13866 -5.052177 0.5 -35.40955 -2.532541 3.1 -35.40955 -2.532541 0.5 -35.5 -8.785294e-12 3.1 -35.5 -1.345862e-12 0.5 -35.40955 2.532541 3.1 -35.40955 2.532541 0.5 -35.13866 5.052177 3.1 -35.13866 5.052177 0.5 -34.68871 7.546068 3.1 -34.68871 7.546068 0.5 -34.062 10.00151 3.1 -34.062 10.00151 0.5 -33.26172 12.40598 3.1 -33.26172 12.40598 0.5 -32.29194 14.74723 3.1 -32.29194 14.74723 0.5 -31.1576 17.01334 3.1 -31.1576 17.01334 0.5 -29.8645 19.19275 3.1 -29.8645 19.19275 0.5 -28.41921 21.27436 3.1 -28.41921 21.27436 0.5 -26.82911 23.24756 3.1 -26.82911 23.24756 0.5 -25.10229 25.10229 3.1 -25.10229 25.10229 0.5 -23.24756 26.82911 3.1 -23.24756 26.82911 0.5 -21.27436 28.41921 3.1 -21.27436 28.41921 0.5 -19.19275 29.8645 3.1 -19.19275 29.8645 0.5 -17.01334 31.1576 3.1 -17.01334 31.1576 0.5 -14.74723 32.29194 3.1 -14.74723 32.29194 0.5 -12.40598 33.26172 3.1 -12.40598 33.26172 0.5 -10.00151 34.062 3.1 -10.00151 34.062 0.5 -7.546068 34.68871 3.1 -7.546068 34.68871 0.5 -5.052177 35.13866 3.1 -5.052177 35.13866 0.5 -2.532541 35.40955 3.1 -2.532541 35.40955 0.5 7.296463 -37.02215 41.81607 7.29692 -37.01446 41.78091 7.506957 -36.91563 41.80186 9.107841 -37.55403 47.12775 9.12432 -36.93417 45.79348 9.974376 -35.96714 46.19114 10.73937 -33.93359 45.50347 10.75623 -33.0815 42.65853 10.75363 -33.88732 45.51944 9.965406 -36.61377 47.59094 9.962832 -36.80403 47.95981 9.977 -35.78253 45.73918 10.33603 -34.90376 45.16853 10.33334 -35.20056 45.96404 10.33165 -35.38951 46.42867 10.74212 -33.12911 42.64835 9.981181 -35.49252 44.96527 7.242221 -37.96579 44.89559 10.75 -35.07995 48.34654 10.75206 -34.39193 46.83889 10.93856 -33.58188 47.172 9.158469 -35.72047 41.94572 9.992965 -34.70181 42.15636 7.256866 -37.70485 44.2015 7.468839 -37.61016 44.2342 7.454901 -37.87263 44.93159 9.992606 -34.72534 42.26607 10.93807 -34.29095 48.73522 9.157809 -35.74305 42.05038 9.992476 -34.73389 42.30527 9.10311 -37.73637 47.47928 9.961279 -36.91983 48.17644 8.754254 -37.84394 46.98493 8.773724 -37.23284 45.67066 10.73552 -35.12419 48.32475 10.73771 -34.43735 46.82022 9.136821 -36.47904 44.62469 8.813013 -36.06649 42.02038 9.15757 -35.75125 42.08777 10.9387 -33.37961 46.66764 10.5666 -34.41107 45.33863 10.57128 -33.62047 42.54331 7.446154 -38.0397 45.33886 9.100257 -37.84733 47.68571 8.814075 -36.03613 41.88045 7.233033 -38.13188 45.30096 10.74941 -35.28251 48.74402 10.93793 -34.49977 49.14745 8.813296 -36.0584 41.98354 8.748665 -38.0237 47.33119 10.7349 -35.32639 48.7214 8.745295 -38.13309 47.53452 10.56009 -35.58064 48.09988 10.56379 -34.906 46.6275 10.75267 -34.19561 46.35235 10.93893 -33.06203 45.80437 10.74905 -35.40581 48.97749 10.93784 -34.6269 49.3896 7.416274 -38.62477 46.60028 10.73835 -34.24136 46.33467 10.73452 -35.44948 48.95438 7.201644 -38.71356 46.55654 8.788495 -36.7841 44.51937 10.3433 -34.12759 42.43489 7.407701 -38.79689 46.93269 10.55902 -35.77922 48.488 7.19264 -38.8847 46.88743 7.402531 -38.90164 47.1279 7.18721 -38.98885 47.08176 9.129141 -36.75716 45.36259 10.32589 -36.05149 47.86793 10.57133 -33.61156 42.50212 10.56488 -34.71346 46.15225 10.55838 -35.9001 48.71597 10.34361 -34.09477 42.28188 8.77942 -37.05831 45.24623 10.34338 -34.11884 42.39461 10.32423 -36.24631 48.24726 10.32323 -36.36489 48.47005 7.508155 -36.89432 41.703 7.506522 -36.92337 41.83719 7.298179 -36.99328 41.68253 4.7 27.17165 80.09744 10.9085 33.24685 45.74056 10.97713 33.48803 47.82852 10.97732 32.73839 45.9161 7.468839 37.61016 44.2342 8.767567 37.42361 46.10696 8.788495 36.7841 44.51937 8.794862 36.59451 43.96239 7.256866 37.70485 44.2015 7.436703 38.22233 45.75757 10.32983 35.59611 46.90637 10.32589 36.05149 47.86793 10.69374 34.77968 47.26351 7.223103 38.31345 45.71772 9.965406 36.61377 47.59094 7.478621 37.4287 43.69986 10.97738 32.51646 45.24586 9.157543 35.75217 42.09195 9.14221 36.28676 44.05924 9.984114 35.29205 44.3723 9.992461 34.73484 42.30965 10.90875 33.02886 45.08459 9.992835 34.71036 42.19656 9.158229 35.72867 41.98407 9.971539 36.16897 46.65579 7.267144 37.52446 43.66972 10.73937 33.93359 45.50347 10.73702 34.65166 47.31951 8.812981 36.06739 42.02449 8.813791 36.04423 41.91822 10.6965 34.06508 45.45808 7.506473 36.92424 41.84113 9.107841 37.55403 47.12775 7.507719 36.90207 41.73922 10.74008 33.72092 44.86678 7.296412 37.02301 41.82 7.297721 37.00098 41.71858 8.754254 37.84394 46.98493 10.69733 33.85342 44.82508 10.33603 34.90376 45.16853 9.119109 37.12767 46.23642 10.97755 31.90024 42.91624 10.97701 33.98161 48.88761 10.33792 34.69862 44.55907 9.981181 35.49252 44.96527 10.9072 34.46763 48.64819 7.416274 38.62477 46.60028 7.201644 38.71356 46.55654 10.73552 35.12419 48.32475 10.69972 33.26543 42.6241 10.69199 35.24989 48.26282 9.136821 36.47904 44.62469 10.90771 33.98303 47.612 10.34329 34.12857 42.43939 10.34353 34.10352 42.32318 -2.496871 34.91082 -1.064866e-10 -4.981019 34.64375 -1.064873e-10 -7.439785 34.20014 -1.064882e-10 -9.860639 33.58225 -1.06489e-10 -12.23125 32.79324 -1.064899e-10 -14.53953 31.83712 -1.064907e-10 -16.77371 30.71876 -1.064916e-10 -18.92243 29.44387 -1.064925e-10 -20.97472 28.01894 -1.064934e-10 -22.92013 26.45124 -1.064943e-10 -24.74874 24.74874 -1.064952e-10 -26.45124 22.92013 -1.06496e-10 -28.01894 20.97472 -1.064969e-10 -29.44387 18.92243 -1.064977e-10 -30.71876 16.77371 -1.064985e-10 -31.83712 14.53953 -1.064993e-10 -32.79324 12.23125 -1.065e-10 -33.58225 9.860639 -1.065007e-10 -34.20014 7.439785 -1.065013e-10 -34.64375 4.981019 -1.06502e-10 -34.91082 2.496871 -1.065025e-10 -35 -8.81565e-12 -1.06503e-10 -34.91082 -2.496871 -1.065035e-10 -34.64375 -4.981019 -1.065039e-10 -34.20014 -7.439785 -1.065042e-10 -33.58225 -9.860639 -1.065045e-10 -32.79324 -12.23125 -1.065048e-10 -31.83712 -14.53953 -1.065049e-10 -30.71876 -16.77371 -1.06505e-10 -29.44387 -18.92243 -1.065051e-10 -28.01894 -20.97472 -1.06505e-10 -26.45124 -22.92013 -1.065049e-10 -24.74874 -24.74874 -1.065048e-10 -22.92013 -26.45124 -1.065046e-10 -20.97472 -28.01894 -1.065043e-10 -18.92243 -29.44387 -1.06504e-10 -16.77371 -30.71876 -1.065036e-10 -14.53953 -31.83712 -1.065031e-10 -12.23125 -32.79324 -1.065026e-10 -9.860639 -33.58225 -1.065021e-10 -7.439785 -34.20014 -1.065015e-10 -4.981019 -34.64375 -1.065008e-10 -2.496871 -34.91082 -1.065001e-10 4.7 37.5 44.49896 4.7 37.33827 45.88265 4.7 36.8618 47.19175 4.7 29.32334 75.20326 4.7 28.50181 77.76215 -4.7 36.8618 47.19175 1.836058e-14 37.5 44.49896 -4.7 37.33827 45.88265 -4.7 37.5 44.49896 -2.027576e-14 15.5 86 -5.727394e-14 -15.5 86 -10.50512 13.89348 86 -10.54915 12.3429 86 -10.35224 15.5 86 -10.54915 -12.3429 86 -10.50512 -13.89348 86 -10.35224 -15.5 86 4.7 -28.50181 77.76215 4.7 -29.32334 75.20326 4.7 -36.8618 47.19175 4.7 -37.33827 45.88265 4.7 -37.5 44.49896 -7.115115e-14 -37.5 44.49896 -4.7 -37.33827 45.88265 -4.7 -37.5 44.49896 -4.7 -36.8618 47.19175 -4.7 -36.09627 48.35568 -4.65 -27.12985 80.15549 -4.7 -27.17165 80.09744 -4.7 -28.50181 77.76215 -4.7 -29.32334 75.20326 -4.7 27.17165 80.09744 -4.65 27.12985 80.15549 -4.7 28.50181 77.76215 -4.7 29.32334 75.20326 10.98 -11.74701 51.97767 10.98 -11.75588 51.98191 10.984 -11.74701 51.97767 10.988 -11.74701 51.97767 10.992 -11.74701 51.97767 10.996 -11.74701 51.97767 10.98 -11.7388 51.97083 10.984 -11.7388 51.97083 10.988 -11.7388 51.97083 10.992 -11.7388 51.97083 10.996 -11.7388 51.97083 10.98 -11.73123 51.96098 10.984 -11.73123 51.96098 10.988 -11.73123 51.96098 10.992 -11.73123 51.96098 10.996 -11.73123 51.96098 10.98 -11.68114 51.47136 10.984 -11.68114 51.47136 10.98 -11.67398 49.81876 10.988 -11.68114 51.47136 10.992 -11.68114 51.47136 10.996 -11.68114 51.47136 10.98 -11.75588 52.0228 10.98 -11.25772 52.0433 10.98 -10.61622 52.05704 10.98 -9.592636 51.92732 10.98 -10.07119 52.02798 10.98 -8.589499 50.48743 10.98 -8.634429 50.89977 10.98 -8.755567 51.23382 10.98 -8.932435 51.49659 10.98 -9.144554 51.69509 10.98 -9.371447 51.83633 10.98 -9.162745 49.26603 10.98 -8.95391 49.46032 10.98 -8.757596 49.7553 10.98 -8.636507 50.08538 10.98 -9.558548 49.02709 10.98 -9.365799 49.12354 10.98 -9.558548 49.01352 10.98 -8.32341 47.2939 10.98 -7.879891 46.75474 10.98 -8.065786 46.95516 10.98 -7.879891 46.71379 10.98 -8.903471 46.71379 10.98 -9.121789 46.74116 10.98 -9.01009 46.71978 10.98 -10.52074 48.8224 10.98 -10.70499 48.8224 10.98 -10.70499 48.54939 10.98 -10.62308 46.75474 10.98 -10.63213 46.76121 10.98 -10.64048 46.77064 10.98 -10.64818 46.78344 10.98 -10.69594 47.22339 10.98 -10.62308 46.71379 10.98 -11.75588 46.71379 10.98 -11.75588 46.75474 10.98 -11.67398 49.06805 10.98 -11.71661 46.81782 10.98 -11.73049 46.7813 10.98 -11.74114 46.766 10.98 -11.74827 46.75948 10.98 -10.70499 51.19033 10.98 -9.850863 49.79763 10.98 -9.988438 49.69592 10.98 -9.66056 50.07917 10.98 -9.739567 49.92834 10.98 -10.14107 49.62407 10.98 -9.615786 50.23645 10.98 -10.31801 49.57655 10.98 -9.599505 50.41917 10.98 -9.599505 50.42604 10.98 -10.5071 49.55938 10.98 -10.70499 49.56625 10.98 -9.625629 50.65427 10.98 -9.683499 50.81256 10.98 -9.764585 50.93678 10.98 -9.870558 51.03853 10.98 -9.999901 51.11686 10.98 -10.1511 51.17079 10.98 -10.28559 51.1956 10.98 -10.43212 51.20398 11 -9.625629 50.65427 11 -9.599505 50.42604 11 -9.683499 50.81256 11 -9.764585 50.93678 11 -9.870558 51.03853 11 -9.999901 51.11686 11 -10.1511 51.17079 11 -10.28559 51.1956 11 -10.43212 51.20398 11 -9.599505 50.41917 11 -9.850863 49.79763 11 -9.988438 49.69592 11 -9.739567 49.92834 11 -9.66056 50.07917 11 -9.615786 50.23645 11 -10.31801 49.57655 11 -10.5071 49.55938 11 -10.14107 49.62407 11 -10.70499 49.56625 11 -10.70499 51.19033 10.98 -5.075062 46.62518 10.98 -4.357447 46.71052 10.98 -3.719255 46.95316 10.98 -3.177428 47.33309 10.98 -2.748906 47.83027 10.98 -2.450633 48.42465 10.98 -2.326728 48.89753 10.98 -2.284055 49.40246 10.98 -7.845433 49.35464 10.98 -7.760074 48.66881 10.98 -7.517261 48.04916 10.98 -7.136884 47.51607 10.98 -6.638835 47.0899 10.98 -6.043005 46.79102 10.98 -5.574908 46.66783 10.98 -5.00664 52.1047 10.98 -5.741424 52.01916 10.98 -6.397092 51.77509 10.98 -6.954023 51.39129 10.98 -7.354623 50.94196 10.98 -7.62137 50.46516 10.98 -7.787712 49.93373 10.98 -2.284055 49.40933 10.98 -2.369705 50.11698 10.98 -2.583426 50.68717 10.98 -2.8751 51.13455 10.98 -3.250872 51.50923 10.98 -3.701101 51.8012 10.98 -4.216145 52.00046 10.98 -4.600068 52.07811 10.98 -3.770435 48.14227 10.98 -3.586704 48.41142 10.98 -6.19718 50.75586 10.98 -5.86744 50.98614 10.98 -3.452574 48.71792 10.98 -6.122263 47.92765 10.98 -3.37513 49.03533 10.98 -6.378492 48.18333 10.98 -6.577188 48.49113 10.98 -5.81494 47.73276 10.98 -5.462965 47.60731 10.98 -5.481296 51.13231 10.98 -6.722649 48.88371 10.98 -3.348578 49.37514 10.98 -5.260177 47.57191 10.98 -5.047583 47.55983 10.98 -6.780896 49.36838 10.98 -5.047583 51.18346 10.98 -6.747848 49.74219 10.98 -4.616044 47.61177 10.98 -3.348578 49.382 10.98 -3.406678 49.86374 10.98 -6.652113 50.08666 10.98 -4.270841 47.74098 10.98 -4.698995 51.14815 10.98 -3.999802 47.9167 10.98 -4.378733 51.04664 10.98 -4.066918 50.86757 10.98 -6.461683 50.45239 10.98 -3.572254 50.29486 10.98 -3.802349 50.62598 11 -3.406678 49.86374 11 -3.348578 49.382 11 -3.572254 50.29486 11 -3.802349 50.62598 11 -4.066918 50.86757 11 -4.378733 51.04664 11 -4.698995 51.14815 11 -5.047583 51.18346 11 -3.348578 49.37514 11 -4.616044 47.61177 11 -5.047583 47.55983 11 -4.270841 47.74098 11 -3.999802 47.9167 11 -3.770435 48.14227 11 -3.586704 48.41142 11 -3.452574 48.71792 11 -3.37513 49.03533 11 -6.780896 49.36838 11 -6.722649 48.88371 11 -6.577188 48.49113 11 -6.378492 48.18333 11 -6.122263 47.92765 11 -5.81494 47.73276 11 -5.462965 47.60731 11 -5.260177 47.57191 11 -5.481296 51.13231 11 -5.86744 50.98614 11 -6.19718 50.75586 11 -6.461683 50.45239 11 -6.652113 50.08666 11 -6.747848 49.74219 10.98 0.9784854 47.0072 10.98 1.24717 47.21115 10.98 1.464363 47.47879 10.98 1.601253 47.76686 10.98 1.655545 47.98326 10.98 1.67452 48.21503 10.98 -0.5706236 46.70016 10.98 0.283201 46.76081 10.98 0.6680309 46.86031 10.98 -1.143691 46.71373 10.98 -1.580602 46.73423 10.98 -1.580602 46.7753 10.98 -1.491845 49.0682 10.98 -1.52792 46.87476 10.98 -1.545538 46.81208 10.98 -1.556974 46.79231 10.98 -1.565959 46.78306 10.98 -1.57306 46.77839 10.98 -1.491845 49.81876 10.98 -1.573732 51.97515 10.98 -1.561022 51.96418 10.98 -1.5497 51.94829 10.98 -1.539686 51.92611 10.98 -1.497825 51.40291 10.98 -1.573732 52.01609 10.98 -1.116487 52.03654 10.98 -0.3932489 52.05017 10.98 0.5212408 51.92732 10.98 0.0870264 52.01946 10.98 1.456202 50.63766 10.98 1.410646 51.02176 10.98 1.304471 51.29966 10.98 1.170825 51.50017 10.98 1.014047 51.65839 10.98 0.8466284 51.77884 10.98 0.6761113 51.86827 10.98 0.6168664 49.50481 10.98 0.8519737 49.59632 10.98 1.055828 49.73635 10.98 1.223303 49.91769 10.98 1.349275 50.13315 10.98 1.428616 50.37554 10.98 0.6168664 49.49122 10.98 1.67452 48.2219 10.98 1.635027 48.55053 10.98 1.524639 48.83763 10.98 1.355493 49.07923 10.98 1.139724 49.27135 10.98 0.8894699 49.41 10.98 0.005758052 51.17475 10.98 0.4819976 48.75852 10.98 0.5639343 48.63572 10.98 0.2348587 51.05934 10.98 0.6178122 48.49091 10.98 0.3907797 50.86745 10.98 0.322921 50.97277 10.98 0.2833585 50.08837 10.98 0.3705445 50.20279 10.98 -0.5364125 51.1972 10.98 -0.5364125 49.86659 10.98 -0.5364125 49.04083 10.98 0.5701221 48.01017 10.98 0.4283923 50.33188 10.98 -0.528168 47.58627 10.98 -0.5311097 47.58916 10.98 0.6190198 48.15105 10.98 -0.5329259 47.59198 10.98 -0.3521681 49.85972 10.98 -0.5230192 47.58317 10.98 -0.2906161 49.05446 10.98 -0.5346273 47.59655 10.98 0.6324907 48.23109 10.98 -0.5160783 47.58044 10.98 -0.5364125 47.62826 10.98 -0.1764595 49.87163 10.98 -0.2634122 47.56681 10.98 0.1321429 48.99302 10.98 -0.04460308 47.587 10.98 0.6372005 48.3243 10.98 0.6372005 48.31743 10.98 0.09110529 47.62014 10.98 0.214304 47.66904 10.98 0.009450927 49.91425 10.98 0.3696727 47.76294 10.98 0.2596712 48.93736 10.98 0.378433 48.85913 10.98 0.451635 50.43179 10.98 0.4892024 47.88116 10.98 0.1521996 49.98229 10.98 -0.2634122 51.21085 10.98 0.4598259 50.54889 10.98 0.4598259 50.54213 10.98 0.4401607 50.72887 10.98 -0.1231973 51.20177 10.98 0.1285014 51.12679 11 0.6178122 48.49091 11 0.6372005 48.3243 11 0.5639343 48.63572 11 0.4819976 48.75852 11 0.378433 48.85913 11 0.2596712 48.93736 11 0.1321429 48.99302 11 0.6372005 48.31743 11 0.3696727 47.76294 11 0.214304 47.66904 11 0.4892024 47.88116 11 0.5701221 48.01017 11 0.6190198 48.15105 11 0.6324907 48.23109 11 -0.04460308 47.587 11 -0.2634122 47.56681 11 0.09110529 47.62014 11 -0.5160783 47.58044 11 -0.5346273 47.59655 11 -0.5364125 47.62826 11 -0.5329259 47.59198 11 -0.5311097 47.58916 11 -0.528168 47.58627 11 -0.5230192 47.58317 11 -0.5364125 49.04083 11 -0.2906161 49.05446 11 0.4401607 50.72887 11 0.4598259 50.54889 11 0.3907797 50.86745 11 0.322921 50.97277 11 0.2348587 51.05934 11 0.1285014 51.12679 11 0.005758052 51.17475 11 -0.1231973 51.20177 11 -0.2634122 51.21085 11 0.4598259 50.54213 11 0.1521996 49.98229 11 0.009450927 49.91425 11 0.2833585 50.08837 11 0.3705445 50.20279 11 0.4283923 50.33188 11 0.451635 50.43179 11 -0.1764595 49.87163 11 -0.3521681 49.85972 11 -0.5364125 49.86659 11 -0.5364125 51.1972 10.98 5.004933 46.62518 10.98 5.722457 46.71052 10.98 6.360619 46.95316 10.98 6.902458 47.33309 10.98 7.331015 47.83027 10.98 7.62933 48.42465 10.98 7.753258 48.89753 10.98 7.79594 49.40246 10.98 2.234535 49.35464 10.98 2.319894 48.66878 10.98 2.562714 48.04911 10.98 2.943108 47.51601 10.98 3.441191 47.08984 10.98 4.037075 46.79097 10.98 4.505128 46.66782 10.98 5.073355 52.1047 10.98 4.338523 52.01916 10.98 3.682835 51.77509 10.98 3.125905 51.39129 10.98 2.725316 50.94196 10.98 2.458582 50.46516 10.98 2.292251 49.93373 10.98 7.79594 49.40933 10.98 7.710291 50.11694 10.98 7.496577 50.68711 10.98 7.204918 51.13447 10.98 6.829173 51.50914 10.98 6.378987 51.80112 10.98 5.864006 52.0004 10.98 5.480006 52.07809 10.98 6.30956 48.14227 10.98 6.493291 48.41142 10.98 3.882797 50.75586 10.98 4.212546 50.98614 10.98 6.62742 48.71792 10.98 3.957716 47.92765 10.98 6.704864 49.03533 10.98 3.701479 48.18333 10.98 3.502776 48.49113 10.98 4.265047 47.73276 10.98 4.617028 47.60731 10.98 4.598696 51.13231 10.98 3.357308 48.88371 10.98 6.731417 49.37514 10.98 4.819817 47.57191 10.98 5.032411 47.55983 10.98 3.299058 49.36838 10.98 5.032411 51.18346 10.98 3.332107 49.74219 10.98 5.46395 47.61177 10.98 6.731417 49.382 10.98 6.673307 49.86374 10.98 3.427847 50.08666 10.98 5.809154 47.74098 10.98 5.38096 51.14815 10.98 6.080193 47.9167 10.98 5.701204 51.04664 10.98 6.013017 50.86757 10.98 3.618285 50.45239 10.98 6.50771 50.29486 10.98 6.277596 50.62598 11 6.673307 49.86374 11 6.731417 49.382 11 6.50771 50.29486 11 6.277596 50.62598 11 6.013017 50.86757 11 5.701204 51.04664 11 5.38096 51.14815 11 5.032411 51.18346 11 6.731417 49.37514 11 5.46395 47.61177 11 5.032411 47.55983 11 5.809154 47.74098 11 6.080193 47.9167 11 6.30956 48.14227 11 6.493291 48.41142 11 6.62742 48.71792 11 6.704864 49.03533 11 3.357308 48.88371 11 3.299058 49.36838 11 3.502776 48.49113 11 3.701479 48.18333 11 3.957716 47.92765 11 4.265047 47.73276 11 4.617028 47.60731 11 4.819817 47.57191 11 4.598696 51.13231 11 4.212546 50.98614 11 3.882797 50.75586 11 3.618285 50.45239 11 3.427847 50.08666 11 3.332107 49.74219 10.98 8.096969 51.07425 10.98 8.136571 51.10751 10.98 8.187616 51.13396 10.98 8.348072 51.17226 10.98 8.560671 51.18346 10.98 8.042286 51.07425 10.98 8.042286 52.03643 10.98 12.04771 52.03643 10.98 12.04771 51.07425 10.98 12.00017 51.07425 10.98 11.53606 51.18346 10.98 11.79018 51.16488 10.98 11.88885 51.13897 10.98 11.95009 51.11078 10.98 10.55342 51.18346 10.98 10.55342 49.06805 10.98 10.65592 46.75478 10.98 10.64589 46.75657 10.98 10.63744 46.76023 10.98 10.63029 46.76539 10.98 10.62356 46.77249 10.98 10.61723 46.7817 10.98 10.6094 46.79755 10.98 10.56042 47.37252 10.98 10.65592 46.71384 10.98 9.441224 46.71384 10.98 9.441224 46.75478 10.98 9.536713 49.06805 10.98 9.497902 46.86727 10.98 9.476524 46.79576 10.98 9.461975 46.77236 10.98 9.452023 46.7623 10.98 9.536713 51.18346 10.98 13.84962 46.75478 10.98 13.82971 46.77663 10.98 13.81278 46.80799 10.98 13.76147 47.35807 10.98 13.75414 49.06805 10.98 13.84962 46.71384 10.98 12.63493 46.71384 10.98 12.63493 46.7615 10.98 12.73056 49.06118 10.98 12.68078 46.83682 10.98 12.66259 46.79361 10.98 12.64954 46.77535 10.98 12.73056 49.81861 10.98 12.6418 51.98878 10.98 12.65701 51.97397 10.98 12.67038 51.95319 10.98 12.72303 51.45101 10.98 12.6418 52.03643 10.98 13.84275 52.03643 10.98 13.84275 51.98878 10.98 13.75414 49.81861 10.98 13.80027 51.91764 10.98 13.81713 51.9588 10.98 13.82921 51.976 10.98 19.65009 47.92848 10.98 19.86757 48.28766 10.98 20.04246 48.79085 10.98 20.11421 49.39559 10.98 18.80403 47.12334 10.98 19.15231 47.36241 10.98 19.43838 47.6439 10.98 18.80403 47.10273 10.98 19.47959 46.80256 10.98 20.0664 46.59094 10.98 20.30532 46.53641 10.98 20.33953 46.5091 10.98 19.71852 45.84714 10.98 19.64336 45.84714 10.98 19.67191 45.83805 10.98 19.68346 45.83691 10.98 19.69683 45.83859 10.98 19.70711 45.84196 10.98 18.76308 46.24982 10.98 17.96469 46.69345 10.98 17.67136 46.63865 10.98 17.32348 46.61831 10.98 14.53906 49.34106 10.98 14.60855 48.72411 10.98 14.80763 48.15748 10.98 15.12227 47.6566 10.98 15.53841 47.23689 10.98 16.04199 46.91378 10.98 16.61898 46.7027 10.98 16.96339 46.63984 10.98 17.40509 52.1047 10.98 16.66594 52.01916 10.98 16.00571 51.77509 10.98 15.44418 51.3913 10.98 15.03952 50.94199 10.98 14.76929 50.4652 10.98 14.59897 49.93021 10.98 14.55427 49.64114 10.98 20.11421 49.40246 10.98 20.02867 50.11091 10.98 19.8156 50.68151 10.98 19.52539 51.1292 10.98 19.15227 51.50433 10.98 18.70624 51.79706 10.98 18.1973 51.99758 10.98 17.81227 52.07737 10.98 18.1224 47.73021 10.98 17.77378 47.59917 10.98 15.73334 50.08488 10.98 17.33694 51.19033 10.98 17.69005 51.15473 10.98 19.04969 49.382 10.98 19.04969 49.37514 10.98 19.02311 49.03484 10.98 18.39559 47.90814 10.98 18.99153 49.86425 10.98 15.92479 50.45189 10.98 16.06129 48.11727 10.98 18.62638 48.13613 10.98 16.33011 47.8708 10.98 18.01371 51.05247 10.98 18.82553 50.29664 10.98 15.82857 48.45319 10.98 18.32816 50.8722 10.98 16.64848 47.68729 10.98 18.59441 50.62924 10.98 16.19013 50.75755 10.98 15.66186 48.88746 10.98 18.81097 48.40763 10.98 16.97719 47.58286 10.98 17.33694 47.54642 10.98 18.94552 48.71613 10.98 15.60359 49.36838 10.98 16.52011 50.99025 10.98 15.63692 49.74054 10.98 16.90546 51.13838 11 19.04969 49.382 11 18.99153 49.86425 11 18.82553 50.29664 11 18.59441 50.62924 11 18.32816 50.8722 11 18.01371 51.05247 11 17.69005 51.15473 11 17.33694 51.19033 11 19.04969 49.37514 11 17.77378 47.59917 11 17.33694 47.54642 11 18.1224 47.73021 11 18.39559 47.90814 11 18.62638 48.13613 11 18.81097 48.40763 11 18.94552 48.71613 11 19.02311 49.03484 11 15.66186 48.88746 11 15.60359 49.36838 11 15.82857 48.45319 11 16.06129 48.11727 11 16.33011 47.8708 11 16.64848 47.68729 11 16.97719 47.58286 11 16.90546 51.13838 11 16.52011 50.99025 11 16.19013 50.75755 11 15.92479 50.45189 11 15.73334 50.08488 11 15.63692 49.74054 10.98 -18.06358 53.43935 10.98 -18.20382 53.44885 10.98 -18.31393 53.43137 10.98 -18.39999 53.39455 10.98 -18.46687 53.34434 10.98 -18.51851 53.28531 10.98 -18.56204 53.21318 10.98 -18.59593 53.13236 10.98 -18.62248 53.03967 10.98 -15.06883 52.89102 10.98 -14.4717 52.46633 10.98 -14.50842 52.56242 10.98 -14.56178 52.64229 10.98 -14.62774 52.70763 10.98 -14.70226 52.76014 10.98 -14.905 52.84808 10.98 -14.15226 51.17456 10.98 -14.43773 50.63433 10.98 -14.31176 50.6717 10.98 -14.23271 50.71741 10.98 -14.18255 50.76606 10.98 -14.14962 50.81806 10.98 -14.12827 50.87783 10.98 -14.11849 50.94537 10.98 -14.12028 51.02069 10.98 -14.13166 51.09453 10.98 -18.36472 49.93662 10.98 -19.08726 50.5769 10.98 -19.10208 50.41675 10.98 -19.08679 50.29726 10.98 -19.05353 50.20794 10.98 -19.00505 50.13432 10.98 -18.94447 50.07494 10.98 -18.87492 50.0283 10.98 -18.77367 49.98338 10.98 -18.50863 49.93465 10.98 -13.77395 49.80643 10.98 -13.81279 49.91159 10.98 -13.84941 49.97016 10.98 -13.90699 50.03077 10.98 -13.97979 50.07804 10.98 -14.06383 50.10878 10.98 -14.16763 50.12433 10.98 -14.25508 50.12399 10.98 -14.35449 50.1125 10.98 -13.1897 47.40162 10.98 -13.89491 46.64154 10.98 -13.65315 46.67369 10.98 -13.4858 46.73191 10.98 -13.36509 46.80333 10.98 -13.28598 46.87574 10.98 -13.22357 46.96494 10.98 -13.18399 47.0651 10.98 -13.16665 47.17426 10.98 -13.1691 47.2813 10.98 -17.85979 47.24157 10.98 -18.20906 47.76791 10.98 -18.23222 47.62898 10.98 -18.22712 47.53146 10.98 -18.20656 47.46047 10.98 -18.17537 47.40455 10.98 -18.13217 47.35618 10.98 -18.07696 47.31538 10.98 -18.00974 47.28214 10.98 -17.93956 47.25884 10.98 -17.96681 49.07728 10.98 -17.38509 49.57474 10.98 -17.61079 49.51495 10.98 -17.72224 49.46017 10.98 -17.79945 49.40006 10.98 -17.87378 49.3102 10.98 -17.92702 49.20715 10.98 -19.29222 46.92658 10.98 -19.43247 46.93656 10.98 -19.54267 46.91945 10.98 -19.62885 46.88292 10.98 -19.6959 46.83292 10.98 -19.74772 46.77405 10.98 -19.79146 46.70204 10.98 -19.8256 46.62131 10.98 -19.85242 46.52868 10.98 -16.46385 46.48913 10.98 -15.63412 45.94819 10.98 -15.67964 46.07643 10.98 -15.74978 46.18112 10.98 -15.84006 46.26525 10.98 -15.94598 46.33187 10.98 -16.20123 46.42867 10.98 -15.33503 44.6508 10.98 -15.62221 44.11142 10.98 -15.50385 44.14666 10.98 -15.42865 44.19123 10.98 -15.38012 44.23933 10.98 -15.34742 44.29114 10.98 -15.32513 44.35101 10.98 -15.31325 44.41896 10.98 -15.31177 44.49497 10.98 -15.31925 44.56966 10.98 -19.60329 43.42499 10.98 -20.32407 44.06704 10.98 -20.33946 43.90685 10.98 -20.32483 43.78713 10.98 -20.29222 43.69748 10.98 -20.2444 43.62347 10.98 -20.18448 43.56364 10.98 -20.11554 43.51655 10.98 -20.01494 43.47105 10.98 -19.89833 43.43955 10.98 -19.70487 43.42007 -13.26619 23.51613 0.3125 -13.26619 23.51613 -1.064926e-10 -12.91153 23.71271 -1.064918e-10 -12.91153 23.71271 0.3125 -12.55395 23.90394 0.3125 -12.55395 23.90394 -1.064917e-10 -12.19355 24.08978 0.3125 -12.19355 24.08978 -1.064926e-10 -12.19355 -24.08978 0.3125 -12.19355 -24.08978 -1.064926e-10 -12.55395 -23.90394 -1.06501e-10 -12.55395 -23.90394 0.3125 -12.91153 -23.71271 0.3125 -12.91153 -23.71271 -1.065011e-10 -13.26619 -23.51613 0.3125 -13.26619 -23.51613 -1.064926e-10 -15.23155 23 -1.064926e-10 -15.23155 23 0.3125 -23.59237 23 -1.064926e-10 -23.59237 23 0.3125 -26.04353 21.85714 0.3125 -27.65918 19.77296 0.3125 -26.04353 21.85714 -1.064926e-10 -26.04353 -21.85714 0.3125 -26.04353 -21.85714 -1.064926e-10 -27.65918 -19.77296 -1.065047e-10 -27.65918 -19.77296 0.3125 -29.10843 -17.56983 0.3125 -29.10843 -17.56983 -1.065047e-10 -30.38259 -15.26101 0.3125 -30.38259 -15.26101 -1.065046e-10 -31.47397 -12.86038 0.3125 -31.47397 -12.86038 -1.065045e-10 -32.37601 -10.38239 0.3125 -32.37601 -10.38239 -1.065043e-10 -33.08329 -7.841941 0.3125 -33.08329 -7.841941 -1.06504e-10 -33.59155 -5.254317 0.3125 -33.59155 -5.254317 -1.065036e-10 -33.89773 -2.635084 0.3125 -33.89773 -2.635084 -1.065032e-10 -34 -5.780296e-11 0.3125 -34 -5.782425e-11 -1.065027e-10 -33.89773 2.635084 0.3125 -33.89773 2.635084 -1.065022e-10 -33.59155 5.254317 0.3125 -33.59155 5.254317 -1.065016e-10 -33.08329 7.841941 0.3125 -33.08329 7.841941 -1.065009e-10 -32.37601 10.38239 0.3125 -32.37601 10.38239 -1.065002e-10 -31.47397 12.86038 0.3125 -31.47397 12.86038 -1.064995e-10 -30.38259 15.26101 -1.064987e-10 -30.38259 15.26101 0.3125 -29.10843 17.56983 -1.064979e-10 -29.10843 17.56983 0.3125 -27.65918 19.77296 -1.06497e-10 -23.59237 -23 -1.064926e-10 -23.59237 -23 0.3125 -15.23155 -23 0.3125 -15.23155 -23 -1.064926e-10 -10 -27.65863 -1.064926e-10 -10 -27.65863 0.3125 -10 -30.03997 0.3125 -10 -30.03997 -1.064926e-10 -8.312352 -32.86004 -1.064949e-10 -8.312352 -32.86004 0.3125 -9.00892 -32.35529 0.3125 -9.00892 -32.35529 -1.064948e-10 -9.545863 -31.68321 0.3125 -9.545863 -31.68321 -1.064945e-10 -9.884377 -30.89239 0.3125 -9.884377 -30.89239 -1.064941e-10 -10 30.03997 -1.064926e-10 -10 27.65863 0.3125 -10 27.65863 -1.064926e-10 -10 30.03997 0.3125 -9.884377 30.89239 -1.064937e-10 -9.884377 30.89239 0.3125 -9.545863 31.68321 0.3125 -9.545863 31.68321 -1.064939e-10 -9.00892 32.35529 0.3125 -9.00892 32.35529 -1.064939e-10 -8.312352 32.86004 0.3125 -8.312352 32.86004 -1.064938e-10 -10.1509 26.57031 0.3125 -10.1509 26.57031 -1.064917e-10 -10.59223 25.56409 0.3125 -10.59223 25.56409 -1.06492e-10 -11.29068 24.71592 0.3125 -11.29068 24.71592 -1.064924e-10 -11.29068 -24.71592 0.3125 -11.29068 -24.71592 -1.064912e-10 -10.59223 -25.56409 0.3125 -10.59223 -25.56409 -1.064912e-10 -10.1509 -26.57031 0.3125 -10.1509 -26.57031 -1.064912e-10 -13.88848 23.23222 0.3125 -13.88848 23.23222 -1.064929e-10 -14.55005 23.05848 0.3125 -14.55005 23.05848 -1.064932e-10 -14.55005 -23.05848 0.3125 -14.55005 -23.05848 -1.064916e-10 -13.88848 -23.23222 0.3125 -13.88848 -23.23222 -1.064915e-10 -25.35064 22.47367 -1.064926e-10 -25.35064 22.47367 0.3125 -24.51005 22.86559 0.3125 -24.51005 22.86559 -1.064923e-10 -24.51005 -22.86559 -1.064935e-10 -24.51005 -22.86559 0.3125 -25.35064 -22.47367 0.3125 -25.35064 -22.47367 -1.064936e-10 -18.94259 -32.29464 30.92408 -18.64317 -32.35742 31.48683 -18.94572 -32.17903 31.45888 -11.75397 -35.4769 33.97173 -11.9117 -35.35552 34.20209 -12.16534 -35.26796 34.03051 -18.62957 -32.47702 30.95636 -17.89612 -31.72348 33.69126 -17.68052 -31.85678 33.71479 -17.678 -31.84493 33.73181 -11.27784 -35.63234 34.31908 -11.44768 -35.51034 34.54016 -10.9834 -35.80555 33.94782 -19.041 -32.23646 30.91514 -19.04085 -32.12213 31.45128 -16.17866 -33.59105 32.24496 -15.52841 -33.90164 32.43546 -16.27047 -33.3016 32.889 -16.37639 -33.24773 32.86218 -19.91414 -31.4803 31.73418 -12.19776 -35.25662 34.00921 -12.51303 -34.93721 34.52963 -19.80832 -31.2434 32.45521 -17.31083 -32.57058 33.02439 -17.1448 -32.7021 32.98105 -17.14499 -32.66296 33.05344 -19.26603 -31.88903 31.75606 -13.98518 -34.04204 34.40166 -12.67265 -34.73305 34.80992 -17.29957 -32.3806 33.35418 -19.29164 -32.08643 30.89498 -19.28319 -31.97543 31.43449 -17.9071 -31.76841 33.6249 -18.16654 -32.7394 31.01499 -18.5233 -32.53801 30.96866 -17.68993 -31.90195 33.64888 -12.01416 -35.38891 33.79538 -19.9455 -31.56131 31.40724 -16.29064 -33.53596 32.21545 -12.04741 -35.37751 33.77348 -19.97642 -31.66271 30.85883 -17.1423 -32.7902 32.81056 -16.38746 -33.19 32.97388 -16.40174 -33.0997 33.13968 -14.1534 -33.96859 34.32095 -17.31178 -32.6095 32.95157 -14.22746 -33.9359 34.28649 -10.16778 -36.04633 34.62682 -10.68203 -35.89688 34.18591 -15.33164 -34.16461 31.67359 -15.07258 -34.28012 31.76149 -15.21053 -34.12524 32.23408 -15.46018 -34.01169 32.15107 -13.88591 -34.2476 34.12023 -18.04903 -31.61371 33.69397 -17.89318 -31.7117 33.7084 -17.14143 -32.80771 32.77532 -11.47939 -35.64916 33.58487 -16.38419 -33.20797 32.93961 -18.05226 -31.62544 33.67674 -13.86299 -34.29008 34.05818 -17.7314 -32.12879 33.29179 -17.27396 -32.15118 33.70625 -12.64094 -34.77632 34.75316 -14.05987 -34.17355 34.03646 -17.13941 -32.84105 32.70686 -16.37752 -33.24222 32.87305 -13.8076 -34.38616 33.91211 -12.56507 -34.87426 34.61958 -17.13904 -32.84641 32.69569 -18.06439 -31.67019 33.61007 -14.03818 -34.2159 33.97373 -16.12574 -33.69787 31.95314 -17.31192 -32.69708 32.78008 -13.79591 -34.40534 33.88193 -12.54918 -34.89383 34.59198 -14.13644 -34.1406 34.00068 -17.31159 -32.71448 32.74463 -11.75032 -35.56051 33.40051 -17.3106 -32.7476 32.67577 -16.24034 -33.64219 31.92239 -13.77298 -34.44196 33.82332 -12.51812 -34.93119 34.53838 -11.78493 -35.54902 33.37762 -17.3104 -32.75292 32.66453 -14.1153 -34.18288 33.93766 -17.95685 -31.99384 33.26531 -13.76921 -34.44786 33.81375 -18.33473 -31.43077 33.67295 -13.98568 -34.31166 33.82607 -18.33851 -31.44242 33.65558 -13.97459 -34.33078 33.79556 -17.75685 -32.31612 32.95711 -14.06408 -34.2785 33.78931 -13.9528 -34.36727 33.7363 -18.35273 -31.48682 33.58836 -18.42381 -31.38704 33.65063 -17.76084 -32.35443 32.8832 -14.75064 -33.69882 34.06089 -18.12015 -31.89458 33.24872 -13.94922 -34.37314 33.72663 -8.931295 -36.03801 38.37135 -14.05324 -34.29759 33.75865 -8.922149 -36.04413 38.36668 -8.295024 -36.38458 38.23017 -18.43867 -31.43134 33.58325 -14.03196 -34.33402 33.69912 -14.349 -34.59039 32.03432 -8.370193 -36.36723 38.08897 -8.11537 -36.48834 37.96317 -7.600209 -36.67519 37.90335 -17.76806 -32.44053 32.7091 -14.02846 -34.33989 33.6894 -14.93216 -33.614 33.98967 -8.716983 -36.28505 37.4974 -17.9897 -32.17973 32.92818 -14.67731 -33.9015 33.76618 -9.603993 -35.86583 37.27927 -16.02197 -33.84511 31.46324 -7.681185 -36.65829 37.75192 -9.753383 -35.82095 37.09422 -17.76917 -32.45762 32.67311 -14.66 -33.94332 33.70118 -9.74521 -35.82708 37.0882 -8.472202 -36.40672 37.35564 -17.99529 -32.21772 32.85371 -9.842284 -35.7962 36.97853 -17.77097 -32.49013 32.60319 -13.53075 -34.76013 33.24459 -14.86493 -33.81593 33.69203 -9.834214 -35.80233 36.97238 -17.77122 -32.49536 32.59178 -9.099397 -36.19025 36.9329 -14.61769 -34.03787 33.54817 -18.67515 -31.22159 33.63964 -8.054548 -36.57791 37.1176 -10.1811 -35.67526 36.66132 -17.09661 -33.12523 32.03034 -14.60868 -34.05673 33.51656 -16.1408 -33.78838 31.43043 -10.19516 -35.67116 36.64488 -14.84894 -33.85759 33.62638 -10.13384 -35.7133 36.62136 -18.4195 -31.70925 33.22386 -13.72157 -34.68416 33.15123 -18.15835 -32.0794 32.90985 -10.12611 -35.71943 36.61484 -18.69185 -31.26559 33.57179 -14.59094 -34.09273 33.45515 -10.148 -35.70921 36.60481 -18.75418 -31.16886 33.63728 -9.25026 -36.15165 36.72983 -14.58801 -34.09852 33.44513 -18.00618 -32.30301 32.6783 -10.14029 -35.71534 36.59827 -8.86554 -36.3124 36.77599 -13.80556 -34.65032 33.1113 -13.41407 -34.87783 32.98677 -18.16509 -32.11714 32.83499 -9.345315 -36.12698 36.60674 -18.50872 -31.65317 33.21784 -15.78105 -32.97757 34.04225 -9.02067 -36.27395 36.56748 -18.77146 -31.21276 33.56929 -14.80971 -33.95173 33.47184 -9.118402 -36.24936 36.44111 -18.00805 -32.31993 32.64204 -8.465863 -36.48468 36.51251 -14.80133 -33.97051 33.43991 -17.27764 -33.02948 31.9952 -9.656907 -36.0442 36.22679 -15.53389 -33.32319 33.77799 -18.0113 -32.35211 32.57158 -9.672041 -36.0401 36.20918 -18.01178 -32.35727 32.56008 -14.7848 -34.00634 33.37789 -8.628015 -36.44658 36.29487 -14.78207 -34.01211 33.36776 -11.0585 -35.32775 36.00314 -17.06497 -33.22687 31.72882 -18.17865 -32.20183 32.65864 -13.60962 -34.80127 32.89057 -9.438704 -36.16679 36.05101 -8.730151 -36.4222 36.16297 -13.69568 -34.76717 32.84942 -18.18106 -32.21862 32.62218 -15.74964 -33.21525 33.71086 -9.454258 -36.1627 36.03293 -18.46753 -31.89206 32.88189 -15.48678 -33.52246 33.47118 -10.95514 -35.42721 35.89066 -18.9743 -31.0766 33.56531 -13.20668 -35.04403 32.55383 -15.47514 -33.56352 33.40349 -10.93361 -35.44708 35.86742 -18.18536 -32.25056 32.55135 -11.23305 -35.27112 35.84042 -18.18601 -32.25568 32.53979 -16.33599 -32.62395 33.97183 -10.89163 -35.48502 35.82229 -18.77159 -31.48562 33.20375 -16.33597 -32.63616 33.95561 -18.47637 -31.92933 32.80633 -10.88475 -35.49113 35.81492 -14.39838 -34.40458 32.84879 -11.2589 -35.26265 35.81694 -16.33556 -32.68272 33.89285 -17.25014 -33.13001 31.69186 -16.43067 -32.57184 33.9494 -11.13279 -35.37047 35.72524 -18.55967 -31.83536 32.87496 -16.43083 -32.58402 33.93312 -18.85425 -31.43221 33.20045 -13.40995 -34.96648 32.45288 -11.1119 -35.39031 35.70144 -18.56914 -31.87249 32.79919 -11.1591 -35.36197 35.70136 -15.70971 -33.41351 33.40094 -18.49482 -32.01289 32.62831 -15.44603 -33.65623 33.24414 -11.1383 -35.38182 35.67748 -17.76434 -32.76553 31.91204 -11.07115 -35.42821 35.65522 -15.43973 -33.67471 33.21121 -11.06447 -35.43431 35.64768 -18.49822 -32.02944 32.5915 -16.43111 -32.6305 33.87011 -18.58904 -31.9557 32.62069 -13.49939 -34.93192 32.40968 -11.09773 -35.41971 35.63111 -18.50444 -32.0609 32.52 -15.69963 -33.45434 33.33256 -11.09109 -35.42581 35.62354 -14.60389 -34.31652 32.76541 -18.50541 -32.06595 32.50832 -9.064784 -36.34018 35.75583 -15.4272 -33.70996 33.14726 -9.08103 -36.33611 35.73697 -19.06488 -31.29456 33.19445 -18.59274 -31.97218 32.58378 -15.42512 -33.71563 33.13682 -14.30302 -34.51938 32.57863 -11.73604 -35.07176 35.49254 -18.83116 -31.66596 32.85826 -15.67413 -33.5465 33.17159 -16.99549 -33.36493 31.22271 -11.69737 -35.11548 35.44076 -18.59953 -32.0035 32.51207 -15.66856 -33.56486 33.13832 -10.46579 -35.8154 35.37671 -18.60059 -32.00852 32.50037 -16.32536 -32.91752 33.55324 -18.84249 -31.70266 32.7819 -11.60526 -35.21445 35.3189 -15.65746 -33.59988 33.0737 -11.58604 -35.23423 35.29372 -18.91654 -31.61196 32.85415 -18.01835 -32.62396 31.87509 -15.65561 -33.60551 33.06315 -11.99154 -34.9824 35.29111 -14.51351 -34.43053 32.49252 -11.54853 -35.27198 35.24482 -18.92845 -31.64852 32.77761 -19.49995 -30.6386 33.65892 -16.42457 -32.86477 33.52915 -11.54239 -35.27807 35.23684 -16.30452 -33.11292 33.23547 -17.74792 -32.86294 31.60396 -19.50597 -30.64987 33.64104 -10.65722 -35.7583 35.19893 -17.18733 -33.2661 31.18272 -17.10651 -32.13589 33.87868 -10.68556 -35.74975 35.17328 -18.86667 -31.78483 32.60199 -11.95478 -35.02602 35.23788 -14.1304 -34.68059 32.12501 -19.52881 -30.69277 33.57179 -10.26978 -35.93809 35.17821 -16.29855 -33.15309 33.16534 -11.86715 -35.12474 35.11259 -18.87124 -31.80109 32.56478 -17.11257 -32.1839 33.81285 -18.2023 -32.51977 31.85106 -11.84885 -35.14447 35.08671 -19.13408 -31.47277 32.84613 -16.40701 -33.05965 33.21009 -10.46637 -35.88093 34.99567 -17.11402 -32.1959 33.79614 -18.95397 -31.73035 32.59726 -15.28456 -34.01408 32.51555 -18.87971 -31.83197 32.4925 -11.81312 -35.18214 35.03643 -18.88104 -31.83693 32.4807 -11.80726 -35.1882 35.02823 -18.95882 -31.74654 32.55996 -10.49547 -35.87236 34.96932 -19.14747 -31.50897 32.76913 -12.41274 -34.83012 34.98458 -17.11929 -32.24169 33.73148 -18.00768 -32.71964 31.56461 -17.25861 -32.04576 33.85424 -9.932347 -36.11209 34.84488 -18.96782 -31.77728 32.4875 -12.37912 -34.87353 34.92911 -16.28263 -33.24367 33.00023 -18.96924 -31.78222 32.47567 -19.17642 -31.58993 32.58768 -11.16594 -35.60098 34.76209 -17.26583 -32.0936 33.78806 -18.19577 -32.61417 31.53888 -12.29879 -34.9718 34.79857 -19.18196 -31.60594 32.55015 -16.27902 -33.2617 32.9661 -10.13743 -36.0549 34.65432 -19.64072 -30.90647 33.19569 -17.26757 -32.10556 33.77126 -18.53944 -32.32511 31.81289 -12.28198 -34.99143 34.77159 -16.2717 -33.29607 32.89982 -12.64319 -34.74417 34.8292 -19.19231 -31.63632 32.47725 -17.70289 -32.99348 31.08691 -19.19394 -31.64119 32.46534 -12.24915 -35.02892 34.71921 -18.6399 -32.26618 31.80297 -12.24377 -35.03496 34.71066 -17.97184 -32.84714 31.04356 -12.61126 -34.78746 34.77258 -18.54047 -32.41709 31.49765 -19.72886 -31.08025 32.84207 -10.98867 -35.72328 34.54705 -18.93587 -32.09003 31.77761 -12.53489 -34.88544 34.63933 -17.139 -32.47204 33.38135 -19.7463 -31.11542 32.76386 -12.5189 -34.90501 34.6118 -19.02894 -32.03385 31.77082 -17.66767 -31.79754 33.7989 -19.78462 -31.19389 32.57952 -12.48764 -34.94239 34.55834 -19.79207 -31.20936 32.54139 -12.48251 -34.94841 34.54961 -19.80608 -31.2387 32.46731 -17.88123 -31.66455 33.77593 -12.58645 35.18772 33.43783 -12.75906 35.12495 33.33761 -12.89174 35.00553 33.58538 -16.33603 32.974 33.4475 -17.14081 32.28093 33.65822 -16.35013 32.72388 33.8207 -12.07334 35.05248 34.95872 -12.39062 34.86931 34.92116 -12.15748 34.95397 35.08657 -12.31049 34.96756 34.79048 -13.17108 35.11086 31.68598 -13.36788 35.03641 31.59203 -13.51876 34.92442 32.40038 -13.23094 35.03485 32.54158 -12.05576 35.07216 34.93231 -12.29373 34.98719 34.76349 -17.74765 32.86308 31.60386 -18.02567 32.61981 31.87389 -17.76408 32.76567 31.91195 -18.01517 32.71545 31.56333 -15.79167 32.93037 34.09742 -12.01583 35.11575 34.8727 -16.0662 32.7853 34.02007 -12.25565 35.03066 34.70255 -12.18016 35.26277 34.0208 -12.72338 35.0679 33.6828 -17.29303 33.02128 31.9923 -17.77096 32.49544 32.5918 -17.32496 32.74488 32.66207 -17.15703 32.83661 32.6924 -12.49651 34.94323 34.54057 -12.52553 35.29406 32.92152 -15.7823 33.02432 33.97355 -16.06086 32.87874 33.89466 -17.97959 32.84287 31.04214 -18.51056 32.54528 30.96981 -12.86634 35.22368 31.83795 -12.34595 35.35748 33.02645 -16.31559 33.14211 33.16538 -17.16236 32.6901 32.98222 -17.15921 32.52606 33.27338 -11.92427 35.35123 34.19338 -16.31523 33.1445 33.16115 -17.16234 32.69243 32.97785 -12.02936 35.3837 33.78539 -11.76687 35.47259 33.96277 -16.03483 33.13056 33.52606 -11.66939 35.43724 34.37455 -17.11563 33.11524 32.02654 -11.40459 35.2127 35.69253 -12.15961 34.95137 35.08985 -16.29957 33.23503 32.99593 -17.16011 32.78048 32.80725 -11.40212 35.21531 35.68951 -11.76614 35.55525 33.39006 -17.26588 33.12171 31.68881 -15.57272 33.13158 34.03798 -11.30484 35.31453 35.57181 -16.29601 33.25305 32.96179 -12.11885 35.48779 32.24608 -17.1593 32.79797 32.772 -11.28456 35.33434 35.5475 -17.70261 32.99363 31.0868 -15.54099 33.14765 34.04813 -11.2478 35.26452 35.83224 -11.24526 35.26713 35.82929 -16.28759 33.29288 32.88471 -11.50535 35.55896 34.14894 -16.00573 33.30003 33.24749 -11.23857 35.37825 35.49262 -11.92842 35.55226 32.35863 -16.00524 33.30245 33.24331 -11.14521 35.36647 35.71392 -15.74476 33.27772 33.60956 -11.49282 35.64482 33.57551 -11.12437 35.38631 35.69009 -17.08441 33.21676 31.72483 -11.07471 35.32076 35.99309 -15.98463 33.39382 33.08019 -11.07209 35.32338 35.99021 -11.0771 35.43026 35.63629 -15.98007 33.41201 33.04649 -11.00461 35.34503 36.05489 -10.96897 35.42283 35.87751 -15.52652 33.38612 33.67759 -15.96938 33.45225 32.9704 -10.9475 35.44269 35.85423 -11.22044 35.73177 33.77006 -15.49347 33.40236 33.68829 -10.9003 35.44452 35.94326 -15.70729 33.44845 33.33454 -10.89881 35.48669 35.80169 -10.87858 35.46439 35.92021 -15.70667 33.45088 33.33041 -10.82933 35.5084 35.86816 -19.92248 30.19867 33.8299 -17.20363 33.25764 31.17941 -10.84253 35.70195 35.03403 -19.96448 30.26559 33.72528 -15.68129 33.54302 33.16939 -19.98848 30.30389 33.66334 -11.31318 35.75278 32.74826 -20.04104 30.38793 33.52177 -19.73668 30.43338 33.70967 -10.6706 35.75427 35.18677 -17.01564 33.35462 31.2184 -15.67574 33.56137 33.13612 -19.75916 30.47197 33.64802 -10.65665 35.82448 34.82633 -15.48273 33.55776 33.40533 -19.80827 30.55668 33.50715 -11.02296 35.84333 32.94678 -10.4807 35.81099 35.36258 -15.48202 33.56021 33.40125 -20.17902 30.60993 33.10335 -19.31464 30.78895 33.63073 -15.44872 33.57414 33.41645 -19.93657 30.78085 33.09098 -10.48011 35.87689 34.98318 -10.40668 35.8328 35.43323 -15.448 33.57659 33.41238 -20.2682 30.75477 32.78536 -20.26944 30.7568 32.78058 -10.73359 35.93105 33.15494 -15.66286 33.60198 33.06101 -19.35712 30.87492 33.49129 -16.19676 33.58219 32.24015 -10.28509 35.93368 35.1637 -20.31594 30.83293 32.59384 -20.32505 30.8479 32.55522 -10.33587 35.99837 34.47753 -15.45303 33.6529 33.24185 -20.01882 30.92751 32.77484 -10.20907 35.95551 35.23625 -10.17813 35.6761 36.66485 -15.44674 33.67137 33.20892 -10.12317 35.72023 36.61843 -15.41846 33.66936 33.25323 -20.01996 30.92957 32.77009 -15.41206 33.68785 33.22036 -20.34501 30.88078 32.46798 -10.15176 36.05086 34.64128 -20.06256 31.00683 32.58448 -15.4322 33.71224 33.13458 -9.948323 36.10768 34.82973 -15.39727 33.72876 33.14613 -20.07087 31.02204 32.54609 -9.913025 35.78018 36.87275 -9.869002 36.1295 34.90546 -16.14426 33.68891 31.94813 -19.46671 31.10312 33.07968 -9.844598 35.7994 36.95923 -9.753716 35.82469 37.07713 -15.86027 33.7451 32.33413 -20.08905 31.05546 32.4594 -9.792916 36.19875 33.91126 -9.653706 36.04505 36.23055 -18.88445 31.19622 33.49247 -19.53556 31.25315 32.76726 -15.79989 33.85355 32.04589 -9.596942 36.25119 34.08622 -15.53607 33.89807 32.43303 -9.601631 35.86644 37.2827 -19.53651 31.25527 32.76257 -16.86241 33.49491 30.39798 -9.435414 36.16764 36.05487 -20.48016 31.10749 31.73702 -16.04118 33.83598 31.4579 -9.429393 36.10493 36.5008 -19.57155 31.33463 32.57922 -15.29203 34.01066 32.51302 -9.380323 36.30784 34.28754 -15.25507 34.02753 32.52556 -19.57833 31.35029 32.54131 -9.35633 36.1241 36.59271 -15.46802 34.00809 32.14855 -18.97452 31.42842 33.08593 -9.295839 36.32957 34.36843 -19.59307 31.38473 32.45568 -14.37116 33.92775 34.11723 -18.32926 31.45202 33.65142 -9.25927 36.14932 36.718 -15.68404 34.00365 31.56196 -20.21025 31.28714 31.73307 -9.204839 36.22737 36.33234 -9.129725 36.24649 36.4267 -14.21541 33.99671 34.18745 -18.35716 31.54055 33.51552 -9.061347 36.34102 35.75986 -20.52381 31.18345 31.40558 -15.21818 34.1218 32.23146 -19.02936 31.58179 32.7776 -9.096797 36.19091 36.93648 -15.18034 34.13882 32.24445 -19.0301 31.58396 32.77297 -9.029933 36.27163 36.55535 -14.29362 34.10371 33.86109 -8.820471 36.40038 36.04945 -19.05722 31.6654 32.5921 -8.862866 36.31306 36.77967 -20.24805 31.36555 31.40375 -14.29241 34.10622 33.85725 -8.741984 36.41935 36.14794 -17.89286 31.68201 33.74477 -8.637697 36.44428 36.28221 -19.06238 31.68149 32.55471 -8.963754 36.00593 38.44385 -13.97453 34.10152 34.30159 -14.2441 34.2015 33.70735 -8.715856 36.28533 37.49918 -17.9031 31.72266 33.68597 -8.922201 36.04409 38.36677 -14.13328 34.17318 33.93371 -8.940558 36.01178 38.48776 -19.07352 31.71694 32.47026 -15.33976 34.16094 31.67092 -8.434901 36.53906 35.281 -18.42552 31.77697 33.11503 -8.898536 36.05002 38.41096 -14.132 34.1757 33.9299 -8.463068 36.48533 36.51635 -17.65625 31.74801 33.86739 -17.92472 31.81222 33.55178 -8.875139 36.05586 38.4552 -8.295024 36.38458 38.23017 -14.23386 34.22051 33.67639 -14.21044 34.26261 33.60648 -8.471043 36.407 37.35747 -19.68711 31.62561 31.73857 -8.17788 36.59744 35.59028 -20.57404 31.27589 30.84971 -8.094106 36.61606 35.69548 -17.67217 31.81915 33.76861 -14.08105 34.27129 33.78141 -7.982773 36.64049 35.83889 -17.68095 31.86002 33.71021 -15.83584 33.9923 30.6632 -8.370164 36.36724 38.08903 -18.46474 31.93383 32.81153 -8.344831 36.3731 38.13602 -14.07028 34.29037 33.75073 -8.319782 36.37888 38.18307 -18.46525 31.93605 32.80698 -15.08052 34.27662 31.75872 -8.053336 36.57818 37.11951 -17.69931 31.95009 33.57697 -15.04125 34.29393 31.77247 -13.88527 34.27876 34.05166 -8.115341 36.48835 37.96322 -20.2891 31.46234 30.85139 -8.089268 36.49416 38.01149 -13.88388 34.28129 34.04792 -19.71352 31.70856 31.41347 -18.48352 32.01965 32.62901 -8.063488 36.4999 38.05981 -7.600209 36.67519 37.90335 -7.681155 36.65829 37.75197 -14.04565 34.33261 33.68149 -7.653866 36.66401 37.80238 -17.97531 32.05189 33.15657 -7.626882 36.66965 37.85284 -13.82884 34.37733 33.90166 -13.81723 34.3965 33.87145 -18.48689 32.03621 32.59223 -15.45919 34.16524 30.77733 -18.49399 32.0727 32.50915 -17.27491 32.05973 33.82242 -13.79071 34.43896 33.80325 -19.13899 31.96689 31.76319 -17.28108 32.10098 33.76478 -13.38526 34.34856 34.61084 -17.74064 32.19139 33.18463 -13.99838 34.57174 33.02221 -15.09592 34.3273 30.89635 -17.12534 32.14824 33.84634 -13.2355 34.40925 34.69667 -18.00172 32.21144 32.85726 -13.82374 34.64297 33.10272 -18.00204 32.2137 32.85277 -13.2784 34.52751 34.3709 -17.29356 32.19195 33.6333 -17.13053 32.18963 33.789 -13.27676 34.53007 34.36731 -19.73661 31.81342 30.8681 -19.15334 32.05432 31.44268 -13.89325 34.68796 32.75757 -18.01304 32.29897 32.67731 -14.82224 34.44635 30.99198 -14.78076 34.46417 31.00693 -13.21162 34.62712 34.22691 -18.01493 32.31587 32.64105 -13.12414 34.58861 34.45944 -17.76037 32.35228 32.88758 -13.12243 34.59117 34.45588 -13.19793 34.6465 34.19792 -17.7606 32.35456 32.88313 -18.01871 32.35317 32.55916 -13.55351 34.75113 33.23326 -13.71431 34.75977 32.84058 -17.31824 32.43606 33.24636 -13.16676 34.68942 34.13246 -17.7678 32.44066 32.70903 -13.0547 34.68845 34.31707 -18.5274 32.3321 31.81381 -13.04049 34.70788 34.2884 -17.76891 32.45774 32.67305 -13.00812 34.75091 34.22368 -12.75274 34.59923 34.99514 -13.4374 34.86876 32.97509 -19.15735 32.16714 30.90493 -13.70469 34.85162 32.31319 -17.32592 32.59926 32.95355 -17.32597 32.60158 32.94915 -12.52558 34.68566 35.14786 -12.62675 34.77978 34.76714 -18.52816 32.42419 31.49865 -16.35117 32.58891 34.0033 -12.62482 34.78236 34.76372 -17.32633 32.68911 32.77758 -12.54868 34.88032 34.63032 -12.53275 34.89989 34.60277 -17.32605 32.70649 32.74213 -16.35129 32.63098 33.94763 -12.39265 34.86673 34.92451 -8.39043 -36.26324 41.22835 -7.510005 -36.86149 41.54566 -9.159487 -35.68567 41.77916 -8.143141 -36.42881 41.1847 -8.50871 -36.15827 39.31418 -8.134133 -36.37761 39.17392 -8.041297 -36.41577 39.36996 -8.480863 -36.14799 40.72654 -8.709401 -36.07933 38.93391 -8.756689 -35.93955 40.79388 -9.16416 -35.58019 40.79699 -8.780775 -35.91575 40.69223 -7.445809 -36.70415 39.9509 -6.873828 -36.8854 39.22163 -6.672621 -36.97583 39.76436 -7.631104 -36.61039 39.45048 -6.548787 -37.05256 40.20413 -9.141259 -35.60424 40.89465 -8.668504 -36.05551 41.28127 -8.420713 -36.19717 39.5024 -7.96101 -36.45179 39.55465 -9.304437 -35.44226 40.83758 -8.689862 -36.03798 39.38348 -9.281994 -35.46642 40.93385 -6.416271 -37.19124 40.94993 -5.565613 -37.4639 41.42602 -5.599721 -37.35731 40.87351 -5.706419 -37.23954 40.2039 -6.518999 -37.07571 40.33298 -9.056556 -35.72161 41.36295 -8.344539 -36.23381 39.67962 -9.198689 -35.58444 41.39551 -9.48393 -35.28046 41.46596 -8.604249 -36.07717 39.56801 -7.78297 -36.54682 40.03742 -7.330597 -36.78209 40.35605 -7.302625 -36.80534 40.47475 -8.530104 -36.11407 39.74173 -8.837693 -35.90967 39.65309 -7.313271 -36.74643 38.35218 -6.185412 -37.02307 38.77246 -7.671731 -36.62531 40.42812 -8.175181 -36.33016 40.14255 -7.071028 -36.81662 38.79463 -8.766166 -35.94684 39.82246 -6.965163 -36.85182 39.01436 -7.644605 -36.64864 40.54259 -5.737931 -37.21638 40.06397 -5.73753 -37.21643 40.0639 -8.365044 -36.21098 40.19535 -8.033104 -36.46219 38.64669 -7.204221 -36.91978 41.04346 -8.068742 -36.40932 40.517 -8.606668 -36.04441 40.26453 -8.346051 -36.30036 38.7782 -7.811742 -36.53763 39.05614 -8.042648 -36.43278 40.62669 -8.261002 -36.29048 40.56216 -7.548296 -36.76298 41.0911 -7.714842 -36.57502 39.25915 -8.235429 -36.31401 40.66961 -8.878073 -35.83531 40.34516 -8.505751 -36.12434 40.62187 -7.948985 -36.54734 41.15247 -7.715334 36.57493 39.25861 -6.708054 36.95764 39.65727 -6.965708 36.85174 39.01379 -7.478564 36.68547 39.85221 -8.320232 36.25174 40.57684 -8.24753 36.32637 40.91301 -8.108695 36.41462 40.88516 -8.182392 36.34016 40.54399 -7.737088 36.56624 39.21152 -6.989462 36.84354 38.9628 -8.205238 36.31106 40.05131 -7.671428 36.62538 40.42855 -7.814499 36.52794 39.94223 -8.068458 36.4094 40.5174 -8.317321 36.24157 40.08354 -8.610051 36.04799 40.64857 -8.539524 36.12305 40.97449 -8.041767 36.41568 39.36944 -8.062614 36.40682 39.32397 -7.971685 36.48208 38.7544 -7.246027 36.76484 38.46847 -8.452892 36.15284 40.12313 -9.159487 35.68567 41.77916 -9.01962 35.72891 41.08542 -6.4644 37.12658 40.61018 -7.510005 36.86149 41.54566 -5.565613 37.4639 41.42602 -5.737252 37.21641 40.06445 -8.125615 36.43366 38.49273 -7.4146 36.72014 38.18612 -6.54843 37.05262 40.20461 -8.421155 36.19707 39.50189 -7.250899 36.85605 40.73019 -8.737831 35.94842 40.20866 -6.185705 37.02297 38.77176 -8.440922 36.18805 39.45825 -7.330278 36.78216 40.35649 -9.239464 35.51892 41.14108 -8.287265 36.32076 38.88234 -7.594236 36.69942 40.78892 -8.529923 36.12714 39.54065 -9.086283 35.6529 40.77544 -8.549375 36.11808 39.49752 -8.661449 36.03791 39.58804 -7.993956 36.48374 40.86277 -8.434579 36.27107 38.62928 -8.680517 36.02881 39.54551 -9.304211 35.44234 40.83794 -8.653744 36.10019 39.03403 -8.937757 35.83259 39.68952 -8.758753 36.0298 39.07817 -8.793199 36.04935 38.79066 -4.7 38.77383 45.30918 -5.422756 39.31499 46.66567 -5.415564 39.41542 46.85608 -5.346814 40.41449 48.5252 -5.131311 40.43612 48.51565 -4.915705 40.45687 48.5065 -4.7 40.47674 48.49773 -4.7 37.5 40.98409 -5.533431 37.24727 40.06445 -4.938838 37.33076 40.06445 -4.34329 37.40473 40.06445 -5.488543 38.42993 44.71625 -5.023723 37.97237 43.1821 -4.7 38.0138 43.1821 -5.476336 38.58978 45.11266 -5.112014 38.63973 45.11266 -4.7 41.33279 50.03776 -5.2734 41.71543 51.12278 -4.7 41.95374 51.68732 -5.165181 42.35172 53.93165 -4.7 42.39614 54.01949 -4.7 42.37198 56.39598 -5.022377 42.29809 56.83467 -4.7 41.80102 58.97309 -4.870651 41.66931 59.32511 -4.7 40.53239 61.6143 -4.7 40.1337 62.20015 -6.333713 39.94978 62.06695 -6.293501 24.31617 83.6716 -7.825 23.80239 83.2995 -7.853824 39.43129 61.69143 -9.140128 22.98509 82.70757 -9.157771 38.61321 61.09893 -10.14926 21.91997 81.93616 -10.15758 37.55073 60.32944 -10.78363 20.67961 81.03783 -10.78578 36.31555 59.43486 -11 19.34854 80.07381 -11 34.99099 58.47556 -4.716712 40.27031 62.00741 -4.7 40.27044 62.0075 -4.733315 40.40315 61.81206 -4.7 40.40344 61.81225 -4.749802 40.53215 61.61415 -6.347452 40.08084 61.87574 -6.361091 40.20814 61.68211 -6.611975 40.01546 61.83031 -4.889425 41.49375 59.76872 -6.374626 40.33163 61.48611 -6.625007 40.14151 61.63771 -6.637937 40.26377 61.44278 -4.919738 41.66761 59.32447 -7.863661 39.5535 61.50929 -7.873422 39.67213 61.32495 -7.883104 39.78713 61.13845 -6.48887 41.24687 59.66553 -8.384959 39.27319 61.31451 -6.747034 41.16921 59.63306 -8.393195 39.38786 61.13553 -6.513586 41.41094 59.2289 -5.057359 42.25795 57.07625 -8.401364 39.499 60.95447 -6.770625 41.33134 59.19926 -5.070764 42.29447 56.83415 -9.163643 38.72387 60.93278 -9.169469 38.83127 60.76465 -9.175247 38.93536 60.59458 -7.964668 40.63635 59.41032 -7.982276 40.78776 58.99686 -9.795276 38.11198 60.50758 -8.470153 40.31909 59.2777 -6.625404 41.95997 57.02711 -9.79907 38.21173 60.35183 -6.636261 41.9929 56.7907 -9.802833 38.30841 60.19427 -6.877308 41.87279 57.01274 -8.484995 40.46515 58.87674 -6.887663 41.90512 56.77805 -10.16021 37.64767 60.18493 -5.19754 42.37838 54.28098 -10.16282 37.74178 60.03868 -5.212927 42.34761 53.93206 -10.16541 37.83301 59.89073 -9.223891 39.70313 59.02021 -9.234384 39.83978 58.64388 -8.061768 41.28969 56.91659 -10.69446 36.65406 59.49447 -8.069472 41.31917 56.69363 -9.834524 39.02195 58.73547 -10.69537 36.73632 59.3687 -10.78641 36.39708 59.3159 -10.69627 36.8161 59.24143 -8.551978 40.94841 56.86032 -6.738659 42.04951 54.30397 -9.841362 39.14906 58.3867 -10.78703 36.4763 59.19544 -8.558468 40.97667 56.64428 -10.78765 36.55315 59.07353 -11 35.63901 57.32134 -6.751052 42.01657 53.96493 -6.985284 41.95806 54.31036 -10.18722 38.50694 58.52019 -5.30674 41.84869 51.53282 -6.997094 41.925 53.97402 -10.19193 38.62717 58.19237 -5.32063 41.71094 51.12436 -9.281725 40.2915 56.752 -9.28631 40.31786 56.54937 -10.70387 37.40734 58.06053 -8.142007 41.35816 54.35229 -5.356153 41.23479 49.98167 -9.87222 39.56993 56.63302 -8.15077 41.32548 54.03355 -10.79289 37.12316 57.94174 -10.70551 37.51331 57.77763 -9.875209 39.59458 56.44516 -8.619544 41.01172 54.37651 -6.826446 41.51416 51.63771 -10.79402 37.22548 57.67045 -8.62692 40.97976 54.06788 -7.068924 41.42434 51.66588 -10.21319 39.02626 56.54337 -6.837586 41.37795 51.24211 -10.21525 39.04978 56.36667 -7.079535 41.2889 51.2736 -9.329458 40.34947 54.4228 -9.334667 40.31936 54.13346 -6.866046 40.90976 50.13608 -7.135223 40.02381 48.78318 -10.71294 37.86797 56.35238 -7.106639 40.82375 50.17694 -8.204015 40.84328 51.84808 -10.71366 37.88925 56.19946 -9.903347 39.62597 54.47337 -10.79914 37.56882 56.30305 -8.211872 40.71391 51.47692 -10.79964 37.58955 56.15628 -11 36.06751 54.7221 -11 36.00545 56.04527 -9.906745 39.59832 54.20506 -8.671726 40.51104 51.95226 -10.23466 39.08239 54.51137 -8.678336 40.38554 51.59304 -10.237 39.05674 54.25883 -8.231934 40.27074 50.43966 -8.712994 39.21982 49.31408 -9.366309 39.87922 52.15037 -9.370976 39.76149 51.81371 -8.695211 39.95592 50.58922 -10.72046 37.9263 54.59218 -10.72128 37.90514 54.37318 -9.927386 39.19182 52.36592 -10.80433 37.62789 54.61303 -10.8049 37.60791 54.4027 -9.930432 39.08289 52.05367 -9.38289 39.3586 50.87298 -9.946398 38.07069 50.0729 -10.25124 38.67645 52.52752 -10.25335 38.57426 52.23353 -9.938206 38.70992 51.18115 -10.72628 37.58185 52.87075 -10.25871 38.22404 51.41198 -10.7309 36.6738 50.99532 -10.80835 37.29943 52.9593 -10.72702 37.49415 52.61547 -10.80886 37.21549 52.71401 -10.72891 37.19271 51.90193 -10.81017 36.92667 52.02832 -11 35.14755 52.00316 -11 35.82207 53.42255 -11 35.5347 52.68959 -10.79828 12.3429 85.2378 -10.79828 -12.3429 85.2378 -10.94937 12.3429 84.45028 -10.94937 -12.3429 84.45028 -11 12.3429 83.65 -11 -12.3429 83.65 -9.49896 15.86027 87.25524 -9.498601 15.5 87.35264 -8.376869 16.14753 88.25612 -10.78363 17.96693 83.62128 -10.14926 18.80369 84.90398 -10.14926 19.30305 84.55965 -8.376869 16.86463 88.02896 -5.84728 20.47618 87.4678 -10.14926 19.96085 84.0442 -9.49896 19.84751 85.30745 -9.49896 20.55676 84.75168 -5.84728 18.8986 88.36484 -7.003853 18.74953 88.06094 -9.49896 21.36981 84.00431 -8.376869 22.10704 84.73969 -10.78363 13.77969 85.19273 -11 13.6982 83.54316 -10.78363 18.40162 83.32154 -11 17.43426 81.99289 -9.49896 16.52322 87.04523 -10.14926 20.71491 83.35105 -10.14926 15.60508 86.36613 -10.78363 18.97422 82.87285 -11 18.46704 81.1088 -5.84728 21.10481 87.03433 -10.78363 19.63062 82.26947 -8.376869 18.41646 87.38192 -7.003853 17.1126 88.74347 -7.003853 20.29124 87.18429 -10.78363 14.50941 85.06292 -11 15.02002 83.2253 -10.14926 16.21994 86.17135 -5.84728 21.93288 86.38545 -7.003853 20.90557 86.76069 -10.78363 15.18258 84.89406 -9.49896 17.95788 86.44704 -8.376869 19.87801 86.55084 -7.003853 21.71482 86.12656 -10.78363 15.71781 84.72451 -11 16.27571 82.70425 -5.84728 22.88216 85.51286 -10.14926 17.55052 85.61656 -8.376869 20.46041 86.14926 -9.49896 19.30909 85.67872 -5.84728 16.44955 89.30844 -7.003893 15.5 89.20088 -5.847279 15.5 89.54747 -7.003853 22.64251 85.27381 -5.84728 17.22358 89.06325 -8.376869 21.22758 85.5481 -7.003853 16.35617 88.98309 -8.376744 15.5 88.4249 -10.78363 16.87606 84.24157 -7.37055 -16.31205 88.82937 -6.056766 -16.43744 89.26625 -6.056766 -15.5998 89.48047 -8.581598 -16.81387 87.88271 -8.581598 -18.54287 87.14554 -7.37055 -18.88442 87.81461 -7.37055 -21.61179 86.00424 -6.056766 -23.2149 85.104 -6.056766 -21.90461 86.35188 -7.37055 -17.06017 88.59239 -10.78363 -17.96693 83.62128 -11 -16.27571 82.70425 -11 -17.43426 81.99289 -10.78363 -18.40162 83.32154 -7.37055 -22.88196 84.79458 -10.35224 -18.59558 84.58495 -10.35224 -17.54608 85.19285 -9.557027 -19.27102 85.62036 -9.557027 -18.10815 86.29393 -6.056766 -20.4522 87.43103 -6.056766 -21.07897 86.99885 -8.581598 -16.10482 88.10732 -8.581332 -15.5 88.26564 -9.556666 -15.5 87.28072 -9.557027 -21.63131 83.63228 -10.14926 -21.91997 81.93616 -9.140128 -22.98509 82.70757 -9.557027 -16.50038 86.97941 -8.581598 -22.3317 84.28319 -7.37055 -20.81144 86.6314 -10.78363 -17.02295 84.16806 -9.557027 -15.84104 87.18827 -9.994142 -15.5 86.65973 -8.581598 -21.12785 85.42969 -10.35224 -16.09506 85.8115 -10.78363 -15.71781 84.72451 -11 -15.02002 83.2253 -7.37055 -20.20386 87.05035 -6.056766 -19.09107 88.21944 -10.78363 -15.18258 84.89406 -10.78363 -14.60165 85.04262 -11 -13.6982 83.54316 -10.35224 -20.72576 82.79069 -10.78363 -20.67961 81.03783 -10.78363 -13.95571 85.16637 -8.581598 -20.36929 86.0241 -9.557027 -20.51187 84.69839 -8.581598 -19.79343 86.42118 -10.78363 -19.88295 82.00742 -11 -18.46704 81.1088 -11 -19.34854 80.07381 -9.557027 -19.8065 85.25113 -10.35224 -19.71546 83.75287 -6.056766 -17.20919 89.02179 -10.35224 -19.07885 84.25172 -6.293501 -24.31617 83.6716 -10.78363 -18.97422 82.87285 -7.825 -23.80239 83.2995 -6.056741 -15.5 89.50244 -7.370402 -15.5 89.03676 -4.875115 -41.69372 59.25862 -4.7 -41.67559 59.32489 -4.7 -40.53239 61.6143 -4.7 -42.31436 56.84536 -5.028336 -42.31231 56.72544 -5.157455 -42.36853 54.10743 -4.7 -42.38771 53.92855 -5.259239 -41.85508 51.5373 -4.7 -41.76324 51.09728 -5.309008 -41.24217 49.98382 -4.7 -40.47674 48.49773 -4.915705 -40.45687 48.5065 -5.131311 -40.43612 48.51565 -5.346814 -40.41449 48.5252 -10.78641 -36.39707 59.31589 -10.78578 -36.31555 59.43486 -11 -34.99099 58.47556 -10.69537 -36.73625 59.36866 -10.69446 -36.65404 59.49446 -10.78703 -36.47623 59.1954 -11 -35.42227 57.78101 -10.78765 -36.55301 59.07345 -10.79025 -36.85456 58.53489 -5.356067 -41.23769 49.98594 -5.324698 -41.66682 51.00179 -5.306539 -41.85061 51.53867 -6.865974 -40.91259 50.14022 -7.135223 -40.02381 48.78318 -7.10657 -40.82656 50.18105 -6.840846 -41.3344 51.12343 -7.08264 -41.24562 51.15591 -6.826285 -41.51607 51.64338 -5.222804 -42.32175 53.70254 -7.068771 -41.42623 51.6715 -8.231883 -40.2734 50.44354 -8.712994 -39.21982 49.31408 -5.20524 -42.36452 54.10777 -8.695168 -39.9585 50.59298 -8.214171 -40.67259 51.36559 -8.203902 -40.84509 51.8534 -6.759003 -41.98952 53.742 -8.680269 -40.34548 51.48529 -9.382859 -39.36102 50.87651 -9.946398 -38.07069 50.0729 -7.004671 -41.89791 53.75288 -6.744862 -42.03452 54.13564 -8.67163 -40.5128 51.95741 -5.090424 -42.33972 56.47032 -6.991195 -41.943 54.14337 -5.076717 -42.30916 56.72499 -9.372341 -39.72391 51.71273 -9.938186 -38.71216 51.18442 -9.366241 -39.88087 52.1552 -8.156391 -41.29895 53.82403 -10.2587 -38.22614 51.41506 -10.7309 -36.6738 50.99532 -9.931322 -39.04812 51.96001 -8.146394 -41.34321 54.19403 -6.652175 -42.03306 56.43564 -8.631651 -40.95387 53.86501 -9.927342 -39.19334 52.37039 -6.641082 -42.00602 56.68415 -6.902839 -41.94448 56.42561 -8.623236 -40.99708 54.22327 -10.25396 -38.54162 52.14535 -4.930674 -41.72688 59.16005 -6.89226 -41.91799 56.67228 -4.924179 -41.69187 59.25794 -10.7289 -37.19453 51.9046 -10.25121 -38.67788 52.53173 -9.338009 -40.295 53.94327 -10.81016 -36.92841 52.03088 -11 -35.73706 53.17158 -11 -35.14755 52.00316 -9.332066 -40.33568 54.27913 -8.080759 -41.35475 56.35891 -10.72724 -37.46612 52.53889 -8.072891 -41.33085 56.59317 -4.819061 -41.03944 60.73759 -9.908924 -39.57591 54.02869 -10.80901 -37.18865 52.64042 -10.72627 -37.58307 52.87441 -6.522494 -41.46672 59.06745 -8.567974 -41.0107 56.31999 -9.905048 -39.61332 54.34014 -6.517204 -41.43378 59.16356 -10.80834 -37.30061 52.96282 -11 -36.04179 54.44847 -8.561348 -40.98785 56.54695 -6.779127 -41.38643 59.03887 -10.2385 -39.03589 54.09283 -6.774078 -41.35389 59.13435 -4.749799 -40.53193 61.61401 -4.7 -40.40334 61.81218 -4.733314 -40.40305 61.81199 -4.7 -40.27041 62.00748 -10.23583 -39.07067 54.38598 -4.716712 -40.27028 62.00739 -4.7 -40.1337 62.20015 -9.293028 -40.34957 56.24521 -9.288346 -40.32828 56.45807 -6.431381 -40.81579 60.61987 -7.988619 -40.83915 58.84406 -10.72181 -37.88775 54.2292 -6.692145 -40.74292 60.58152 -7.984852 -40.8088 58.93501 -9.879589 -39.62429 56.16317 -10.72087 -37.91667 54.48345 -10.80526 -37.59142 54.2644 -9.876536 -39.60434 56.36052 -6.374624 -40.33142 61.48598 -8.490342 -40.5147 58.72857 -10.80461 -37.61882 54.5086 -8.487167 -40.48544 58.81676 -6.36109 -40.20804 61.68204 -6.637935 -40.26356 61.44265 -10.21827 -39.0782 56.1014 -6.347452 -40.08081 61.87572 -6.333713 -39.94978 62.06695 -6.625006 -40.14141 61.63765 -10.21617 -39.0591 56.28705 -6.611975 -40.01543 61.83029 -7.853824 -39.43129 61.69143 -7.92366 -40.23715 60.3153 -9.238163 -39.88613 58.50483 -9.235919 -39.85876 58.5876 -8.435574 -39.93373 60.1556 -7.883103 -39.78693 61.13832 -10.71472 -37.91523 55.96985 -7.873422 -39.67203 61.32488 -10.71398 -37.89774 56.13055 -9.843825 -39.19219 58.25782 -10.80037 -37.61492 55.93588 -7.863661 -39.55347 61.50928 -9.842362 -39.16672 58.33453 -10.79986 -37.59782 56.09014 -11 -35.75042 57.0327 -11 -36.04524 55.75832 -8.401363 -39.4988 60.95435 -9.199441 -39.34243 59.84437 -8.393195 -39.38776 61.13547 -10.19363 -38.66798 58.07122 -8.384959 -39.27317 61.31449 -9.157771 -38.61321 61.09893 -10.19262 -38.64388 58.14334 -9.175247 -38.93517 60.59447 -9.818594 -38.68663 59.49919 -9.169469 -38.83118 60.76459 -9.163643 -38.72384 60.93277 -10.7061 -37.54934 57.67304 -10.17625 -38.19007 59.23783 -10.70575 -37.52806 57.7353 -9.802833 -38.30824 60.19417 -10.79443 -37.26028 57.57015 -10.79418 -37.23973 57.62986 -9.79907 -38.21165 60.35177 -9.795276 -38.11196 60.50757 -10.15758 -37.55073 60.32944 -10.16541 -37.83285 59.89063 -10.16282 -37.7417 60.03863 -10.16021 -37.64765 60.18492 -10.70005 -37.12889 58.67928 -10.69627 -36.81597 59.24134 -4.7 -39.34414 46.54005 -5.463154 -38.76458 45.52038 -4.7 -37.5 40.98409 -4.343282 -37.40466 40.06392 -4.938829 -37.33069 40.06392 -5.533421 -37.2472 40.06392 -5.521684 -38.00549 43.51834 -5.037032 -38.07297 43.51828 -4.7 -38.44082 44.46861 -5.134477 -38.80952 45.52036 -7.454901 37.87263 44.93159 -7.468839 37.61016 44.2342 -8.788495 36.7841 44.51937 -10.93784 34.6269 49.3896 -10.93793 34.49977 49.14745 -11 33.49735 49.12617 -10.73937 33.93359 45.50347 -10.75623 33.0815 42.65853 -10.75363 33.88732 45.51944 -7.296463 37.02215 41.81607 -7.506957 36.91563 41.80186 -7.506522 36.92337 41.83719 -7.29692 37.01446 41.78091 -9.107841 37.55403 47.12775 -9.974376 35.96714 46.19114 -9.965406 36.61377 47.59094 -10.74212 33.12911 42.64835 -9.977 35.78253 45.73918 -9.981181 35.49252 44.96527 -10.33603 34.90376 45.16853 -10.33334 35.20056 45.96404 -9.12432 36.93417 45.79348 -7.242221 37.96579 44.89559 -10.33165 35.38951 46.42867 -9.158469 35.72047 41.94572 -9.992965 34.70181 42.15636 -7.256866 37.70485 44.2015 -9.157809 35.74305 42.05038 -9.992606 34.72534 42.26607 -10.75 35.07995 48.34654 -10.75206 34.39193 46.83889 -10.93807 34.29095 48.73522 -9.10311 37.73637 47.47928 -9.962832 36.80403 47.95981 -10.73552 35.12419 48.32475 -10.56379 34.906 46.6275 -10.73771 34.43735 46.82022 -8.754254 37.84394 46.98493 -8.773724 37.23284 45.67066 -9.15757 35.75125 42.08777 -9.992476 34.73389 42.30527 -11 32.2316 46.09107 -9.136821 36.47904 44.62469 -8.813013 36.06649 42.02038 -10.93856 33.58188 47.172 -10.9387 33.37961 46.66764 -7.446154 38.0397 45.33886 -8.77942 37.05831 45.24623 -10.5666 34.41107 45.33863 -10.57128 33.62047 42.54331 -9.100257 37.84733 47.68571 -9.961279 36.91983 48.17644 -8.814075 36.03613 41.88045 -7.233033 38.13188 45.30096 -10.74941 35.28251 48.74402 -8.813296 36.0584 41.98354 -8.748665 38.0237 47.33119 -10.7349 35.32639 48.7214 -8.745295 38.13309 47.53452 -10.75267 34.19561 46.35235 -10.93893 33.06203 45.80437 -10.56009 35.58064 48.09988 -10.74905 35.40581 48.97749 -7.416274 38.62477 46.60028 -10.73452 35.44948 48.95438 -10.73835 34.24136 46.33467 -7.201644 38.71356 46.55654 -7.407701 38.79689 46.93269 -10.3433 34.12759 42.43489 -10.55902 35.77922 48.488 -7.19264 38.8847 46.88743 -7.402531 38.90164 47.1279 -9.129141 36.75716 45.36259 -7.18721 38.98885 47.08176 -10.32589 36.05149 47.86793 -10.57133 33.61156 42.50212 -10.56488 34.71346 46.15225 -10.55838 35.9001 48.71597 -10.34361 34.09477 42.28188 -10.32423 36.24631 48.24726 -10.34338 34.11884 42.39461 -10.32323 36.36489 48.47005 -7.508155 36.89432 41.703 -7.298179 36.99328 41.68253 -9.992835 -34.71036 42.19656 -9.992461 -34.73484 42.30965 -10.34353 -34.10352 42.32318 -10.9085 -33.24685 45.74056 -10.90771 -33.98303 47.612 -10.97732 -32.73839 45.9161 -7.468839 -37.61016 44.2342 -7.223103 -38.31345 45.71772 -7.436703 -38.22233 45.75757 -8.788495 -36.7841 44.51937 -10.32983 -35.59611 46.90637 -10.69199 -35.24989 48.26282 -10.69374 -34.77968 47.26351 -7.256866 -37.70485 44.2015 -10.32589 -36.05149 47.86793 -7.478621 -37.4287 43.69986 -8.794862 -36.59451 43.96239 -10.97738 -32.51646 45.24586 -11 -32.2316 46.09107 -9.157543 -35.75217 42.09195 -9.984114 -35.29205 44.3723 -9.14221 -36.28676 44.05924 -10.90875 -33.02886 45.08459 -9.158229 -35.72867 41.98407 -9.971539 -36.16897 46.65579 -9.965406 -36.61377 47.59094 -7.267144 -37.52446 43.66972 -10.73937 -33.93359 45.50347 -10.73702 -34.65166 47.31951 -8.812981 -36.06739 42.02449 -8.813791 -36.04423 41.91822 -10.6965 -34.06508 45.45808 -7.506473 -36.92424 41.84113 -9.107841 -37.55403 47.12775 -7.507719 -36.90207 41.73922 -10.74008 -33.72092 44.86678 -7.296412 -37.02301 41.82 -8.754254 -37.84394 46.98493 -7.297721 -37.00098 41.71858 -10.69733 -33.85342 44.82508 -10.33603 -34.90376 45.16853 -9.119109 -37.12767 46.23642 -10.97755 -31.90024 42.91624 -8.767567 -37.42361 46.10696 -10.97701 -33.98161 48.88761 -11 -33.49735 49.12617 -10.33792 -34.69862 44.55907 -9.981181 -35.49252 44.96527 -10.9072 -34.46763 48.64819 -10.97713 -33.48803 47.82852 -7.416274 -38.62477 46.60028 -10.73552 -35.12419 48.32475 -7.201644 -38.71356 46.55654 -10.69972 -33.26543 42.6241 -9.136821 -36.47904 44.62469 -10.34329 -34.12857 42.43939 -10.98 11.74701 51.97767 -10.98 11.75588 51.98191 -10.984 11.74701 51.97767 -10.988 11.74701 51.97767 -11 11.75588 51.98191 -10.992 11.74701 51.97767 -11 11.74701 51.97767 -10.996 11.74701 51.97767 -10.98 11.7388 51.97083 -10.984 11.7388 51.97083 -10.988 11.7388 51.97083 -10.992 11.7388 51.97083 -11 11.7388 51.97083 -10.996 11.7388 51.97083 -10.98 11.73123 51.96098 -10.984 11.73123 51.96098 -10.98 11.68114 51.47136 -10.988 11.73123 51.96098 -10.992 11.73123 51.96098 -11 11.73123 51.96098 -10.996 11.73123 51.96098 -11 11.68114 51.47136 -10.98 11.67398 49.81876 -10.984 11.68114 51.47136 -11 11.67398 49.81876 -10.988 11.68114 51.47136 -10.992 11.68114 51.47136 -10.996 11.68114 51.47136 -11 11.75588 52.0228 -10.98 11.75588 52.0228 -10.98 11.25772 52.0433 -11 11.25772 52.0433 -10.98 10.61622 52.05704 -11 10.61622 52.05704 -10.98 9.592636 51.92732 -11 9.592636 51.92732 -11 10.07119 52.02798 -10.98 10.07119 52.02798 -10.98 8.589499 50.48743 -11 8.589499 50.48743 -11 8.634429 50.89977 -10.98 8.634429 50.89977 -10.98 8.755567 51.23382 -11 8.755567 51.23382 -10.98 8.932435 51.49659 -11 8.932435 51.49659 -10.98 9.144554 51.69509 -11 9.144554 51.69509 -10.98 9.371447 51.83633 -11 9.371447 51.83633 -10.98 9.162745 49.26603 -11 9.162745 49.26603 -11 8.95391 49.46032 -10.98 8.95391 49.46032 -10.98 8.757596 49.7553 -11 8.757596 49.7553 -10.98 8.636507 50.08538 -11 8.636507 50.08538 -10.98 9.558548 49.02709 -11 9.558548 49.02709 -11 9.365799 49.12354 -10.98 9.365799 49.12354 -11 9.558548 49.01352 -10.98 9.558548 49.01352 -10.98 8.32341 47.2939 -11 8.32341 47.2939 -10.98 7.879891 46.75474 -11 7.879891 46.75474 -10.98 8.065786 46.95516 -11 8.065786 46.95516 -11 7.879891 46.71379 -10.98 7.879891 46.71379 -10.98 8.903471 46.71379 -11 8.903471 46.71379 -10.98 9.121789 46.74116 -11 9.121789 46.74116 -11 9.01009 46.71978 -10.98 9.01009 46.71978 -10.98 10.52074 48.8224 -11 10.52074 48.8224 -10.98 10.70499 48.8224 -11 10.70499 48.8224 -11 10.70499 48.54939 -10.98 10.70499 48.54939 -10.98 10.62308 46.75474 -11 10.62308 46.75474 -11 10.63213 46.76121 -10.98 10.63213 46.76121 -10.98 10.64048 46.77064 -11 10.64048 46.77064 -10.98 10.64818 46.78344 -11 10.64818 46.78344 -10.98 10.69594 47.22339 -11 10.69594 47.22339 -11 10.62308 46.71379 -10.98 10.62308 46.71379 -11 11.75588 46.71379 -10.98 11.75588 46.71379 -11 11.75588 46.75474 -10.98 11.75588 46.75474 -10.98 11.67398 49.06805 -11 11.67398 49.06805 -10.98 11.71661 46.81782 -11 11.71661 46.81782 -10.98 11.73049 46.7813 -11 11.73049 46.7813 -10.98 11.74114 46.766 -11 11.74114 46.766 -10.98 11.74827 46.75948 -11 11.74827 46.75948 -10.98 10.70499 51.19033 -10.98 9.850863 49.79763 -10.98 9.988438 49.69592 -10.98 9.66056 50.07917 -10.98 9.739567 49.92834 -10.98 10.14107 49.62407 -10.98 9.615786 50.23645 -10.98 10.31801 49.57655 -10.98 9.599505 50.41917 -10.98 9.599505 50.42604 -10.98 10.5071 49.55938 -10.98 10.70499 49.56625 -10.98 9.625629 50.65427 -10.98 9.683499 50.81256 -10.98 9.764585 50.93678 -10.98 9.870558 51.03853 -10.98 9.999901 51.11686 -10.98 10.1511 51.17079 -10.98 10.28559 51.1956 -10.98 10.43212 51.20398 -11 9.625629 50.65427 -11 9.599505 50.42604 -11 9.683499 50.81256 -11 9.764585 50.93678 -11 9.870558 51.03853 -11 9.999901 51.11686 -11 10.1511 51.17079 -11 10.28559 51.1956 -11 10.43212 51.20398 -11 9.599505 50.41917 -11 9.850863 49.79763 -11 9.988438 49.69592 -11 9.739567 49.92834 -11 9.66056 50.07917 -11 9.615786 50.23645 -11 10.5071 49.55938 -11 10.31801 49.57655 -11 10.14107 49.62407 -11 10.70499 49.56625 -11 10.70499 51.19033 -10.98 5.075062 46.62518 -11 5.075062 46.62518 -11 4.357447 46.71052 -10.98 4.357447 46.71052 -10.98 3.719255 46.95316 -11 3.719255 46.95316 -10.98 3.177428 47.33309 -11 3.177428 47.33309 -10.98 2.748906 47.83027 -11 2.748906 47.83027 -10.98 2.450633 48.42465 -11 2.450633 48.42465 -10.98 2.326728 48.89753 -11 2.326728 48.89753 -10.98 2.284055 49.40246 -11 2.284055 49.40246 -10.98 7.845433 49.35464 -11 7.845433 49.35464 -10.98 7.760074 48.66881 -11 7.760074 48.66881 -10.98 7.517261 48.04916 -11 7.517261 48.04916 -10.98 7.136884 47.51607 -11 7.136884 47.51607 -10.98 6.638835 47.0899 -11 6.638835 47.0899 -10.98 6.043005 46.79102 -11 6.043005 46.79102 -10.98 5.574908 46.66783 -11 5.574908 46.66783 -10.98 5.00664 52.1047 -11 5.00664 52.1047 -10.98 5.741424 52.01916 -11 5.741424 52.01916 -10.98 6.397092 51.77509 -11 6.397092 51.77509 -10.98 6.954023 51.39129 -11 6.954023 51.39129 -10.98 7.354623 50.94196 -11 7.354623 50.94196 -10.98 7.62137 50.46516 -11 7.62137 50.46516 -10.98 7.787712 49.93373 -11 7.787712 49.93373 -10.98 2.284055 49.40933 -11 2.284055 49.40933 -11 2.369705 50.11698 -10.98 2.369705 50.11698 -10.98 2.583426 50.68717 -11 2.583426 50.68717 -10.98 2.8751 51.13455 -11 2.8751 51.13455 -10.98 3.250872 51.50923 -11 3.250872 51.50923 -10.98 3.701101 51.8012 -11 3.701101 51.8012 -10.98 4.216145 52.00046 -11 4.216145 52.00046 -10.98 4.600068 52.07811 -11 4.600068 52.07811 -10.98 3.770435 48.14227 -10.98 3.586704 48.41142 -10.98 6.19718 50.75586 -10.98 5.86744 50.98614 -10.98 3.452574 48.71792 -10.98 6.122263 47.92765 -10.98 3.37513 49.03533 -10.98 6.378492 48.18333 -10.98 6.577188 48.49113 -10.98 5.81494 47.73276 -10.98 5.462965 47.60731 -10.98 5.481296 51.13231 -10.98 6.722649 48.88371 -10.98 3.348578 49.37514 -10.98 5.260177 47.57191 -10.98 5.047583 47.55983 -10.98 6.780896 49.36838 -10.98 5.047583 51.18346 -10.98 6.747848 49.74219 -10.98 4.616044 47.61177 -10.98 3.348578 49.382 -10.98 3.406678 49.86374 -10.98 6.652113 50.08666 -10.98 4.270841 47.74098 -10.98 4.698995 51.14815 -10.98 3.999802 47.9167 -10.98 4.378733 51.04664 -10.98 4.066918 50.86757 -10.98 6.461683 50.45239 -10.98 3.572254 50.29486 -10.98 3.802349 50.62598 -11 3.348578 49.382 -11 3.406678 49.86374 -11 3.572254 50.29486 -11 3.802349 50.62598 -11 4.066918 50.86757 -11 4.378733 51.04664 -11 4.698995 51.14815 -11 5.047583 51.18346 -11 3.348578 49.37514 -11 4.616044 47.61177 -11 5.047583 47.55983 -11 4.270841 47.74098 -11 3.999802 47.9167 -11 3.770435 48.14227 -11 3.586704 48.41142 -11 3.452574 48.71792 -11 3.37513 49.03533 -11 6.722649 48.88371 -11 6.780896 49.36838 -11 6.577188 48.49113 -11 6.378492 48.18333 -11 6.122263 47.92765 -11 5.81494 47.73276 -11 5.462965 47.60731 -11 5.260177 47.57191 -11 5.481296 51.13231 -11 5.86744 50.98614 -11 6.19718 50.75586 -11 6.461683 50.45239 -11 6.652113 50.08666 -11 6.747848 49.74219 -10.98 -0.9784854 47.0072 -11 -0.9784854 47.0072 -11 -1.24717 47.21115 -10.98 -1.24717 47.21115 -10.98 -1.464363 47.47879 -11 -1.464363 47.47879 -10.98 -1.601253 47.76686 -11 -1.601253 47.76686 -10.98 -1.655545 47.98326 -11 -1.655545 47.98326 -10.98 -1.67452 48.21503 -11 -1.67452 48.21503 -10.98 0.5706236 46.70016 -11 0.5706236 46.70016 -10.98 -0.283201 46.76081 -11 -0.283201 46.76081 -10.98 -0.6680309 46.86031 -11 -0.6680309 46.86031 -10.98 1.143691 46.71373 -11 1.143691 46.71373 -10.98 1.580602 46.73423 -11 1.580602 46.73423 -11 1.580602 46.7753 -10.98 1.580602 46.7753 -10.98 1.491845 49.0682 -11 1.491845 49.0682 -11 1.52792 46.87476 -10.98 1.52792 46.87476 -10.98 1.545538 46.81208 -11 1.545538 46.81208 -10.98 1.556974 46.79231 -11 1.556974 46.79231 -10.98 1.565959 46.78306 -11 1.565959 46.78306 -10.98 1.57306 46.77839 -11 1.57306 46.77839 -10.98 1.491845 49.81876 -11 1.491845 49.81876 -10.98 1.573732 51.97515 -11 1.573732 51.97515 -11 1.561022 51.96418 -10.98 1.561022 51.96418 -10.98 1.5497 51.94829 -11 1.5497 51.94829 -10.98 1.539686 51.92611 -11 1.539686 51.92611 -10.98 1.497825 51.40291 -11 1.497825 51.40291 -11 1.573732 52.01609 -10.98 1.573732 52.01609 -10.98 1.116487 52.03654 -11 1.116487 52.03654 -10.98 0.3932489 52.05017 -11 0.3932489 52.05017 -10.98 -0.5212408 51.92732 -11 -0.5212408 51.92732 -11 -0.0870264 52.01946 -10.98 -0.0870264 52.01946 -10.98 -1.456202 50.63766 -11 -1.456202 50.63766 -10.98 -1.410646 51.02176 -11 -1.410646 51.02176 -10.98 -1.304471 51.29966 -11 -1.304471 51.29966 -10.98 -1.170825 51.50017 -11 -1.170825 51.50017 -10.98 -1.014047 51.65839 -11 -1.014047 51.65839 -10.98 -0.8466284 51.77884 -11 -0.8466284 51.77884 -10.98 -0.6761113 51.86827 -11 -0.6761113 51.86827 -10.98 -0.6168664 49.50481 -11 -0.6168664 49.50481 -10.98 -0.8519737 49.59632 -11 -0.8519737 49.59632 -10.98 -1.055828 49.73635 -11 -1.055828 49.73635 -10.98 -1.223303 49.91769 -11 -1.223303 49.91769 -10.98 -1.349275 50.13315 -11 -1.349275 50.13315 -10.98 -1.428616 50.37554 -11 -1.428616 50.37554 -11 -0.6168664 49.49122 -10.98 -0.6168664 49.49122 -10.98 -1.67452 48.2219 -11 -1.67452 48.2219 -10.98 -1.635027 48.55053 -11 -1.635027 48.55053 -10.98 -1.524639 48.83763 -11 -1.524639 48.83763 -10.98 -1.355493 49.07923 -11 -1.355493 49.07923 -10.98 -1.139724 49.27135 -11 -1.139724 49.27135 -10.98 -0.8894699 49.41 -11 -0.8894699 49.41 -10.98 -0.005758052 51.17475 -10.98 -0.4819976 48.75852 -10.98 -0.5639343 48.63572 -10.98 -0.2348587 51.05934 -10.98 -0.6178122 48.49091 -10.98 -0.3907797 50.86745 -10.98 -0.322921 50.97277 -10.98 -0.2833585 50.08837 -10.98 -0.3705445 50.20279 -10.98 0.5364125 51.1972 -10.98 0.5364125 49.86659 -10.98 0.5364125 49.04083 -10.98 -0.5701221 48.01017 -10.98 -0.4283923 50.33188 -10.98 0.528168 47.58627 -10.98 0.5311097 47.58916 -10.98 -0.6190198 48.15105 -10.98 0.5329259 47.59198 -10.98 0.3521681 49.85972 -10.98 0.5230192 47.58317 -10.98 0.2906161 49.05446 -10.98 0.5346273 47.59655 -10.98 -0.6324907 48.23109 -10.98 0.5160783 47.58044 -10.98 0.5364125 47.62826 -10.98 0.1764595 49.87163 -10.98 0.2634122 47.56681 -10.98 -0.1321429 48.99302 -10.98 0.04460308 47.587 -10.98 -0.6372005 48.3243 -10.98 -0.6372005 48.31743 -10.98 -0.09110529 47.62014 -10.98 -0.214304 47.66904 -10.98 -0.009450927 49.91425 -10.98 -0.3696727 47.76294 -10.98 -0.2596712 48.93736 -10.98 -0.378433 48.85913 -10.98 -0.451635 50.43179 -10.98 -0.4892024 47.88116 -10.98 -0.1521996 49.98229 -10.98 0.2634122 51.21085 -10.98 -0.4598259 50.54889 -10.98 -0.4598259 50.54213 -10.98 -0.4401607 50.72887 -10.98 0.1231973 51.20177 -10.98 -0.1285014 51.12679 -11 -0.6178122 48.49091 -11 -0.6372005 48.3243 -11 -0.5639343 48.63572 -11 -0.4819976 48.75852 -11 -0.378433 48.85913 -11 -0.2596712 48.93736 -11 -0.1321429 48.99302 -11 -0.6372005 48.31743 -11 -0.3696727 47.76294 -11 -0.214304 47.66904 -11 -0.4892024 47.88116 -11 -0.5701221 48.01017 -11 -0.6190198 48.15105 -11 -0.6324907 48.23109 -11 0.2634122 47.56681 -11 0.04460308 47.587 -11 -0.09110529 47.62014 -11 0.5160783 47.58044 -11 0.5346273 47.59655 -11 0.5364125 47.62826 -11 0.5329259 47.59198 -11 0.5311097 47.58916 -11 0.528168 47.58627 -11 0.5230192 47.58317 -11 0.5364125 49.04083 -11 0.2906161 49.05446 -11 -0.4401607 50.72887 -11 -0.4598259 50.54889 -11 -0.3907797 50.86745 -11 -0.322921 50.97277 -11 -0.2348587 51.05934 -11 -0.1285014 51.12679 -11 -0.005758052 51.17475 -11 0.1231973 51.20177 -11 0.2634122 51.21085 -11 -0.4598259 50.54213 -11 -0.1521996 49.98229 -11 -0.009450927 49.91425 -11 -0.2833585 50.08837 -11 -0.3705445 50.20279 -11 -0.4283923 50.33188 -11 -0.451635 50.43179 -11 0.1764595 49.87163 -11 0.3521681 49.85972 -11 0.5364125 49.86659 -11 0.5364125 51.1972 -10.98 -5.004933 46.62518 -11 -5.004933 46.62518 -11 -5.722457 46.71052 -10.98 -5.722457 46.71052 -10.98 -6.360619 46.95316 -11 -6.360619 46.95316 -10.98 -6.902458 47.33309 -11 -6.902458 47.33309 -10.98 -7.331015 47.83027 -11 -7.331015 47.83027 -10.98 -7.62933 48.42465 -11 -7.62933 48.42465 -10.98 -7.753258 48.89753 -11 -7.753258 48.89753 -10.98 -7.79594 49.40246 -11 -7.79594 49.40246 -10.98 -2.234535 49.35464 -11 -2.234535 49.35464 -10.98 -2.319894 48.66878 -11 -2.319894 48.66878 -10.98 -2.562714 48.04911 -11 -2.562714 48.04911 -10.98 -2.943108 47.51601 -11 -2.943108 47.51601 -10.98 -3.441191 47.08984 -11 -3.441191 47.08984 -10.98 -4.037075 46.79097 -11 -4.037075 46.79097 -10.98 -4.505128 46.66782 -11 -4.505128 46.66782 -10.98 -5.073355 52.1047 -11 -5.073355 52.1047 -11 -4.338523 52.01916 -10.98 -4.338523 52.01916 -10.98 -3.682835 51.77509 -11 -3.682835 51.77509 -10.98 -3.125905 51.39129 -11 -3.125905 51.39129 -10.98 -2.725316 50.94196 -11 -2.725316 50.94196 -10.98 -2.458582 50.46516 -11 -2.458582 50.46516 -10.98 -2.292251 49.93373 -11 -2.292251 49.93373 -10.98 -7.79594 49.40933 -11 -7.79594 49.40933 -11 -7.710291 50.11694 -10.98 -7.710291 50.11694 -10.98 -7.496577 50.68711 -11 -7.496577 50.68711 -10.98 -7.204918 51.13447 -11 -7.204918 51.13447 -10.98 -6.829173 51.50914 -11 -6.829173 51.50914 -10.98 -6.378987 51.80112 -11 -6.378987 51.80112 -10.98 -5.864006 52.0004 -11 -5.864006 52.0004 -10.98 -5.480006 52.07809 -11 -5.480006 52.07809 -10.98 -6.30956 48.14227 -10.98 -6.493291 48.41142 -10.98 -3.882797 50.75586 -10.98 -4.212546 50.98614 -10.98 -6.62742 48.71792 -10.98 -3.957716 47.92765 -10.98 -6.704864 49.03533 -10.98 -3.701479 48.18333 -10.98 -3.502776 48.49113 -10.98 -4.265047 47.73276 -10.98 -4.617028 47.60731 -10.98 -4.598696 51.13231 -10.98 -3.357308 48.88371 -10.98 -6.731417 49.37514 -10.98 -4.819817 47.57191 -10.98 -5.032411 47.55983 -10.98 -3.299058 49.36838 -10.98 -5.032411 51.18346 -10.98 -3.332107 49.74219 -10.98 -5.46395 47.61177 -10.98 -6.731417 49.382 -10.98 -6.673307 49.86374 -10.98 -3.427847 50.08666 -10.98 -5.809154 47.74098 -10.98 -5.38096 51.14815 -10.98 -6.080193 47.9167 -10.98 -5.701204 51.04664 -10.98 -6.013017 50.86757 -10.98 -3.618285 50.45239 -10.98 -6.50771 50.29486 -10.98 -6.277596 50.62598 -11 -6.673307 49.86374 -11 -6.731417 49.382 -11 -6.50771 50.29486 -11 -6.277596 50.62598 -11 -6.013017 50.86757 -11 -5.701204 51.04664 -11 -5.38096 51.14815 -11 -5.032411 51.18346 -11 -6.731417 49.37514 -11 -5.46395 47.61177 -11 -5.032411 47.55983 -11 -5.809154 47.74098 -11 -6.080193 47.9167 -11 -6.30956 48.14227 -11 -6.493291 48.41142 -11 -6.62742 48.71792 -11 -6.704864 49.03533 -11 -3.357308 48.88371 -11 -3.299058 49.36838 -11 -3.502776 48.49113 -11 -3.701479 48.18333 -11 -3.957716 47.92765 -11 -4.265047 47.73276 -11 -4.617028 47.60731 -11 -4.819817 47.57191 -11 -4.598696 51.13231 -11 -4.212546 50.98614 -11 -3.882797 50.75586 -11 -3.618285 50.45239 -11 -3.427847 50.08666 -11 -3.332107 49.74219 -10.98 -8.096969 51.07425 -11 -8.096969 51.07425 -11 -8.136571 51.10751 -10.98 -8.136571 51.10751 -10.98 -8.187616 51.13396 -11 -8.187616 51.13396 -10.98 -8.348072 51.17226 -11 -8.348072 51.17226 -10.98 -8.560671 51.18346 -11 -8.560671 51.18346 -11 -8.042286 51.07425 -10.98 -8.042286 51.07425 -11 -8.042286 52.03643 -10.98 -8.042286 52.03643 -11 -12.04771 52.03643 -10.98 -12.04771 52.03643 -11 -12.04771 51.07425 -10.98 -12.04771 51.07425 -11 -12.00017 51.07425 -10.98 -12.00017 51.07425 -10.98 -11.53606 51.18346 -11 -11.53606 51.18346 -11 -11.79018 51.16488 -10.98 -11.79018 51.16488 -10.98 -11.88885 51.13897 -11 -11.88885 51.13897 -10.98 -11.95009 51.11078 -11 -11.95009 51.11078 -11 -10.55342 51.18346 -10.98 -10.55342 51.18346 -11 -10.55342 49.06805 -10.98 -10.55342 49.06805 -10.98 -10.65592 46.75478 -11 -10.65592 46.75478 -11 -10.64589 46.75657 -10.98 -10.64589 46.75657 -10.98 -10.63744 46.76023 -11 -10.63744 46.76023 -10.98 -10.63029 46.76539 -11 -10.63029 46.76539 -10.98 -10.62356 46.77249 -11 -10.62356 46.77249 -10.98 -10.61723 46.7817 -11 -10.61723 46.7817 -10.98 -10.6094 46.79755 -11 -10.6094 46.79755 -10.98 -10.56042 47.37252 -11 -10.56042 47.37252 -11 -10.65592 46.71384 -10.98 -10.65592 46.71384 -11 -9.441224 46.71384 -10.98 -9.441224 46.71384 -11 -9.441224 46.75478 -10.98 -9.441224 46.75478 -10.98 -9.536713 49.06805 -11 -9.536713 49.06805 -11 -9.497902 46.86727 -10.98 -9.497902 46.86727 -10.98 -9.476524 46.79576 -11 -9.476524 46.79576 -10.98 -9.461975 46.77236 -11 -9.461975 46.77236 -10.98 -9.452023 46.7623 -11 -9.452023 46.7623 -11 -9.536713 51.18346 -10.98 -9.536713 51.18346 -10.98 -13.84962 46.75478 -11 -13.84962 46.75478 -11 -13.82971 46.77663 -10.98 -13.82971 46.77663 -10.98 -13.81278 46.80799 -11 -13.81278 46.80799 -10.98 -13.76147 47.35807 -11 -13.76147 47.35807 -10.98 -13.75414 49.06805 -11 -13.75414 49.06805 -11 -13.84962 46.71384 -10.98 -13.84962 46.71384 -11 -12.63493 46.71384 -10.98 -12.63493 46.71384 -11 -12.63493 46.7615 -10.98 -12.63493 46.7615 -10.98 -12.73056 49.06118 -11 -12.73056 49.06118 -11 -12.68078 46.83682 -10.98 -12.68078 46.83682 -10.98 -12.66259 46.79361 -11 -12.66259 46.79361 -10.98 -12.64954 46.77535 -11 -12.64954 46.77535 -11 -12.73056 49.81861 -10.98 -12.73056 49.81861 -10.98 -12.6418 51.98878 -11 -12.6418 51.98878 -11 -12.65701 51.97397 -10.98 -12.65701 51.97397 -10.98 -12.67038 51.95319 -11 -12.67038 51.95319 -10.98 -12.72303 51.45101 -11 -12.72303 51.45101 -11 -12.6418 52.03643 -10.98 -12.6418 52.03643 -11 -13.84275 52.03643 -10.98 -13.84275 52.03643 -11 -13.84275 51.98878 -10.98 -13.84275 51.98878 -10.98 -13.75414 49.81861 -11 -13.75414 49.81861 -11 -13.80027 51.91764 -10.98 -13.80027 51.91764 -10.98 -13.81713 51.9588 -11 -13.81713 51.9588 -10.98 -13.82921 51.976 -11 -13.82921 51.976 -10.98 -19.65009 47.92848 -11 -19.65009 47.92848 -10.98 -19.86757 48.28766 -11 -19.86757 48.28766 -10.98 -20.04246 48.79085 -11 -20.04246 48.79085 -10.98 -20.11421 49.39559 -11 -20.11421 49.39559 -10.98 -18.80403 47.12334 -11 -18.80403 47.12334 -10.98 -19.15231 47.36241 -11 -19.15231 47.36241 -10.98 -19.43838 47.6439 -11 -19.43838 47.6439 -11 -18.80403 47.10273 -10.98 -18.80403 47.10273 -10.98 -19.47959 46.80256 -11 -19.47959 46.80256 -10.98 -20.0664 46.59094 -11 -20.0664 46.59094 -10.98 -20.30532 46.53641 -11 -20.30532 46.53641 -10.98 -20.33953 46.5091 -11 -20.33953 46.5091 -10.98 -19.71852 45.84714 -11 -19.71852 45.84714 -10.98 -19.64336 45.84714 -11 -19.64336 45.84714 -11 -19.67191 45.83805 -10.98 -19.67191 45.83805 -10.98 -19.68346 45.83691 -11 -19.68346 45.83691 -10.98 -19.69683 45.83859 -11 -19.69683 45.83859 -10.98 -19.70711 45.84196 -11 -19.70711 45.84196 -10.98 -18.76308 46.24982 -11 -18.76308 46.24982 -10.98 -17.96469 46.69345 -11 -17.96469 46.69345 -10.98 -17.67136 46.63865 -11 -17.67136 46.63865 -10.98 -17.32348 46.61831 -11 -17.32348 46.61831 -10.98 -14.53906 49.34106 -11 -14.53906 49.34106 -11 -14.60855 48.72411 -10.98 -14.60855 48.72411 -10.98 -14.80763 48.15748 -11 -14.80763 48.15748 -10.98 -15.12227 47.6566 -11 -15.12227 47.6566 -10.98 -15.53841 47.23689 -11 -15.53841 47.23689 -10.98 -16.04199 46.91378 -11 -16.04199 46.91378 -10.98 -16.61898 46.7027 -11 -16.61898 46.7027 -10.98 -16.96339 46.63984 -11 -16.96339 46.63984 -10.98 -17.40509 52.1047 -11 -17.40509 52.1047 -11 -16.66594 52.01916 -10.98 -16.66594 52.01916 -10.98 -16.00571 51.77509 -11 -16.00571 51.77509 -10.98 -15.44418 51.3913 -11 -15.44418 51.3913 -10.98 -15.03952 50.94199 -11 -15.03952 50.94199 -10.98 -14.76929 50.4652 -11 -14.76929 50.4652 -10.98 -14.59897 49.93021 -11 -14.59897 49.93021 -10.98 -14.55427 49.64114 -11 -14.55427 49.64114 -10.98 -20.11421 49.40246 -11 -20.11421 49.40246 -11 -20.02867 50.11091 -10.98 -20.02867 50.11091 -10.98 -19.8156 50.68151 -11 -19.8156 50.68151 -10.98 -19.52539 51.1292 -11 -19.52539 51.1292 -10.98 -19.15227 51.50433 -11 -19.15227 51.50433 -10.98 -18.70624 51.79706 -11 -18.70624 51.79706 -10.98 -18.1973 51.99758 -11 -18.1973 51.99758 -10.98 -17.81227 52.07737 -11 -17.81227 52.07737 -10.98 -18.1224 47.73021 -10.98 -17.77378 47.59917 -10.98 -15.73334 50.08488 -10.98 -17.33694 51.19033 -10.98 -17.69005 51.15473 -10.98 -19.04969 49.382 -10.98 -19.04969 49.37514 -10.98 -19.02311 49.03484 -10.98 -18.39559 47.90814 -10.98 -18.99153 49.86425 -10.98 -15.92479 50.45189 -10.98 -16.06129 48.11727 -10.98 -18.62638 48.13613 -10.98 -16.33011 47.8708 -10.98 -18.01371 51.05247 -10.98 -18.82553 50.29664 -10.98 -15.82857 48.45319 -10.98 -18.32816 50.8722 -10.98 -16.64848 47.68729 -10.98 -18.59441 50.62924 -10.98 -16.19013 50.75755 -10.98 -15.66186 48.88746 -10.98 -18.81097 48.40763 -10.98 -16.97719 47.58286 -10.98 -17.33694 47.54642 -10.98 -18.94552 48.71613 -10.98 -15.60359 49.36838 -10.98 -16.52011 50.99025 -10.98 -15.63692 49.74054 -10.98 -16.90546 51.13838 -11 -18.99153 49.86425 -11 -19.04969 49.382 -11 -18.82553 50.29664 -11 -18.59441 50.62924 -11 -18.32816 50.8722 -11 -18.01371 51.05247 -11 -17.69005 51.15473 -11 -17.33694 51.19033 -11 -19.04969 49.37514 -11 -17.33694 47.54642 -11 -17.77378 47.59917 -11 -18.1224 47.73021 -11 -18.39559 47.90814 -11 -18.62638 48.13613 -11 -18.81097 48.40763 -11 -18.94552 48.71613 -11 -19.02311 49.03484 -11 -15.66186 48.88746 -11 -15.60359 49.36838 -11 -15.82857 48.45319 -11 -16.06129 48.11727 -11 -16.33011 47.8708 -11 -16.64848 47.68729 -11 -16.97719 47.58286 -11 -16.90546 51.13838 -11 -16.52011 50.99025 -11 -16.19013 50.75755 -11 -15.92479 50.45189 -11 -15.73334 50.08488 -11 -15.63692 49.74054 -10.98 18.06358 53.43935 -11 18.06358 53.43935 -11 18.20382 53.44885 -10.98 18.20382 53.44885 -10.98 18.31393 53.43137 -11 18.31393 53.43137 -10.98 18.39999 53.39455 -11 18.39999 53.39455 -10.98 18.46687 53.34434 -11 18.46687 53.34434 -10.98 18.51851 53.28531 -11 18.51851 53.28531 -10.98 18.56204 53.21318 -11 18.56204 53.21318 -10.98 18.59593 53.13236 -11 18.59593 53.13236 -10.98 18.62248 53.03967 -11 18.62248 53.03967 -10.98 15.06883 52.89102 -11 15.06883 52.89102 -10.98 14.4717 52.46633 -11 14.4717 52.46633 -11 14.50842 52.56242 -10.98 14.50842 52.56242 -10.98 14.56178 52.64229 -11 14.56178 52.64229 -10.98 14.62774 52.70763 -11 14.62774 52.70763 -10.98 14.70226 52.76014 -11 14.70226 52.76014 -10.98 14.905 52.84808 -11 14.905 52.84808 -10.98 14.15226 51.17456 -11 14.15226 51.17456 -10.98 14.43773 50.63433 -11 14.43773 50.63433 -11 14.31176 50.6717 -10.98 14.31176 50.6717 -10.98 14.23271 50.71741 -11 14.23271 50.71741 -10.98 14.18255 50.76606 -11 14.18255 50.76606 -10.98 14.14962 50.81806 -11 14.14962 50.81806 -10.98 14.12827 50.87783 -11 14.12827 50.87783 -10.98 14.11849 50.94537 -11 14.11849 50.94537 -10.98 14.12028 51.02069 -11 14.12028 51.02069 -10.98 14.13166 51.09453 -11 14.13166 51.09453 -10.98 18.36472 49.93662 -11 18.36472 49.93662 -10.98 19.08726 50.5769 -11 19.08726 50.5769 -11 19.10208 50.41675 -10.98 19.10208 50.41675 -10.98 19.08679 50.29726 -11 19.08679 50.29726 -10.98 19.05353 50.20794 -11 19.05353 50.20794 -10.98 19.00505 50.13432 -11 19.00505 50.13432 -10.98 18.94447 50.07494 -11 18.94447 50.07494 -10.98 18.87492 50.0283 -11 18.87492 50.0283 -10.98 18.77367 49.98338 -11 18.77367 49.98338 -10.98 18.50863 49.93465 -11 18.50863 49.93465 -10.98 13.77395 49.80643 -11 13.77395 49.80643 -10.98 13.81279 49.91159 -11 13.81279 49.91159 -10.98 13.84941 49.97016 -11 13.84941 49.97016 -10.98 13.90699 50.03077 -11 13.90699 50.03077 -10.98 13.97979 50.07804 -11 13.97979 50.07804 -10.98 14.06383 50.10878 -11 14.06383 50.10878 -10.98 14.16763 50.12433 -11 14.16763 50.12433 -10.98 14.25508 50.12399 -11 14.25508 50.12399 -10.98 14.35449 50.1125 -11 14.35449 50.1125 -10.98 13.1897 47.40162 -11 13.1897 47.40162 -10.98 13.89491 46.64154 -11 13.89491 46.64154 -11 13.65315 46.67369 -10.98 13.65315 46.67369 -10.98 13.4858 46.73191 -11 13.4858 46.73191 -10.98 13.36509 46.80333 -11 13.36509 46.80333 -10.98 13.28598 46.87574 -11 13.28598 46.87574 -10.98 13.22357 46.96494 -11 13.22357 46.96494 -10.98 13.18399 47.0651 -11 13.18399 47.0651 -10.98 13.16665 47.17426 -11 13.16665 47.17426 -10.98 13.1691 47.2813 -11 13.1691 47.2813 -10.98 17.85979 47.24157 -11 17.85979 47.24157 -10.98 18.20906 47.76791 -11 18.20906 47.76791 -11 18.23222 47.62898 -10.98 18.23222 47.62898 -10.98 18.22712 47.53146 -11 18.22712 47.53146 -10.98 18.20656 47.46047 -11 18.20656 47.46047 -10.98 18.17537 47.40455 -11 18.17537 47.40455 -10.98 18.13217 47.35618 -11 18.13217 47.35618 -10.98 18.07696 47.31538 -11 18.07696 47.31538 -10.98 18.00974 47.28214 -11 18.00974 47.28214 -10.98 17.93956 47.25884 -11 17.93956 47.25884 -10.98 17.96681 49.07728 -11 17.96681 49.07728 -10.98 17.38509 49.57474 -11 17.38509 49.57474 -11 17.61079 49.51495 -10.98 17.61079 49.51495 -10.98 17.72224 49.46017 -11 17.72224 49.46017 -10.98 17.79945 49.40006 -11 17.79945 49.40006 -10.98 17.87378 49.3102 -11 17.87378 49.3102 -10.98 17.92702 49.20715 -11 17.92702 49.20715 -10.98 19.29222 46.92658 -11 19.29222 46.92658 -11 19.43247 46.93656 -10.98 19.43247 46.93656 -10.98 19.54267 46.91945 -11 19.54267 46.91945 -10.98 19.62885 46.88292 -11 19.62885 46.88292 -10.98 19.6959 46.83292 -11 19.6959 46.83292 -10.98 19.74772 46.77405 -11 19.74772 46.77405 -10.98 19.79146 46.70204 -11 19.79146 46.70204 -10.98 19.8256 46.62131 -11 19.8256 46.62131 -10.98 19.85242 46.52868 -11 19.85242 46.52868 -10.98 16.46385 46.48913 -11 16.46385 46.48913 -10.98 15.63412 45.94819 -11 15.63412 45.94819 -11 15.67964 46.07643 -10.98 15.67964 46.07643 -10.98 15.74978 46.18112 -11 15.74978 46.18112 -10.98 15.84006 46.26525 -11 15.84006 46.26525 -10.98 15.94598 46.33187 -11 15.94598 46.33187 -10.98 16.20123 46.42867 -11 16.20123 46.42867 -10.98 15.33503 44.6508 -11 15.33503 44.6508 -10.98 15.62221 44.11142 -11 15.62221 44.11142 -11 15.50385 44.14666 -10.98 15.50385 44.14666 -10.98 15.42865 44.19123 -11 15.42865 44.19123 -10.98 15.38012 44.23933 -11 15.38012 44.23933 -10.98 15.34742 44.29114 -11 15.34742 44.29114 -10.98 15.32513 44.35101 -11 15.32513 44.35101 -10.98 15.31325 44.41896 -11 15.31325 44.41896 -10.98 15.31177 44.49497 -11 15.31177 44.49497 -10.98 15.31925 44.56966 -11 15.31925 44.56966 -10.98 19.60329 43.42499 -11 19.60329 43.42499 -10.98 20.32407 44.06704 -11 20.32407 44.06704 -11 20.33946 43.90685 -10.98 20.33946 43.90685 -10.98 20.32483 43.78713 -11 20.32483 43.78713 -10.98 20.29222 43.69748 -11 20.29222 43.69748 -10.98 20.2444 43.62347 -11 20.2444 43.62347 -10.98 20.18448 43.56364 -11 20.18448 43.56364 -10.98 20.11554 43.51655 -11 20.11554 43.51655 -10.98 20.01494 43.47105 -11 20.01494 43.47105 -10.98 19.89833 43.43955 -11 19.89833 43.43955 -10.98 19.70487 43.42007 -11 19.70487 43.42007 -10.3 30.00109 38.79226 -10.3 30.08218 38.19647 -10.3 30.00109 38.00774 -10.3 30.10988 38.4 -10.3 30.08218 38.60353 -10.3 31.25237 40.24514 -10.3 31.19782 40.17129 -10.3 31.32447 40.30198 -10.3 31.40901 40.33778 -10.3 31.1647 40.08567 -10.3 31.09025 39.89422 -10.3 30.96735 39.72964 -10.3 30.80494 39.60388 -10.3 30.61482 39.5261 -10.3 30.41084 39.50196 -10.3 31.09025 36.90578 -10.3 31.1647 36.71433 -10.3 31.32447 36.49802 -10.3 31.40901 36.46222 -10.3 31.25237 36.55486 -10.3 31.19782 36.62871 -10.3 30.96735 37.07036 -10.3 30.80494 37.19612 -10.3 30.61482 37.2739 -10.3 30.41084 37.29804 -10.3 33.0594 39.50301 -10.3 33.13267 39.44769 -10.3 32.97412 39.53702 -10.3 32.8829 39.54734 -10.3 32.79218 39.53321 -10.3 32.58916 39.50196 -10.3 31.67553 40.30198 -10.3 31.74763 40.24514 -10.3 31.80218 40.17129 -10.3 31.59099 40.33778 -10.3 31.8353 40.08567 -10.3 32.38518 39.5261 -10.3 31.90975 39.89422 -10.3 32.19506 39.60388 -10.3 32.03265 39.72964 -10.3 33.0594 37.29699 -10.3 33.13267 37.35231 -10.3 32.97412 37.26298 -10.3 32.8829 37.25266 -10.3 32.79218 37.26679 -10.3 32.58916 37.29804 -10.3 32.38518 37.2739 -10.3 32.19506 37.19612 -10.3 32.03265 37.07036 -10.3 31.90975 36.90578 -10.3 31.8353 36.71433 -10.3 31.80218 36.62871 -10.3 31.74763 36.55486 -10.3 31.67553 36.49802 -10.3 31.59099 36.46222 -10.3 33.23493 39.19897 -10.3 33.22366 39.29009 -10.3 33.22175 39.10812 -10.3 33.18507 39.02395 -10.3 33.18507 37.77605 -10.3 33.22175 37.69188 -10.3 33.23493 37.60103 -10.3 33.22366 37.50991 -9.5 32.79218 39.53321 -9.5 32.58916 39.50196 -9.5 32.38518 39.5261 -9.5 32.19506 39.60388 -9.5 32.03265 39.72964 -9.5 31.90975 39.89422 -9.5 31.8353 40.08567 -9.5 31.19782 40.17129 -9.5 31.1647 40.08567 -9.5 31.25237 40.24514 -9.5 31.32447 40.30198 -9.5 31.40901 40.33778 -9.5 31.5 40.35 -9.5 31.59099 40.33778 -9.5 31.67553 40.30198 -9.5 31.74763 40.24514 -9.5 31.80218 40.17129 -9.5 31.09025 39.89422 -9.5 30.96735 39.72964 -9.5 30.80494 39.60388 -9.5 30.61482 39.5261 -9.5 30.41084 39.50196 -9.5 30.00109 38.79226 -9.5 30.08218 38.60353 -9.5 30.10988 38.4 -9.5 30.08218 38.19647 -9.5 30.00109 38.00774 -9.5 30.41084 37.29804 -9.5 30.61482 37.2739 -9.5 30.80494 37.19612 -9.5 30.96735 37.07036 -9.5 31.09025 36.90578 -9.5 31.1647 36.71433 -9.5 31.80218 36.62871 -9.5 31.8353 36.71433 -9.5 31.74763 36.55486 -9.5 31.67553 36.49802 -9.5 31.59099 36.46222 -9.5 31.5 36.45 -9.5 31.40901 36.46222 -9.5 31.32447 36.49802 -9.5 31.25237 36.55486 -9.5 31.19782 36.62871 -9.5 31.90975 36.90578 -9.5 32.03265 37.07036 -9.5 32.19506 37.19612 -9.5 32.38518 37.2739 -9.5 32.58916 37.29804 -9.5 32.79218 37.26679 -9.5 33.18507 37.77605 -9.5 33.22175 37.69188 -9.5 33.23493 37.60103 -9.5 33.22366 37.50991 -9.5 33.18875 37.425 -9.5 33.13267 37.35231 -9.5 33.0594 37.29699 -9.5 32.97412 37.26298 -9.5 32.8829 37.25266 -9.5 32.8829 39.54734 -9.5 32.97412 39.53702 -9.5 33.0594 39.50301 -9.5 33.13267 39.44769 -9.5 33.18875 39.375 -9.5 33.22366 39.29009 -9.5 33.23493 39.19897 -9.5 33.22175 39.10812 -9.5 33.18507 39.02395 -10.3 -32.99891 38.79226 -10.3 -32.91782 38.19647 -10.3 -32.99891 38.00774 -10.3 -32.89012 38.4 -10.3 -32.91782 38.60353 -10.3 -31.74763 40.24514 -10.3 -31.80218 40.17129 -10.3 -31.67553 40.30198 -10.3 -31.59099 40.33778 -10.3 -31.8353 40.08567 -10.3 -31.90975 39.89422 -10.3 -32.03265 39.72964 -10.3 -32.19506 39.60388 -10.3 -32.38518 39.5261 -10.3 -32.58916 39.50196 -10.3 -31.90975 36.90578 -10.3 -31.8353 36.71433 -10.3 -31.67553 36.49802 -10.3 -31.59099 36.46222 -10.3 -31.74763 36.55486 -10.3 -31.80218 36.62871 -10.3 -32.03265 37.07036 -10.3 -32.19506 37.19612 -10.3 -32.38518 37.2739 -10.3 -32.58916 37.29804 -10.3 -29.9406 39.50301 -10.3 -29.86733 39.44769 -10.3 -30.02588 39.53702 -10.3 -30.1171 39.54734 -10.3 -30.20782 39.53321 -10.3 -30.41084 39.50196 -10.3 -31.32447 40.30198 -10.3 -31.25237 40.24514 -10.3 -31.19782 40.17129 -10.3 -31.40901 40.33778 -10.3 -31.1647 40.08567 -10.3 -30.61482 39.5261 -10.3 -31.09025 39.89422 -10.3 -30.80494 39.60388 -10.3 -30.96735 39.72964 -10.3 -29.9406 37.29699 -10.3 -29.86733 37.35231 -10.3 -30.02588 37.26298 -10.3 -30.1171 37.25266 -10.3 -30.20782 37.26679 -10.3 -30.41084 37.29804 -10.3 -30.61482 37.2739 -10.3 -30.80494 37.19612 -10.3 -30.96735 37.07036 -10.3 -31.09025 36.90578 -10.3 -31.1647 36.71433 -10.3 -31.19782 36.62871 -10.3 -31.25237 36.55486 -10.3 -31.32447 36.49802 -10.3 -31.40901 36.46222 -10.3 -29.76507 39.19897 -10.3 -29.77634 39.29009 -10.3 -29.77825 39.10812 -10.3 -29.81493 39.02395 -10.3 -29.81493 37.77605 -10.3 -29.77825 37.69188 -10.3 -29.76507 37.60103 -10.3 -29.77634 37.50991 -9.5 -30.20782 39.53321 -9.5 -30.41084 39.50196 -9.5 -30.61482 39.5261 -9.5 -30.80494 39.60388 -9.5 -30.96735 39.72964 -9.5 -31.09025 39.89422 -9.5 -31.1647 40.08567 -9.5 -31.80218 40.17129 -9.5 -31.8353 40.08567 -9.5 -31.74763 40.24514 -9.5 -31.67553 40.30198 -9.5 -31.59099 40.33778 -9.5 -31.5 40.35 -9.5 -31.40901 40.33778 -9.5 -31.32447 40.30198 -9.5 -31.25237 40.24514 -9.5 -31.19782 40.17129 -9.5 -31.90975 39.89422 -9.5 -32.03265 39.72964 -9.5 -32.19506 39.60388 -9.5 -32.38518 39.5261 -9.5 -32.58916 39.50196 -9.5 -32.99891 38.79226 -9.5 -32.91782 38.60353 -9.5 -32.89012 38.4 -9.5 -32.91782 38.19647 -9.5 -32.99891 38.00774 -9.5 -32.58916 37.29804 -9.5 -32.38518 37.2739 -9.5 -32.19506 37.19612 -9.5 -32.03265 37.07036 -9.5 -31.90975 36.90578 -9.5 -31.8353 36.71433 -9.5 -31.1647 36.71433 -9.5 -31.19782 36.62871 -9.5 -31.25237 36.55486 -9.5 -31.32447 36.49802 -9.5 -31.40901 36.46222 -9.5 -31.5 36.45 -9.5 -31.59099 36.46222 -9.5 -31.67553 36.49802 -9.5 -31.74763 36.55486 -9.5 -31.80218 36.62871 -9.5 -31.09025 36.90578 -9.5 -30.96735 37.07036 -9.5 -30.80494 37.19612 -9.5 -30.61482 37.2739 -9.5 -30.41084 37.29804 -9.5 -30.20782 37.26679 -9.5 -29.81493 37.77605 -9.5 -29.77825 37.69188 -9.5 -29.76507 37.60103 -9.5 -29.77634 37.50991 -9.5 -29.81125 37.425 -9.5 -29.86733 37.35231 -9.5 -29.9406 37.29699 -9.5 -30.02588 37.26298 -9.5 -30.1171 37.25266 -9.5 -30.1171 39.54734 -9.5 -30.02588 39.53702 -9.5 -29.9406 39.50301 -9.5 -29.86733 39.44769 -9.5 -29.81125 39.375 -9.5 -29.77634 39.29009 -9.5 -29.76507 39.19897 -9.5 -29.77825 39.10812 -9.5 -29.81493 39.02395 13.34157 -23.13736 0.3125 12.06807 -23.83936 0.3125 13.34157 -23.13736 0.1125 12.06807 -23.83936 0.1125 13.68008 -22.97558 0.3125 13.68008 -22.97558 0.1125 13.97656 -22.83363 0.3125 13.97656 -22.83363 0.1125 14.28804 -22.73999 0.3125 14.28804 -22.73999 0.1125 14.64366 -22.63281 0.3125 14.64366 -22.63281 0.1125 15.34533 -22.56583 0.3125 15.34533 -22.56583 0.1125 24.8068 -22.23378 0.3125 24.8068 -22.23378 0.1125 25.14229 -22.16681 0.3125 25.14229 -22.16681 0.1125 25.47742 -21.99743 0.3125 25.47742 -21.99743 0.1125 25.74552 -21.76456 0.3125 25.74552 -21.76456 0.1125 27.01511 -20.15938 0.3125 27.01511 -20.15938 0.1125 28.18663 -18.48721 0.3125 28.18663 -18.48721 0.1125 29.28723 -16.71627 0.3125 29.28723 -16.71627 0.1125 30.22555 -14.91005 0.3125 30.22555 -14.91005 0.1125 31.09332 -13.0367 0.3125 31.09332 -13.0367 0.1125 31.83056 -11.1 0.3125 31.83056 -11.1 0.1125 32.46514 -9.159706 0.3125 32.46514 -9.159706 0.1125 32.93109 -7.152283 0.3125 32.93109 -7.152283 0.1125 33.33283 -5.113217 0.3125 33.33283 -5.113217 0.1125 33.56594 -3.074263 0.3125 33.56594 -3.074263 0.1125 33.69958 -1.035172 0.3125 33.69958 -1.035172 0.1125 33.69951 1.039192 0.3125 33.69951 1.039192 0.1125 33.57399 2.952433 0.3125 33.57399 2.952433 0.1125 33.56573 3.077886 0.3125 33.56573 3.077886 0.1125 33.53911 3.310996 0.3125 33.53911 3.310996 0.1125 33.33248 5.117282 0.3125 33.33248 5.117282 0.1125 32.93059 7.15632 0.3125 32.93059 7.15632 0.1125 32.46451 9.163605 0.3125 32.46451 9.163605 0.1125 31.82979 11.10033 0.3125 31.82979 11.10033 0.1125 31.09242 13.04058 0.3125 31.09242 13.04058 0.1125 30.22453 14.91379 0.3125 30.22453 14.91379 0.1125 29.28608 16.71645 0.3125 29.28608 16.71645 0.1125 28.18535 18.49053 0.3125 28.18535 18.49053 0.1125 27.36298 19.66208 0.3125 27.36298 19.66208 0.1125 27.01372 20.15948 0.3125 27.01372 20.15948 0.1125 25.74402 21.76457 0.3125 25.74402 21.76457 0.1125 25.4759 22.00092 0.3125 25.4759 22.00092 0.1125 25.14076 22.16636 0.3125 25.14076 22.16636 0.1125 24.80562 22.23338 0.3125 24.80562 22.23338 0.1125 15.34377 22.56854 0.3125 15.34377 22.56854 0.1125 14.64209 22.63519 0.3125 14.64209 22.63519 0.1125 13.97499 22.83661 0.3125 13.97499 22.83661 0.1125 13.33998 23.13644 0.3125 13.33998 23.13644 0.1125 12.06643 23.83843 0.3125 12.06643 23.83843 0.1125 11.78261 24.00599 0.3125 11.78261 24.00599 0.1125 11.4988 24.17319 0.3125 11.4988 24.17319 0.1125 10.96574 24.60709 0.3125 10.96574 24.60709 0.1125 10.53074 25.14224 0.3125 10.53074 25.14224 0.1125 10.16313 25.7109 0.3125 10.16313 25.7109 0.1125 9.928865 26.34589 0.3125 9.928865 26.34589 0.1125 9.761626 26.98089 0.3125 9.761626 26.98089 0.1125 9.694575 27.68362 0.3125 9.694575 27.68362 0.1125 9.694493 30.0571 0.3125 9.694493 30.0571 0.1125 9.66096 30.62542 0.3125 9.66096 30.62542 0.1125 9.493725 31.16023 0.3125 9.493725 31.16023 0.1125 9.226656 31.62835 0.3125 9.226656 31.62835 0.1125 8.892209 32.06296 0.3125 8.892209 32.06296 0.1125 8.457575 32.43089 0.3125 8.457575 32.43089 0.1125 7.95627 32.69828 0.3125 7.95627 32.69828 0.1125 7.704909 32.79878 0.3125 7.704909 32.79878 0.1125 7.454261 32.89864 0.3125 7.454261 32.89864 0.1125 6.536045 33.06577 0.3125 6.536045 33.06577 0.1125 5.615222 33.23301 0.3125 5.615222 33.23301 0.1125 4.740285 33.35814 0.3125 4.740285 33.35814 0.1125 3.743025 33.50035 0.3125 3.743025 33.50035 0.1125 1.870831 33.6675 0.3125 1.870831 33.6675 0.1125 -0.001076182 33.70095 0.3125 -0.001076182 33.70095 0.1125 -1.872839 33.66737 0.3125 -1.872839 33.66737 0.1125 -1.997875 33.65623 0.3125 -1.997875 33.65623 0.1125 -3.745339 33.50009 0.3125 -3.745339 33.50009 0.1125 -4.707764 33.3628 0.3125 -4.707764 33.3628 0.1125 -5.617941 33.23262 0.3125 -5.617941 33.23262 0.1125 -6.471778 33.07748 0.3125 -6.471778 33.07748 0.1125 -7.45678 32.89813 0.3125 -7.45678 32.89813 0.1125 -7.725897 32.79083 0.3125 -7.725897 32.79083 0.1125 -7.958493 32.69773 0.3125 -7.958493 32.69773 0.1125 -8.371375 32.47736 0.3125 -8.371375 32.47736 0.1125 -8.459391 32.43031 0.3125 -8.459391 32.43031 0.1125 -8.894706 32.06235 0.3125 -8.894706 32.06235 0.1125 -9.008995 31.91351 0.3125 -9.008995 31.91351 0.1125 -9.228453 31.62736 0.3125 -9.228453 31.62736 0.1125 -9.49655 31.15934 0.3125 -9.49655 31.15934 0.1125 -9.663322 30.62476 0.3125 -9.663322 30.62476 0.1125 -9.696534 30.05643 0.3125 -9.696534 30.05643 0.1125 -9.696452 27.68295 0.3125 -9.696452 27.68295 0.1125 -9.720678 27.42859 0.3125 -9.720678 27.42859 0.1125 -9.763103 26.98056 0.3125 -9.763103 26.98056 0.1125 -9.858967 26.6165 0.3125 -9.858967 26.6165 0.1125 -9.930261 26.34521 0.3125 -9.930261 26.34521 0.1125 -10.16448 25.7102 0.3125 -10.16448 25.7102 0.1125 -10.53199 25.14151 0.3125 -10.53199 25.14151 0.1125 -10.74574 24.87832 0.3125 -10.74574 24.87832 0.1125 -10.96648 24.60633 0.3125 -10.96648 24.60633 0.1125 -11.50223 24.1724 0.3125 -11.50223 24.1724 0.1125 -11.83838 23.97447 0.3125 -11.83838 23.97447 0.1125 -12.07054 23.83759 0.3125 -12.07054 23.83759 0.1125 -13.34009 23.13552 0.3125 -13.34009 23.13552 0.1125 -13.82192 22.90797 0.3125 -13.82192 22.90797 0.1125 -13.9748 22.83564 0.3125 -13.9748 22.83564 0.1125 -14.64549 22.63418 0.3125 -14.64549 22.63418 0.1125 -15.34745 22.56748 0.3125 -15.34745 22.56748 0.1125 -24.80888 22.23167 0.3125 -24.80888 22.23167 0.1125 -25.14402 22.16463 0.3125 -25.14402 22.16463 0.1125 -25.47915 21.99916 0.3125 -25.47915 21.99916 0.1125 -25.5705 21.9178 0.3125 -25.5705 21.9178 0.1125 -25.74401 21.76279 0.3125 -25.74401 21.76279 0.1125 -26.50701 20.79815 0.3125 -26.50701 20.79815 0.1125 -27.01367 20.15726 0.3125 -27.01367 20.15726 0.1125 -28.18497 18.48858 0.3125 -28.18497 18.48858 0.1125 -29.28896 16.71443 0.3125 -29.28896 16.71443 0.1125 -30.22404 14.91171 0.3125 -30.22404 14.91171 0.1125 -31.09504 13.03843 0.3125 -31.09504 13.03843 0.1125 -31.57692 11.76463 0.3125 -31.57692 11.76463 0.1125 -31.82877 11.09848 0.3125 -31.82877 11.09848 0.1125 -32.46371 9.161363 0.3125 -32.46371 9.161363 0.1125 -32.93272 7.154046 0.3125 -32.93272 7.154046 0.1125 -33.3349 5.11498 0.3125 -33.3349 5.11498 0.1125 -33.56758 3.075921 0.3125 -33.56758 3.075921 0.1125 -33.70159 1.036865 0.3125 -33.70159 1.036865 0.1125 -33.70152 -1.037499 0.3125 -33.70152 -1.037499 0.1125 -33.56737 -3.076581 0.3125 -33.56737 -3.076581 0.1125 -33.33455 -5.115519 0.3125 -33.33455 -5.115519 0.1125 -32.93223 -7.154556 0.3125 -32.93223 -7.154556 0.1125 -32.46307 -9.161948 0.3125 -32.46307 -9.161948 0.1125 -31.82801 -11.1022 0.3125 -31.82801 -11.1022 0.1125 -31.47546 -12.03294 0.3125 -31.47546 -12.03294 0.1125 -31.09414 -13.03885 0.3125 -31.09414 -13.03885 0.1125 -30.22301 -14.91214 0.3125 -30.22301 -14.91214 0.1125 -29.2878 -16.71829 0.3125 -29.2878 -16.71829 0.1125 -28.18355 -18.48916 0.3125 -28.18355 -18.48916 0.1125 -27.01227 -20.16124 0.3125 -27.01227 -20.16124 0.1125 -25.7425 -21.76633 0.3125 -25.7425 -21.76633 0.1125 -25.47791 -21.99919 0.3125 -25.47791 -21.99919 0.1125 -25.14249 -22.16855 0.3125 -25.14249 -22.16855 0.1125 -24.80735 -22.2355 0.3125 -24.80735 -22.2355 0.1125 -15.34589 -22.56689 0.3125 -15.34589 -22.56689 0.1125 -15.27871 -22.57332 0.3125 -15.27871 -22.57332 0.1125 -14.64421 -22.63382 0.3125 -14.64421 -22.63382 0.1125 -14.39356 -22.70894 0.3125 -14.39356 -22.70894 0.1125 -13.97322 -22.8346 0.3125 -13.97322 -22.8346 0.1125 -13.64188 -22.99331 0.3125 -13.64188 -22.99331 0.1125 -13.3385 -23.13828 0.3125 -13.3385 -23.13828 0.1125 -12.45342 -23.62761 0.3125 -12.45342 -23.62761 0.1125 -12.06862 -23.84019 0.3125 -12.06862 -23.84019 0.1125 -11.68947 -24.06158 0.3125 -11.68947 -24.06158 0.1125 -11.50042 -24.17189 0.3125 -11.50042 -24.17189 0.1125 -10.96464 -24.60924 0.3125 -10.96464 -24.60924 0.1125 -10.53067 -25.14584 0.3125 -10.53067 -25.14584 0.1125 -10.16299 -25.7144 0.3125 -10.16299 -25.7144 0.1125 -9.92883 -26.34939 0.3125 -9.92883 -26.34939 0.1125 -9.761944 -26.98438 0.3125 -9.761944 -26.98438 0.1125 -9.694822 -27.68718 0.3125 -9.694822 -27.68718 0.1125 -9.69474 -30.0607 0.3125 -9.69474 -30.0607 0.1125 -9.682204 -30.27573 0.3125 -9.682204 -30.27573 0.1125 -9.661348 -30.62901 0.3125 -9.661348 -30.62901 0.1125 -9.574302 -30.90868 0.3125 -9.574302 -30.90868 0.1125 -9.494748 -31.16382 0.3125 -9.494748 -31.16382 0.1125 -9.289564 -31.52163 0.3125 -9.289564 -31.52163 0.1125 -9.226379 -31.63174 0.3125 -9.226379 -31.63174 0.1125 -8.892773 -32.06655 0.3125 -8.892773 -32.06655 0.1125 -8.457434 -32.43406 0.3125 -8.457434 -32.43406 0.1125 -7.956516 -32.7018 0.3125 -7.956516 -32.7018 0.1125 -7.578672 -32.85271 0.3125 -7.578672 -32.85271 0.1125 -7.454649 -32.90215 0.3125 -7.454649 -32.90215 0.1125 -5.615893 -33.23694 0.3125 -5.615893 -33.23694 0.1125 -3.743025 -33.50394 0.3125 -3.743025 -33.50394 0.1125 -3.591969 -33.51742 0.3125 -3.591969 -33.51742 0.1125 -1.871078 -33.67076 0.3125 -1.871078 -33.67076 0.1125 0.001110288 -33.70446 0.3125 0.001110288 -33.70446 0.1125 1.872803 -33.67063 0.3125 1.872803 -33.67063 0.1125 3.744986 -33.50368 0.3125 3.744986 -33.50368 0.1125 5.617164 -33.23656 0.3125 5.617164 -33.23656 0.1125 7.45618 -32.90163 0.3125 7.45618 -32.90163 0.1125 7.958175 -32.70125 0.3125 7.958175 -32.70125 0.1125 8.459461 -32.43347 0.3125 8.459461 -32.43347 0.1125 8.89407 -32.06594 0.3125 8.89407 -32.06594 0.1125 9.228488 -31.63088 0.3125 9.228488 -31.63088 0.1125 9.495524 -31.16317 0.3125 9.495524 -31.16317 0.1125 9.662722 -30.62793 0.3125 9.662722 -30.62793 0.1125 9.696216 -30.06003 0.3125 9.696216 -30.06003 0.1125 9.696134 -27.68651 0.3125 9.696134 -27.68651 0.1125 9.763138 -26.9837 0.3125 9.763138 -26.9837 0.1125 9.930331 -26.3487 0.3125 9.930331 -26.3487 0.1125 10.16455 -25.71369 0.3125 10.16455 -25.71369 0.1125 10.53213 -25.14511 0.3125 10.53213 -25.14511 0.1125 10.96708 -24.60986 0.3125 10.96708 -24.60986 0.1125 11.50047 -24.17109 0.3125 11.50047 -24.17109 0.1125 10.3 29.96516 38.61181 10.3 30.26828 39.1311 10.3 30.26567 39.3365 10.3 30.21591 38.93248 10.3 30.11236 38.75509 10.3 30.56448 36.79045 10.3 30.54238 36.87956 10.3 30.6093 36.71033 10.3 30.67368 36.64487 10.3 30.54458 36.97134 10.3 30.54915 37.1767 10.3 30.49866 37.37581 10.3 30.39681 37.55418 10.3 30.25099 37.69885 10.3 30.07181 37.79929 10.3 31.69387 39.93721 10.3 31.83597 40.08553 10.3 32.06641 40.22415 10.3 32.15821 40.22483 10.3 31.97804 40.19926 10.3 31.89936 40.15194 10.3 31.5173 39.83225 10.3 31.3191 39.7783 10.3 31.11369 39.77928 10.3 30.91602 39.83511 10.3 32.51795 36.7838 10.3 32.60683 36.80683 10.3 32.42615 36.78504 10.3 32.33793 36.81046 10.3 32.25955 36.85825 10.3 32.08398 36.96489 10.3 30.93359 36.57585 10.3 31.02196 36.60074 10.3 31.10064 36.64806 10.3 30.84179 36.57517 10.3 31.16403 36.71447 10.3 31.88631 37.02072 10.3 31.30613 36.86279 10.3 31.6809 37.0217 10.3 31.4827 36.96775 10.3 33.36296 38.82155 10.3 33.40946 38.74239 10.3 33.29722 38.88564 10.3 33.21691 38.93011 10.3 33.1277 38.95181 10.3 32.92819 39.00071 10.3 32.74901 39.10115 10.3 32.60319 39.24582 10.3 32.50134 39.42419 10.3 32.45085 39.6233 10.3 32.45542 39.82866 10.3 32.45762 39.92044 10.3 32.43552 40.00955 10.3 32.3907 40.08967 10.3 32.32632 40.15513 10.3 32.79656 36.9974 10.3 32.75125 36.91755 10.3 32.81919 37.08638 10.3 32.81754 37.17817 10.3 33.29555 38.3309 10.3 33.36168 38.39459 10.3 33.40865 38.47347 10.3 33.43314 38.56195 9.5 32.25955 36.85825 9.5 32.08398 36.96489 9.5 31.88631 37.02072 9.5 31.6809 37.0217 9.5 31.4827 36.96775 9.5 31.30613 36.86279 9.5 31.16403 36.71447 9.5 30.54458 36.97134 9.5 30.54238 36.87956 9.5 30.56448 36.79045 9.5 30.6093 36.71033 9.5 30.67368 36.64487 9.5 30.75305 36.59873 9.5 30.84179 36.57517 9.5 30.93359 36.57585 9.5 31.02196 36.60074 9.5 31.10064 36.64806 9.5 30.54915 37.1767 9.5 30.49866 37.37581 9.5 30.39681 37.55418 9.5 30.25099 37.69885 9.5 30.07181 37.79929 9.5 29.96516 38.61181 9.5 30.11236 38.75509 9.5 30.21591 38.93248 9.5 30.26828 39.1311 9.5 30.26567 39.3365 9.5 30.91602 39.83511 9.5 31.11369 39.77928 9.5 31.3191 39.7783 9.5 31.5173 39.83225 9.5 31.69387 39.93721 9.5 31.83597 40.08553 9.5 32.45542 39.82866 9.5 32.45762 39.92044 9.5 32.43552 40.00955 9.5 32.3907 40.08967 9.5 32.32632 40.15513 9.5 32.24695 40.20127 9.5 32.15821 40.22483 9.5 32.06641 40.22415 9.5 31.97804 40.19926 9.5 31.89936 40.15194 9.5 32.45085 39.6233 9.5 32.50134 39.42419 9.5 32.60319 39.24582 9.5 32.74901 39.10115 9.5 32.92819 39.00071 9.5 33.1277 38.95181 9.5 33.29555 38.3309 9.5 33.36168 38.39459 9.5 33.40865 38.47347 9.5 33.43314 38.56195 9.5 33.43342 38.65376 9.5 33.40946 38.74239 9.5 33.36296 38.82155 9.5 33.29722 38.88564 9.5 33.21691 38.93011 9.5 32.33793 36.81046 9.5 32.42615 36.78504 9.5 32.51795 36.7838 9.5 32.60683 36.80683 9.5 32.68647 36.85249 9.5 32.75125 36.91755 9.5 32.79656 36.9974 9.5 32.81919 37.08638 9.5 32.81754 37.17817 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 5 2 7 2 8 3 7 3 9 3 10 4 9 4 11 4 12 5 11 5 13 5 14 6 15 6 16 6 17 7 18 7 19 7 19 8 18 8 4 8 20 9 14 9 21 9 22 10 20 10 21 10 14 11 16 11 21 11 22 12 21 12 23 12 19 13 4 13 3 13 24 14 22 14 25 14 26 15 24 15 25 15 27 16 28 16 29 16 22 17 23 17 25 17 27 18 29 18 2 18 26 19 25 19 30 19 3 20 5 20 6 20 31 21 26 21 32 21 26 22 30 22 32 22 2 23 29 23 0 23 33 24 31 24 34 24 31 25 32 25 34 25 6 26 7 26 8 26 35 27 33 27 36 27 33 28 34 28 36 28 37 29 35 29 38 29 39 30 37 30 38 30 35 31 36 31 38 31 1 32 0 32 40 32 8 33 9 33 10 33 39 34 38 34 41 34 42 35 40 35 43 35 44 36 45 36 46 36 45 37 44 37 47 37 10 38 11 38 12 38 47 39 44 39 48 39 39 40 41 40 48 40 44 41 39 41 48 41 46 42 49 42 50 42 51 43 43 43 52 43 47 44 48 44 53 44 12 45 13 45 54 45 53 46 48 46 55 46 50 47 56 47 57 47 54 48 13 48 58 48 59 49 52 49 60 49 54 50 58 50 61 50 62 51 55 51 63 51 17 52 57 52 18 52 57 53 56 53 18 53 64 54 60 54 65 54 58 55 64 55 65 55 61 56 58 56 66 56 67 57 63 57 68 57 58 58 65 58 66 58 67 59 68 59 27 59 69 60 61 60 70 60 61 61 66 61 70 61 27 62 68 62 28 62 46 63 45 63 49 63 50 64 49 64 56 64 63 65 67 65 62 65 55 66 62 66 53 66 60 67 64 67 59 67 71 68 69 68 15 68 52 69 59 69 51 69 14 70 71 70 15 70 43 71 51 71 42 71 69 72 70 72 15 72 40 73 42 73 1 73 72 74 73 74 74 74 73 75 75 75 74 75 76 76 77 76 78 76 79 77 80 77 81 77 82 78 76 78 83 78 76 79 78 79 83 79 81 80 80 80 84 80 85 81 82 81 86 81 82 82 83 82 86 82 87 83 72 83 88 83 72 84 74 84 88 84 89 85 85 85 90 85 85 86 86 86 90 86 81 87 84 87 91 87 91 88 84 88 92 88 93 89 89 89 94 89 89 90 90 90 94 90 95 91 87 91 96 91 87 92 88 92 96 92 93 93 97 93 98 93 91 94 92 94 99 94 97 95 93 95 100 95 99 96 92 96 101 96 93 97 94 97 102 97 100 98 93 98 102 98 103 99 95 99 104 99 95 100 96 100 104 100 98 101 105 101 106 101 99 102 101 102 107 102 100 103 102 103 108 103 107 104 101 104 109 104 108 105 102 105 110 105 106 106 105 106 111 106 104 107 112 107 113 107 106 108 111 108 114 108 103 109 104 109 113 109 107 110 109 110 115 110 115 111 109 111 116 111 117 112 110 112 118 112 114 113 111 113 119 113 120 114 113 114 121 114 112 115 115 115 121 115 113 116 112 116 121 116 114 117 119 117 122 117 115 118 116 118 121 118 123 119 120 119 124 119 117 120 118 120 125 120 120 121 121 121 124 121 125 122 118 122 126 122 123 123 124 123 127 123 122 124 119 124 128 124 129 125 123 125 127 125 122 126 128 126 130 126 129 127 127 127 131 127 132 128 129 128 131 128 125 129 126 129 133 129 133 130 126 130 134 130 132 131 131 131 135 131 136 132 132 132 135 132 130 133 128 133 137 133 136 134 135 134 138 134 139 135 136 135 138 135 130 136 137 136 140 136 139 137 138 137 141 137 133 138 134 138 142 138 143 139 139 139 141 139 142 140 134 140 144 140 77 141 143 141 145 141 143 142 141 142 145 142 140 143 137 143 75 143 77 144 145 144 78 144 98 145 97 145 105 145 140 146 75 146 73 146 110 147 117 147 108 147 142 148 144 148 79 148 79 149 144 149 80 149 146 150 147 150 148 150 147 151 149 151 148 151 150 152 146 152 151 152 146 153 148 153 151 153 152 154 150 154 153 154 154 155 155 155 156 155 150 156 151 156 153 156 155 157 157 157 156 157 158 158 152 158 159 158 152 159 153 159 159 159 160 160 154 160 161 160 154 161 156 161 161 161 162 162 158 162 163 162 158 163 159 163 163 163 164 164 160 164 165 164 160 165 161 165 165 165 166 166 162 166 167 166 162 167 163 167 167 167 168 168 164 168 169 168 155 169 166 169 157 169 164 170 165 170 169 170 166 171 167 171 157 171 170 172 168 172 171 172 168 173 169 173 171 173 172 174 170 174 173 174 170 175 171 175 173 175 174 176 172 176 175 176 172 177 173 177 175 177 176 178 174 178 177 178 174 179 175 179 177 179 178 180 176 180 179 180 176 181 177 181 179 181 180 182 178 182 181 182 178 183 179 183 181 183 182 184 180 184 183 184 180 185 181 185 183 185 182 186 183 186 184 186 185 187 182 187 184 187 185 188 184 188 186 188 187 189 185 189 186 189 187 190 186 190 188 190 189 191 187 191 188 191 190 192 189 192 191 192 189 193 188 193 191 193 192 194 190 194 193 194 190 195 191 195 193 195 194 196 192 196 195 196 192 197 193 197 195 197 147 198 194 198 149 198 194 199 195 199 149 199 196 200 197 200 198 200 197 201 199 201 198 201 200 202 196 202 201 202 196 203 198 203 201 203 202 204 200 204 203 204 204 205 205 205 206 205 200 206 201 206 203 206 205 207 207 207 206 207 208 208 202 208 209 208 202 209 203 209 209 209 210 210 204 210 211 210 204 211 206 211 211 211 212 212 208 212 213 212 208 213 209 213 213 213 214 214 210 214 215 214 210 215 211 215 215 215 216 216 212 216 217 216 212 217 213 217 217 217 218 218 214 218 219 218 205 219 216 219 207 219 214 220 215 220 219 220 216 221 217 221 207 221 220 222 218 222 221 222 218 223 219 223 221 223 222 224 220 224 223 224 220 225 221 225 223 225 224 226 222 226 225 226 222 227 223 227 225 227 226 228 224 228 227 228 224 229 225 229 227 229 228 230 226 230 229 230 226 231 227 231 229 231 230 232 228 232 231 232 228 233 229 233 231 233 232 234 230 234 233 234 230 235 231 235 233 235 232 236 233 236 234 236 235 237 232 237 234 237 235 238 234 238 236 238 237 239 235 239 236 239 237 240 236 240 238 240 239 241 237 241 238 241 240 242 239 242 241 242 239 243 238 243 241 243 242 244 240 244 243 244 240 245 241 245 243 245 244 246 242 246 245 246 242 247 243 247 245 247 197 248 244 248 199 248 244 249 245 249 199 249 246 250 247 250 248 250 247 251 249 251 248 251 250 252 251 252 252 252 253 253 246 253 254 253 246 254 248 254 254 254 255 255 253 255 256 255 257 256 250 256 258 256 253 257 254 257 256 257 250 258 252 258 258 258 255 259 256 259 259 259 260 260 257 260 261 260 257 261 258 261 261 261 251 262 255 262 252 262 255 263 259 263 252 263 262 264 260 264 263 264 260 265 261 265 263 265 264 266 262 266 265 266 262 267 263 267 265 267 266 268 264 268 267 268 264 269 265 269 267 269 266 270 267 270 268 270 269 271 266 271 270 271 271 272 269 272 270 272 266 273 268 273 270 273 272 274 271 274 273 274 271 275 270 275 273 275 272 276 273 276 274 276 275 277 272 277 276 277 272 278 274 278 276 278 277 279 275 279 278 279 279 280 277 280 278 280 275 281 276 281 278 281 279 282 278 282 280 282 279 283 280 283 281 283 282 284 279 284 281 284 283 285 282 285 281 285 283 286 281 286 284 286 285 287 283 287 286 287 283 288 284 288 286 288 287 289 285 289 286 289 288 290 287 290 289 290 287 291 286 291 289 291 290 292 288 292 291 292 288 293 289 293 291 293 292 294 290 294 293 294 290 295 291 295 293 295 294 296 292 296 295 296 292 297 293 297 295 297 247 298 294 298 249 298 294 299 295 299 249 299 296 300 297 300 298 300 297 301 299 301 298 301 300 302 296 302 301 302 296 303 298 303 301 303 302 304 303 304 304 304 303 305 305 305 304 305 306 306 300 306 307 306 300 307 301 307 307 307 308 308 302 308 309 308 302 309 304 309 309 309 310 310 306 310 311 310 306 311 307 311 311 311 312 312 308 312 313 312 314 313 310 313 315 313 308 314 309 314 313 314 310 315 311 315 315 315 303 316 314 316 305 316 314 317 315 317 305 317 316 318 312 318 317 318 318 319 316 319 317 319 312 320 313 320 317 320 318 321 317 321 319 321 320 322 318 322 321 322 318 323 319 323 321 323 322 324 320 324 323 324 320 325 321 325 323 325 324 326 322 326 325 326 322 327 323 327 325 327 326 328 324 328 327 328 324 329 325 329 327 329 328 330 326 330 329 330 326 331 327 331 329 331 330 332 328 332 331 332 332 333 330 333 331 333 328 334 329 334 331 334 332 335 331 335 333 335 332 336 333 336 334 336 335 337 332 337 334 337 336 338 335 338 334 338 336 339 334 339 337 339 338 340 336 340 339 340 336 341 337 341 339 341 340 342 338 342 341 342 338 343 339 343 341 343 342 344 340 344 343 344 340 345 341 345 343 345 344 346 342 346 345 346 297 347 344 347 345 347 342 348 343 348 345 348 297 349 345 349 299 349 346 350 347 350 348 350 349 351 348 351 350 351 349 352 346 352 348 352 351 353 350 353 352 353 351 354 349 354 350 354 353 355 352 355 354 355 353 356 351 356 352 356 355 357 354 357 356 357 355 358 353 358 354 358 357 359 356 359 358 359 357 360 355 360 356 360 359 361 357 361 358 361 360 362 361 362 362 362 363 363 360 363 364 363 360 364 362 364 364 364 365 365 363 365 366 365 363 366 364 366 366 366 367 367 365 367 368 367 365 368 366 368 368 368 369 369 367 369 370 369 367 370 368 370 370 370 371 371 369 371 372 371 369 372 370 372 372 372 373 373 371 373 374 373 371 374 372 374 374 374 375 375 373 375 376 375 373 376 374 376 376 376 377 377 375 377 378 377 375 378 376 378 378 378 379 379 377 379 380 379 377 380 378 380 380 380 379 381 380 381 381 381 382 382 383 382 384 382 385 383 382 383 386 383 382 384 384 384 386 384 387 385 385 385 388 385 385 386 386 386 388 386 389 387 387 387 390 387 387 388 388 388 390 388 391 389 389 389 392 389 389 390 390 390 392 390 393 391 391 391 394 391 391 392 392 392 394 392 395 393 393 393 396 393 393 394 394 394 396 394 397 395 395 395 398 395 395 396 396 396 398 396 399 397 397 397 400 397 397 398 398 398 400 398 401 399 399 399 402 399 399 400 400 400 402 400 401 401 402 401 403 401 404 402 372 402 405 402 404 403 405 403 406 403 407 404 408 404 409 404 407 405 409 405 410 405 407 406 411 406 408 406 407 407 412 407 411 407 413 408 414 408 415 408 413 409 416 409 417 409 413 410 415 410 416 410 413 411 418 411 414 411 413 412 406 412 418 412 413 413 404 413 406 413 419 414 372 414 404 414 419 415 410 415 372 415 419 416 407 416 410 416 419 417 404 417 413 417 420 418 421 418 422 418 420 419 417 419 421 419 420 420 422 420 419 420 420 421 413 421 417 421 420 422 419 422 413 422 423 423 424 423 425 423 423 424 426 424 424 424 423 425 427 425 426 425 423 426 425 426 428 426 423 427 428 427 427 427 429 428 430 428 431 428 429 429 431 429 432 429 433 430 432 430 434 430 433 431 429 431 432 431 433 432 430 432 429 432 433 433 435 433 430 433 436 434 434 434 437 434 436 435 437 435 435 435 436 436 433 436 434 436 436 437 435 437 433 437 438 438 437 438 439 438 438 439 435 439 437 439 440 440 439 440 441 440 440 441 438 441 439 441 440 442 435 442 438 442 440 443 442 443 435 443 443 444 444 444 442 444 443 445 440 445 441 445 443 446 442 446 440 446 443 447 441 447 444 447 445 448 446 448 412 448 445 449 422 449 446 449 445 450 419 450 422 450 445 451 412 451 407 451 445 452 407 452 419 452 447 453 448 453 426 453 447 454 449 454 448 454 447 455 450 455 449 455 447 456 451 456 452 456 431 457 453 457 450 457 431 458 430 458 453 458 431 459 450 459 447 459 427 460 454 460 455 460 427 461 455 461 451 461 427 462 451 462 447 462 427 463 447 463 426 463 456 464 431 464 447 464 456 465 447 465 452 465 456 466 452 466 457 466 456 467 457 467 432 467 456 468 432 468 431 468 435 469 442 469 458 469 435 470 458 470 430 470 428 471 459 471 454 471 428 472 454 472 427 472 437 473 460 473 439 473 437 474 434 474 460 474 461 475 462 475 463 475 461 476 425 476 462 476 461 477 428 477 425 477 464 478 465 478 466 478 464 479 466 479 459 479 464 480 459 480 428 480 444 481 467 481 442 481 444 482 468 482 467 482 469 483 470 483 471 483 469 484 463 484 470 484 469 485 472 485 465 485 469 486 461 486 463 486 469 487 464 487 428 487 469 488 428 488 461 488 469 489 465 489 464 489 473 490 441 490 474 490 473 491 474 491 394 491 473 492 444 492 441 492 414 493 472 493 469 493 414 494 418 494 475 494 414 495 475 495 472 495 414 496 469 496 471 496 411 497 476 497 468 497 411 498 477 498 476 498 411 499 412 499 477 499 411 500 473 500 394 500 411 501 394 501 408 501 411 502 468 502 444 502 411 503 444 503 473 503 478 504 415 504 414 504 478 505 471 505 415 505 478 506 414 506 471 506 479 507 480 507 481 507 479 508 482 508 480 508 483 509 484 509 485 509 486 510 481 510 487 510 486 511 479 511 481 511 488 512 485 512 489 512 488 513 483 513 485 513 490 514 487 514 484 514 490 515 486 515 487 515 483 516 490 516 484 516 491 517 489 517 492 517 491 518 488 518 489 518 493 519 492 519 494 519 493 520 491 520 492 520 495 521 494 521 496 521 495 522 493 522 494 522 497 523 496 523 498 523 497 524 495 524 496 524 499 525 498 525 500 525 499 526 497 526 498 526 501 527 500 527 502 527 501 528 499 528 500 528 503 529 502 529 504 529 503 530 501 530 502 530 505 531 504 531 506 531 505 532 503 532 504 532 507 533 506 533 508 533 507 534 505 534 506 534 509 535 507 535 508 535 509 536 508 536 510 536 511 537 509 537 510 537 511 538 510 538 512 538 513 539 511 539 512 539 513 540 512 540 514 540 515 541 513 541 514 541 515 542 514 542 516 542 517 543 515 543 516 543 517 544 516 544 518 544 519 545 518 545 520 545 519 546 517 546 518 546 521 547 520 547 522 547 521 548 519 548 520 548 523 549 522 549 524 549 523 550 521 550 522 550 525 551 524 551 526 551 525 552 523 552 524 552 527 553 526 553 528 553 527 554 525 554 526 554 482 555 528 555 480 555 482 556 527 556 528 556 529 557 530 557 531 557 532 558 533 558 534 558 532 559 529 559 533 559 535 560 534 560 536 560 537 561 538 561 539 561 535 562 532 562 534 562 537 563 540 563 538 563 541 564 536 564 542 564 541 565 535 565 536 565 543 566 539 566 544 566 543 567 537 567 539 567 545 568 542 568 546 568 545 569 541 569 542 569 547 570 544 570 548 570 547 571 543 571 544 571 549 572 546 572 550 572 549 573 545 573 546 573 551 574 548 574 552 574 540 575 550 575 538 575 551 576 547 576 548 576 540 577 549 577 550 577 553 578 552 578 554 578 553 579 551 579 552 579 555 580 554 580 556 580 555 581 553 581 554 581 557 582 556 582 558 582 557 583 555 583 556 583 559 584 558 584 560 584 559 585 557 585 558 585 561 586 560 586 562 586 561 587 559 587 560 587 563 588 562 588 564 588 563 589 561 589 562 589 565 590 564 590 566 590 565 591 563 591 564 591 567 592 565 592 566 592 567 593 566 593 568 593 569 594 567 594 568 594 569 595 568 595 570 595 571 596 569 596 570 596 571 597 570 597 572 597 573 598 572 598 574 598 573 599 571 599 572 599 575 600 574 600 576 600 575 601 573 601 574 601 577 602 576 602 578 602 577 603 575 603 576 603 530 604 578 604 531 604 530 605 577 605 578 605 529 606 531 606 533 606 579 607 580 607 581 607 579 608 582 608 580 608 583 609 581 609 584 609 583 610 579 610 581 610 585 611 584 611 586 611 585 612 583 612 584 612 587 613 586 613 588 613 587 614 585 614 586 614 589 615 588 615 590 615 589 616 587 616 588 616 591 617 590 617 592 617 591 618 589 618 590 618 593 619 594 619 595 619 596 620 593 620 597 620 593 621 595 621 597 621 598 622 596 622 599 622 596 623 597 623 599 623 600 624 598 624 601 624 598 625 599 625 601 625 602 626 600 626 603 626 600 627 601 627 603 627 604 628 602 628 605 628 602 629 603 629 605 629 606 630 604 630 607 630 604 631 605 631 607 631 608 632 606 632 609 632 606 633 607 633 609 633 610 634 608 634 611 634 608 635 609 635 611 635 612 636 610 636 613 636 610 637 611 637 613 637 612 638 613 638 614 638 615 639 616 639 617 639 618 640 615 640 617 640 619 641 618 641 620 641 618 642 617 642 620 642 621 643 619 643 622 643 619 644 620 644 622 644 623 645 621 645 624 645 621 646 622 646 624 646 625 647 623 647 626 647 623 648 624 648 626 648 627 649 625 649 628 649 625 650 626 650 628 650 629 651 627 651 630 651 627 652 628 652 630 652 631 653 629 653 632 653 629 654 630 654 632 654 633 655 631 655 634 655 631 656 632 656 634 656 635 657 633 657 636 657 633 658 634 658 636 658 637 659 605 659 638 659 637 660 638 660 639 660 640 661 641 661 642 661 640 662 642 662 643 662 640 663 644 663 641 663 640 664 645 664 644 664 646 665 647 665 648 665 646 666 649 666 650 666 646 667 648 667 649 667 646 668 651 668 647 668 646 669 639 669 651 669 646 670 637 670 639 670 652 671 605 671 637 671 652 672 643 672 605 672 652 673 640 673 643 673 652 674 637 674 646 674 653 675 654 675 655 675 653 676 650 676 654 676 653 677 655 677 652 677 653 678 646 678 650 678 653 679 652 679 646 679 656 680 657 680 658 680 656 681 659 681 657 681 656 682 660 682 659 682 656 683 658 683 661 683 656 684 661 684 660 684 662 685 663 685 664 685 662 686 664 686 665 686 666 687 665 687 667 687 666 688 662 688 665 688 666 689 663 689 662 689 666 690 668 690 663 690 669 691 670 691 668 691 669 692 667 692 670 692 669 693 666 693 667 693 669 694 668 694 666 694 671 695 668 695 670 695 671 696 670 696 672 696 673 697 674 697 668 697 673 698 672 698 675 698 673 699 671 699 672 699 673 700 668 700 671 700 676 701 677 701 674 701 676 702 674 702 673 702 676 703 673 703 675 703 676 704 675 704 677 704 678 705 679 705 645 705 678 706 655 706 679 706 678 707 652 707 655 707 678 708 645 708 640 708 678 709 640 709 652 709 680 710 681 710 659 710 680 711 682 711 681 711 680 712 683 712 682 712 680 713 684 713 685 713 664 714 686 714 683 714 664 715 663 715 686 715 664 716 683 716 680 716 660 717 687 717 688 717 660 718 688 718 684 718 660 719 684 719 680 719 660 720 680 720 659 720 689 721 664 721 680 721 689 722 680 722 685 722 689 723 685 723 690 723 689 724 690 724 665 724 689 725 665 725 664 725 668 726 674 726 691 726 668 727 691 727 663 727 661 728 692 728 687 728 661 729 687 729 660 729 670 730 693 730 672 730 670 731 667 731 693 731 694 732 695 732 696 732 694 733 658 733 695 733 694 734 661 734 658 734 697 735 698 735 699 735 697 736 699 736 692 736 697 737 692 737 661 737 677 738 700 738 674 738 677 739 701 739 700 739 702 740 703 740 704 740 702 741 696 741 703 741 702 742 705 742 698 742 702 743 694 743 696 743 702 744 697 744 661 744 702 745 661 745 694 745 702 746 698 746 697 746 706 747 675 747 707 747 706 748 707 748 626 748 706 749 677 749 675 749 647 750 705 750 702 750 647 751 651 751 708 751 647 752 708 752 705 752 647 753 702 753 704 753 644 754 709 754 701 754 644 755 710 755 709 755 644 756 645 756 710 756 644 757 706 757 626 757 644 758 626 758 641 758 644 759 701 759 677 759 644 760 677 760 706 760 711 761 648 761 647 761 711 762 704 762 648 762 711 763 647 763 704 763 712 764 713 764 714 764 715 765 714 765 716 765 715 766 712 766 714 766 717 767 716 767 718 767 717 768 715 768 716 768 719 769 718 769 720 769 719 770 717 770 718 770 721 771 720 771 722 771 721 772 719 772 720 772 723 773 722 773 724 773 723 774 721 774 722 774 725 775 723 775 724 775 726 776 727 776 728 776 729 777 726 777 730 777 726 778 728 778 730 778 731 779 729 779 732 779 729 780 730 780 732 780 733 781 731 781 734 781 731 782 732 782 734 782 735 783 733 783 736 783 733 784 734 784 736 784 737 785 735 785 738 785 735 786 736 786 738 786 739 787 737 787 740 787 737 788 738 788 740 788 741 789 739 789 742 789 739 790 740 790 742 790 743 791 741 791 744 791 741 792 742 792 744 792 745 793 743 793 746 793 743 794 744 794 746 794 745 795 746 795 747 795 748 796 749 796 750 796 751 797 748 797 750 797 752 798 751 798 753 798 751 799 750 799 753 799 754 800 752 800 755 800 752 801 753 801 755 801 756 802 754 802 757 802 754 803 755 803 757 803 758 804 756 804 759 804 756 805 757 805 759 805 760 806 758 806 761 806 758 807 759 807 761 807 762 808 760 808 763 808 760 809 761 809 763 809 764 810 762 810 765 810 762 811 763 811 765 811 766 812 764 812 767 812 764 813 765 813 767 813 768 814 766 814 769 814 766 815 767 815 769 815 770 816 738 816 771 816 770 817 771 817 772 817 773 818 774 818 775 818 773 819 775 819 776 819 773 820 777 820 774 820 773 821 778 821 777 821 779 822 780 822 781 822 779 823 782 823 783 823 779 824 781 824 782 824 779 825 784 825 780 825 779 826 772 826 784 826 779 827 770 827 772 827 785 828 738 828 770 828 785 829 776 829 738 829 785 830 773 830 776 830 785 831 770 831 779 831 786 832 787 832 788 832 786 833 783 833 787 833 786 834 788 834 785 834 786 835 785 835 779 835 786 836 779 836 783 836 789 837 790 837 791 837 789 838 792 838 793 838 789 839 794 839 792 839 789 840 791 840 794 840 789 841 793 841 790 841 795 842 796 842 797 842 795 843 797 843 798 843 799 844 798 844 800 844 799 845 795 845 798 845 799 846 796 846 795 846 799 847 801 847 796 847 802 848 803 848 801 848 802 849 800 849 803 849 802 850 799 850 800 850 802 851 801 851 799 851 804 852 801 852 803 852 804 853 803 853 805 853 806 854 807 854 801 854 806 855 805 855 808 855 806 856 804 856 805 856 806 857 801 857 804 857 809 858 810 858 807 858 809 859 807 859 806 859 809 860 806 860 808 860 809 861 808 861 810 861 811 862 812 862 778 862 811 863 788 863 812 863 811 864 785 864 788 864 811 865 778 865 773 865 811 866 773 866 785 866 813 867 814 867 794 867 813 868 815 868 814 868 813 869 816 869 815 869 813 870 817 870 818 870 797 871 819 871 816 871 797 872 796 872 819 872 797 873 816 873 813 873 791 874 820 874 821 874 791 875 821 875 817 875 791 876 817 876 813 876 791 877 813 877 794 877 822 878 797 878 813 878 822 879 813 879 818 879 822 880 818 880 823 880 822 881 823 881 798 881 822 882 798 882 797 882 801 883 807 883 824 883 801 884 824 884 796 884 790 885 825 885 820 885 790 886 820 886 791 886 803 887 826 887 805 887 803 888 800 888 826 888 827 889 828 889 829 889 827 890 793 890 828 890 827 891 790 891 793 891 830 892 831 892 832 892 830 893 832 893 825 893 830 894 825 894 790 894 810 895 833 895 807 895 810 896 834 896 833 896 835 897 836 897 837 897 835 898 829 898 836 898 835 899 838 899 831 899 835 900 827 900 829 900 835 901 830 901 790 901 835 902 790 902 827 902 835 903 831 903 830 903 839 904 808 904 840 904 839 905 840 905 759 905 839 906 810 906 808 906 780 907 838 907 835 907 780 908 784 908 841 908 780 909 841 909 838 909 780 910 835 910 837 910 777 911 842 911 834 911 777 912 843 912 842 912 777 913 778 913 843 913 777 914 839 914 759 914 777 915 759 915 774 915 777 916 834 916 810 916 777 917 810 917 839 917 844 918 781 918 780 918 844 919 837 919 781 919 844 920 780 920 837 920 845 921 846 921 847 921 848 922 849 922 850 922 849 923 851 923 850 923 852 924 853 924 854 924 853 925 845 925 854 925 845 926 847 926 854 926 855 927 848 927 856 927 848 928 850 928 856 928 857 929 852 929 858 929 852 930 854 930 858 930 859 931 857 931 860 931 857 932 858 932 860 932 861 933 855 933 862 933 855 934 856 934 862 934 861 935 862 935 863 935 859 936 860 936 864 936 865 937 859 937 866 937 867 938 861 938 868 938 859 939 864 939 866 939 861 940 863 940 868 940 867 941 868 941 869 941 870 942 865 942 871 942 865 943 866 943 871 943 872 944 867 944 873 944 867 945 869 945 873 945 870 946 871 946 874 946 875 947 870 947 876 947 872 948 873 948 877 948 870 949 874 949 876 949 872 950 877 950 878 950 879 951 875 951 880 951 881 952 872 952 878 952 875 953 876 953 880 953 881 954 878 954 882 954 879 955 880 955 883 955 884 956 879 956 885 956 886 957 881 957 887 957 881 958 882 958 887 958 879 959 883 959 885 959 888 960 886 960 889 960 890 961 884 961 891 961 886 962 887 962 889 962 884 963 885 963 891 963 888 964 889 964 892 964 893 965 890 965 894 965 890 966 891 966 894 966 895 967 888 967 896 967 888 968 892 968 896 968 893 969 894 969 897 969 898 970 893 970 899 970 900 971 895 971 901 971 895 972 896 972 901 972 893 973 897 973 899 973 900 974 901 974 902 974 900 975 902 975 903 975 849 976 898 976 904 976 898 977 899 977 904 977 903 978 902 978 905 978 849 979 904 979 851 979 906 980 903 980 907 980 903 981 905 981 907 981 906 982 907 982 908 982 853 983 906 983 909 983 906 984 908 984 909 984 853 985 909 985 910 985 853 986 910 986 845 986 911 987 912 987 913 987 912 988 914 988 913 988 911 989 913 989 915 989 916 990 917 990 918 990 917 991 919 991 918 991 911 992 915 992 920 992 920 993 915 993 921 993 922 994 916 994 923 994 916 995 918 995 923 995 920 996 921 996 924 996 924 997 921 997 925 997 922 998 923 998 926 998 924 999 925 999 927 999 927 1000 925 1000 928 1000 929 1001 922 1001 930 1001 922 1002 926 1002 930 1002 931 1003 927 1003 932 1003 933 1004 929 1004 934 1004 927 1005 928 1005 932 1005 929 1006 930 1006 934 1006 931 1007 932 1007 935 1007 936 1008 933 1008 937 1008 933 1009 934 1009 937 1009 938 1010 931 1010 939 1010 931 1011 935 1011 939 1011 936 1012 937 1012 940 1012 938 1013 939 1013 941 1013 942 1014 936 1014 943 1014 936 1015 940 1015 943 1015 938 1016 941 1016 944 1016 945 1017 938 1017 946 1017 947 1018 942 1018 948 1018 938 1019 944 1019 946 1019 942 1020 943 1020 948 1020 949 1021 945 1021 950 1021 947 1022 948 1022 951 1022 945 1023 946 1023 950 1023 952 1024 947 1024 951 1024 917 1025 949 1025 953 1025 949 1026 950 1026 953 1026 952 1027 951 1027 954 1027 917 1028 953 1028 919 1028 955 1029 952 1029 956 1029 952 1030 954 1030 956 1030 955 1031 956 1031 957 1031 958 1032 955 1032 957 1032 959 1033 958 1033 957 1033 960 1034 959 1034 961 1034 959 1035 957 1035 961 1035 960 1036 961 1036 962 1036 963 1037 960 1037 964 1037 960 1038 962 1038 964 1038 962 1039 961 1039 965 1039 963 1040 964 1040 966 1040 963 1041 966 1041 967 1041 965 1042 961 1042 968 1042 969 1043 963 1043 970 1043 963 1044 967 1044 970 1044 969 1045 970 1045 971 1045 972 1046 969 1046 973 1046 969 1047 971 1047 973 1047 912 1048 972 1048 914 1048 972 1049 973 1049 914 1049 974 1050 975 1050 896 1050 975 1051 901 1051 896 1051 976 1052 977 1052 978 1052 974 1053 896 1053 892 1053 976 1054 978 1054 979 1054 976 1055 979 1055 980 1055 981 1056 974 1056 889 1056 980 1057 979 1057 982 1057 974 1058 892 1058 889 1058 980 1059 982 1059 983 1059 980 1060 983 1060 984 1060 984 1061 983 1061 985 1061 984 1062 985 1062 986 1062 984 1063 986 1063 987 1063 987 1064 986 1064 988 1064 987 1065 988 1065 989 1065 989 1066 988 1066 990 1066 991 1067 989 1067 992 1067 989 1068 990 1068 992 1068 991 1069 992 1069 993 1069 994 1070 991 1070 993 1070 994 1071 993 1071 995 1071 889 1072 887 1072 996 1072 887 1073 882 1073 996 1073 882 1074 878 1074 996 1074 878 1075 877 1075 996 1075 981 1076 889 1076 996 1076 994 1077 995 1077 997 1077 994 1078 997 1078 998 1078 999 1079 981 1079 1000 1079 981 1080 996 1080 1000 1080 998 1081 997 1081 1001 1081 1002 1082 999 1082 1003 1082 1004 1083 998 1083 1001 1083 999 1084 1000 1084 1003 1084 1005 1085 1004 1085 1006 1085 1007 1086 1002 1086 1008 1086 1004 1087 1001 1087 1006 1087 1002 1088 1003 1088 1008 1088 1007 1089 1008 1089 1009 1089 1010 1090 1005 1090 1011 1090 1005 1091 1006 1091 1011 1091 1007 1092 1009 1092 1012 1092 1012 1093 1009 1093 1013 1093 1014 1094 1010 1094 1015 1094 1010 1095 1011 1095 1015 1095 1012 1096 1013 1096 1016 1096 1017 1097 1014 1097 1018 1097 1014 1098 1015 1098 1018 1098 1012 1099 1016 1099 976 1099 976 1100 1016 1100 977 1100 1019 1101 1017 1101 845 1101 1017 1102 1018 1102 845 1102 1019 1103 845 1103 910 1103 1019 1104 910 1104 1020 1104 1020 1105 910 1105 909 1105 1021 1106 1020 1106 908 1106 1020 1107 909 1107 908 1107 1022 1108 1021 1108 907 1108 1021 1109 908 1109 907 1109 1023 1110 1022 1110 905 1110 1022 1111 907 1111 905 1111 1023 1112 905 1112 902 1112 1023 1113 902 1113 975 1113 975 1114 902 1114 901 1114 1024 1115 1025 1115 1026 1115 1025 1116 1027 1116 1026 1116 1028 1117 965 1117 1029 1117 1029 1118 965 1118 1030 1118 1031 1119 1024 1119 1032 1119 1029 1120 1030 1120 1033 1120 1024 1121 1026 1121 1032 1121 1033 1122 1030 1122 1034 1122 1035 1123 1031 1123 1036 1123 1033 1124 1034 1124 1037 1124 1031 1125 1032 1125 1036 1125 1037 1126 1034 1126 1038 1126 1035 1127 1036 1127 921 1127 1037 1128 1038 1128 1039 1128 1040 1129 1035 1129 915 1129 1035 1130 921 1130 915 1130 1039 1131 1038 1131 1041 1131 1039 1132 1041 1132 1042 1132 921 1133 1036 1133 925 1133 1042 1134 1041 1134 1043 1134 1040 1135 915 1135 913 1135 1042 1136 1043 1136 1044 1136 1044 1137 1043 1137 1045 1137 925 1138 1036 1138 928 1138 1044 1139 1045 1139 1046 1139 1046 1140 1045 1140 1047 1140 1048 1141 1040 1141 914 1141 1040 1142 913 1142 914 1142 1049 1143 1046 1143 1050 1143 1046 1144 1047 1144 1050 1144 1051 1145 1048 1145 973 1145 1049 1146 1050 1146 1052 1146 1048 1147 914 1147 973 1147 1051 1148 973 1148 971 1148 1049 1149 1052 1149 1053 1149 1054 1150 1049 1150 1053 1150 1055 1151 1051 1151 970 1151 1056 1152 1054 1152 1057 1152 1051 1153 971 1153 970 1153 1054 1154 1053 1154 1057 1154 1056 1155 1057 1155 1058 1155 1055 1156 970 1156 967 1156 1056 1157 1058 1157 1059 1157 1055 1158 967 1158 1060 1158 1059 1159 1058 1159 1061 1159 1060 1160 967 1160 966 1160 1059 1161 1061 1161 1062 1161 1063 1162 1060 1162 964 1162 1062 1163 1061 1163 1064 1163 1060 1164 966 1164 964 1164 1062 1165 1064 1165 1065 1165 1063 1166 964 1166 962 1166 1063 1167 962 1167 1028 1167 1062 1168 1065 1168 1066 1168 1028 1169 962 1169 965 1169 1062 1170 1066 1170 1067 1170 1062 1171 1067 1171 1068 1171 1062 1172 1068 1172 1069 1172 1068 1173 1070 1173 1069 1173 1069 1174 1070 1174 1071 1174 1069 1175 1071 1175 1072 1175 1069 1176 1072 1176 1073 1176 1073 1177 1072 1177 1074 1177 1025 1178 1073 1178 1027 1178 1073 1179 1074 1179 1027 1179 1075 1180 1076 1180 1077 1180 1078 1181 1079 1181 1080 1181 1078 1182 1080 1182 1081 1182 1078 1183 1081 1183 1082 1183 1078 1184 1082 1184 1083 1184 1078 1185 1083 1185 1084 1185 1085 1186 1086 1186 1087 1186 1085 1187 1088 1187 1086 1187 1089 1188 1085 1188 1087 1188 1089 1189 1087 1189 1076 1189 1090 1190 1091 1190 1088 1190 1092 1191 1079 1191 1078 1191 1092 1192 1078 1192 1084 1192 1093 1193 1091 1193 1090 1193 1093 1194 1094 1194 1091 1194 1093 1195 1084 1195 1094 1195 1095 1196 1089 1196 1076 1196 1095 1197 1076 1197 1075 1197 1096 1198 1088 1198 1085 1198 1096 1199 1090 1199 1088 1199 1097 1200 1077 1200 1098 1200 1097 1201 1095 1201 1075 1201 1097 1202 1075 1202 1077 1202 1099 1203 1096 1203 1085 1203 1099 1204 1085 1204 1089 1204 1100 1205 1079 1205 1092 1205 1100 1206 1092 1206 1084 1206 1100 1207 1084 1207 1093 1207 1100 1208 1101 1208 1079 1208 1102 1209 1100 1209 1093 1209 1102 1210 1093 1210 1090 1210 1103 1211 1099 1211 1089 1211 1103 1212 1089 1212 1095 1212 1104 1213 1095 1213 1097 1213 1104 1214 1103 1214 1095 1214 1105 1215 1102 1215 1090 1215 1105 1216 1090 1216 1096 1216 1106 1217 1096 1217 1099 1217 1106 1218 1105 1218 1096 1218 1107 1219 1100 1219 1102 1219 1107 1220 1101 1220 1100 1220 1108 1221 1099 1221 1103 1221 1108 1222 1106 1222 1099 1222 1109 1223 1098 1223 1110 1223 1109 1224 1104 1224 1097 1224 1109 1225 1097 1225 1098 1225 1111 1226 1107 1226 1102 1226 1111 1227 1102 1227 1105 1227 1111 1228 1112 1228 1101 1228 1111 1229 1101 1229 1107 1229 1113 1230 1108 1230 1103 1230 1113 1231 1103 1231 1104 1231 1114 1232 1105 1232 1106 1232 1114 1233 1111 1233 1105 1233 1115 1234 1106 1234 1108 1234 1115 1235 1114 1235 1106 1235 1116 1236 1113 1236 1104 1236 1116 1237 1104 1237 1109 1237 1117 1238 1108 1238 1113 1238 1117 1239 1115 1239 1108 1239 1118 1240 1112 1240 1111 1240 1118 1241 1111 1241 1114 1241 1119 1242 1120 1242 1121 1242 1119 1243 1110 1243 1120 1243 1119 1244 1109 1244 1110 1244 1122 1245 1123 1245 1112 1245 1122 1246 1112 1246 1118 1246 1122 1247 1114 1247 1115 1247 1122 1248 1118 1248 1114 1248 1124 1249 1113 1249 1116 1249 1124 1250 1117 1250 1113 1250 1125 1251 1115 1251 1117 1251 1125 1252 1122 1252 1115 1252 1126 1253 1116 1253 1109 1253 1126 1254 1109 1254 1119 1254 1127 1255 1117 1255 1124 1255 1127 1256 1125 1256 1117 1256 1128 1257 1123 1257 1122 1257 1128 1258 1122 1258 1125 1258 1129 1259 1119 1259 1121 1259 1130 1260 1124 1260 1116 1260 1130 1261 1116 1261 1126 1261 1131 1262 1121 1262 1132 1262 1131 1263 1129 1263 1121 1263 1133 1264 1125 1264 1127 1264 1133 1265 1128 1265 1125 1265 1134 1266 1126 1266 1119 1266 1134 1267 1119 1267 1129 1267 1135 1268 1124 1268 1130 1268 1135 1269 1127 1269 1124 1269 1136 1270 1129 1270 1131 1270 1136 1271 1134 1271 1129 1271 1137 1272 1131 1272 1132 1272 1137 1273 1136 1273 1131 1273 1138 1274 1128 1274 1133 1274 1138 1275 1139 1275 1123 1275 1138 1276 1123 1276 1128 1276 1140 1277 1130 1277 1126 1277 1140 1278 1126 1278 1134 1278 1141 1279 1132 1279 1142 1279 1141 1280 1137 1280 1132 1280 1143 1281 1127 1281 1135 1281 1143 1282 1133 1282 1127 1282 1144 1283 1140 1283 1134 1283 1144 1284 1134 1284 1136 1284 1145 1285 1136 1285 1137 1285 1145 1286 1137 1286 1141 1286 1145 1287 1144 1287 1136 1287 1146 1288 1143 1288 1135 1288 1146 1289 1130 1289 1140 1289 1146 1290 1135 1290 1130 1290 1147 1291 1141 1291 1142 1291 1148 1292 1139 1292 1138 1292 1148 1293 1133 1293 1143 1293 1148 1294 1149 1294 1139 1294 1148 1295 1138 1295 1133 1295 1150 1296 1145 1296 1141 1296 1150 1297 1141 1297 1147 1297 1151 1298 1146 1298 1140 1298 1151 1299 1140 1299 1144 1299 1152 1300 1144 1300 1145 1300 1152 1301 1151 1301 1144 1301 1152 1302 1145 1302 1150 1302 1153 1303 1143 1303 1146 1303 1154 1304 1142 1304 1155 1304 1154 1305 1147 1305 1142 1305 1156 1306 1150 1306 1147 1306 1156 1307 1147 1307 1154 1307 1157 1308 1152 1308 1150 1308 1157 1309 1150 1309 1156 1309 1158 1310 1153 1310 1146 1310 1158 1311 1146 1311 1151 1311 1159 1312 1151 1312 1152 1312 1159 1313 1158 1313 1151 1313 1159 1314 1152 1314 1157 1314 1160 1315 1154 1315 1155 1315 1161 1316 1148 1316 1143 1316 1161 1317 1149 1317 1148 1317 1161 1318 1162 1318 1149 1318 1161 1319 1143 1319 1153 1319 1163 1320 1164 1320 1165 1320 1166 1321 1156 1321 1154 1321 1163 1322 1167 1322 1164 1322 1168 1323 1157 1323 1156 1323 1169 1324 1163 1324 1165 1324 1168 1325 1156 1325 1166 1325 1170 1326 1163 1326 1169 1326 1171 1327 1157 1327 1168 1327 1170 1328 1167 1328 1163 1328 1171 1329 1159 1329 1157 1329 1172 1330 1153 1330 1158 1330 1170 1331 1173 1331 1167 1331 1172 1332 1162 1332 1161 1332 1172 1333 1161 1333 1153 1333 1174 1334 1158 1334 1159 1334 1175 1335 1165 1335 1176 1335 1175 1336 1169 1336 1165 1336 1174 1337 1172 1337 1158 1337 1177 1338 1170 1338 1169 1338 1178 1339 1166 1339 1154 1339 1178 1340 1154 1340 1160 1340 1177 1341 1169 1341 1175 1341 1179 1342 1170 1342 1177 1342 1180 1343 1155 1343 1181 1343 1180 1344 1178 1344 1160 1344 1180 1345 1160 1345 1155 1345 1179 1346 950 1346 946 1346 1179 1347 946 1347 1173 1347 1179 1348 1173 1348 1170 1348 1182 1349 1168 1349 1166 1349 1183 1350 1177 1350 1175 1350 1184 1351 1168 1351 1182 1351 1184 1352 1171 1352 1168 1352 1185 1353 1171 1353 1184 1353 1186 1354 1175 1354 1176 1354 1185 1355 1159 1355 1171 1355 1187 1356 1179 1356 1177 1356 1185 1357 1174 1357 1159 1357 1188 1358 1180 1358 1181 1358 1187 1359 1177 1359 1183 1359 1189 1360 1179 1360 1187 1360 1189 1361 950 1361 1179 1361 1190 1362 1174 1362 1185 1362 1189 1363 953 1363 950 1363 1190 1364 1191 1364 1162 1364 1190 1365 1162 1365 1172 1365 1192 1366 1187 1366 1183 1366 1190 1367 1172 1367 1174 1367 1193 1368 1182 1368 1166 1368 1194 1369 1175 1369 1186 1369 1193 1370 1166 1370 1178 1370 1195 1371 1180 1371 1188 1371 1194 1372 1183 1372 1175 1372 1195 1373 1193 1373 1178 1373 1195 1374 1178 1374 1180 1374 1196 1375 1176 1375 1197 1375 1196 1376 1194 1376 1186 1376 1198 1377 1184 1377 1182 1377 1196 1378 1186 1378 1176 1378 1199 1379 953 1379 1189 1379 1199 1380 1187 1380 1192 1380 1200 1381 1190 1381 1185 1381 1199 1382 919 1382 953 1382 1200 1383 1191 1383 1190 1383 1199 1384 1189 1384 1187 1384 1201 1385 1200 1385 1185 1385 1201 1386 1185 1386 1184 1386 1202 1387 1196 1387 1197 1387 1203 1388 919 1388 1199 1388 1203 1389 1199 1389 1192 1389 1204 1390 1195 1390 1188 1390 1205 1391 1198 1391 1182 1391 1206 1392 1183 1392 1194 1392 1205 1393 1182 1393 1193 1393 1206 1394 1192 1394 1183 1394 1207 1395 1181 1395 1208 1395 1207 1396 1188 1396 1181 1396 1209 1397 1206 1397 1194 1397 1210 1398 1193 1398 1195 1398 1209 1399 1194 1399 1196 1399 1209 1400 1196 1400 1202 1400 1211 1401 1209 1401 1202 1401 1210 1402 1205 1402 1193 1402 1210 1403 1195 1403 1204 1403 1212 1404 1200 1404 1201 1404 1212 1405 1191 1405 1200 1405 1212 1406 1213 1406 1191 1406 1214 1407 1202 1407 1197 1407 1215 1408 1184 1408 1198 1408 1214 1409 1197 1409 1216 1409 1215 1410 1201 1410 1184 1410 1214 1411 1211 1411 1202 1411 1217 1412 1210 1412 1204 1412 1218 1413 923 1413 918 1413 1218 1414 918 1414 919 1414 1218 1415 919 1415 1203 1415 1219 1416 1203 1416 1192 1416 1219 1417 1192 1417 1206 1417 1220 1418 1204 1418 1188 1418 1220 1419 1188 1419 1207 1419 1221 1420 1219 1420 1206 1420 1221 1421 1209 1421 1211 1421 1221 1422 1206 1422 1209 1422 1222 1423 1198 1423 1205 1423 1222 1424 1215 1424 1198 1424 1223 1425 1205 1425 1210 1425 1223 1426 1222 1426 1205 1426 1224 1427 1221 1427 1211 1427 1225 1428 1211 1428 1214 1428 1223 1429 1210 1429 1217 1429 1226 1430 1201 1430 1215 1430 1226 1431 1212 1431 1201 1431 1226 1432 1213 1432 1212 1432 1225 1433 1224 1433 1211 1433 1227 1434 1219 1434 1221 1434 1227 1435 1221 1435 1224 1435 1228 1436 1223 1436 1217 1436 1229 1437 1218 1437 1203 1437 1229 1438 1203 1438 1219 1438 1230 1439 1208 1439 1231 1439 1229 1440 923 1440 1218 1440 1230 1441 1207 1441 1208 1441 1232 1442 1227 1442 1224 1442 1233 1443 1226 1443 1215 1443 1233 1444 1234 1444 1213 1444 1233 1445 1215 1445 1222 1445 1235 1446 1214 1446 1216 1446 1233 1447 1213 1447 1226 1447 1236 1448 1204 1448 1220 1448 1236 1449 1217 1449 1204 1449 1235 1450 1216 1450 1237 1450 1236 1451 1228 1451 1217 1451 1238 1452 1232 1452 1224 1452 1238 1453 1224 1453 1225 1453 1239 1454 1222 1454 1223 1454 1239 1455 1223 1455 1228 1455 1240 1456 923 1456 1229 1456 1240 1457 1241 1457 930 1457 1240 1458 930 1458 926 1458 1240 1459 926 1459 923 1459 1242 1460 1240 1460 1229 1460 1243 1461 1239 1461 1228 1461 1242 1462 1229 1462 1219 1462 1244 1463 1220 1463 1207 1463 1242 1464 1219 1464 1227 1464 1244 1465 1207 1465 1230 1465 1245 1466 1227 1466 1232 1466 1245 1467 1242 1467 1227 1467 1246 1468 1228 1468 1236 1468 1246 1469 1243 1469 1228 1469 1247 1470 1222 1470 1239 1470 1247 1471 1234 1471 1233 1471 1248 1472 1214 1472 1235 1472 1247 1473 1233 1473 1222 1473 1248 1474 1225 1474 1214 1474 1247 1475 1239 1475 1243 1475 1249 1476 1232 1476 1238 1476 1249 1477 1245 1477 1232 1477 1250 1478 1251 1478 1252 1478 1250 1479 1231 1479 1251 1479 1250 1480 1230 1480 1231 1480 1253 1481 1240 1481 1242 1481 1253 1482 1242 1482 1245 1482 1254 1483 1255 1483 1234 1483 1253 1484 1241 1484 1240 1484 1254 1485 1234 1485 1247 1485 1256 1486 1235 1486 1237 1486 1254 1487 1247 1487 1243 1487 1256 1488 1257 1488 1258 1488 1256 1489 1237 1489 1257 1489 1259 1490 1236 1490 1220 1490 1259 1491 1220 1491 1244 1491 1260 1492 1261 1492 1241 1492 1260 1493 1253 1493 1245 1493 1260 1494 1241 1494 1253 1494 1262 1495 1243 1495 1246 1495 1263 1496 1238 1496 1225 1496 1263 1497 1225 1497 1248 1497 1264 1498 1230 1498 1250 1498 1264 1499 1244 1499 1230 1499 1265 1500 1245 1500 1249 1500 1265 1501 1260 1501 1245 1501 1266 1502 1236 1502 1259 1502 1267 1503 1235 1503 1256 1503 1266 1504 1246 1504 1236 1504 1268 1505 1255 1505 1254 1505 1267 1506 1248 1506 1235 1506 1268 1507 1254 1507 1243 1507 1269 1508 1249 1508 1238 1508 1268 1509 1243 1509 1262 1509 1269 1510 1238 1510 1263 1510 1270 1511 1264 1511 1250 1511 1269 1512 1265 1512 1249 1512 1270 1513 1250 1513 1252 1513 1271 1514 1261 1514 1260 1514 1272 1515 1244 1515 1264 1515 1271 1516 1260 1516 1265 1516 1272 1517 1266 1517 1259 1517 1273 1518 1258 1518 1274 1518 1273 1519 1256 1519 1258 1519 1272 1520 1259 1520 1244 1520 1275 1521 1262 1521 1246 1521 1276 1522 1263 1522 1248 1522 1276 1523 1248 1523 1267 1523 1275 1524 1246 1524 1266 1524 1277 1525 1264 1525 1270 1525 1278 1526 1265 1526 1269 1526 1277 1527 1272 1527 1264 1527 1279 1528 1256 1528 1273 1528 1280 1529 1275 1529 1266 1529 1279 1530 1267 1530 1256 1530 1280 1531 1266 1531 1272 1531 1281 1532 1268 1532 1262 1532 1282 1533 1263 1533 1276 1533 1281 1534 1255 1534 1268 1534 1281 1535 1283 1535 1255 1535 1282 1536 1269 1536 1263 1536 1281 1537 1262 1537 1275 1537 1282 1538 1278 1538 1269 1538 1284 1539 1252 1539 1285 1539 1286 1540 1287 1540 1261 1540 1286 1541 1271 1541 1265 1541 1284 1542 1270 1542 1252 1542 1286 1543 1261 1543 1271 1543 1286 1544 1265 1544 1278 1544 1288 1545 1280 1545 1272 1545 1289 1546 1273 1546 1274 1546 1288 1547 1272 1547 1277 1547 1290 1548 1285 1548 1291 1548 1290 1549 1284 1549 1285 1549 1292 1550 1276 1550 1267 1550 1292 1551 1267 1551 1279 1551 1293 1552 1274 1552 1294 1552 1293 1553 1289 1553 1274 1553 1295 1554 1275 1554 1280 1554 1296 1555 1277 1555 1270 1555 1296 1556 1270 1556 1284 1556 1297 1557 1278 1557 1282 1557 1298 1558 1279 1558 1273 1558 1299 1559 1280 1559 1288 1559 1298 1560 1273 1560 1289 1560 1299 1561 1295 1561 1280 1561 1298 1562 1289 1562 1293 1562 1300 1563 1297 1563 1282 1563 1300 1564 1282 1564 1276 1564 1300 1565 1276 1565 1292 1565 1301 1566 1296 1566 1284 1566 1301 1567 1284 1567 1290 1567 1302 1568 1298 1568 1293 1568 1303 1569 1290 1569 1291 1569 1304 1570 1283 1570 1281 1570 1305 1571 1293 1571 1294 1571 1304 1572 1275 1572 1295 1572 1306 1573 1287 1573 1286 1573 1304 1574 1307 1574 1283 1574 1306 1575 1308 1575 1287 1575 1304 1576 1281 1576 1275 1576 1306 1577 1286 1577 1278 1577 1306 1578 1278 1578 1297 1578 1309 1579 1277 1579 1296 1579 1310 1580 1298 1580 1302 1580 1309 1581 1288 1581 1277 1581 1310 1582 1279 1582 1298 1582 1310 1583 1292 1583 1279 1583 1311 1584 1305 1584 1294 1584 1312 1585 1304 1585 1295 1585 1312 1586 1295 1586 1299 1586 1311 1587 1294 1587 1313 1587 1314 1588 1291 1588 1315 1588 1314 1589 1303 1589 1291 1589 1316 1590 1297 1590 1300 1590 1317 1591 1309 1591 1296 1591 1318 1592 1310 1592 1302 1592 1317 1593 1296 1593 1301 1593 1319 1594 1302 1594 1293 1594 1320 1595 1301 1595 1290 1595 1320 1596 1290 1596 1303 1596 1320 1597 1303 1597 1314 1597 1319 1598 1305 1598 1311 1598 1319 1599 1293 1599 1305 1599 1321 1600 1292 1600 1310 1600 1321 1601 1316 1601 1300 1601 1322 1602 1288 1602 1309 1602 1321 1603 1310 1603 1318 1603 1321 1604 1300 1604 1292 1604 1322 1605 1299 1605 1288 1605 1323 1606 1314 1606 1315 1606 1324 1607 1311 1607 1313 1607 1325 1608 1306 1608 1297 1608 1326 1609 1307 1609 1304 1609 1326 1610 1327 1610 1307 1610 1325 1611 1328 1611 1308 1611 1326 1612 1304 1612 1312 1612 1325 1613 1297 1613 1316 1613 1325 1614 1308 1614 1306 1614 1329 1615 1319 1615 1311 1615 1330 1616 1320 1616 1314 1616 1330 1617 1314 1617 1323 1617 1331 1618 1322 1618 1309 1618 1332 1619 1321 1619 1318 1619 1331 1620 1309 1620 1317 1620 1333 1621 1302 1621 1319 1621 1333 1622 1318 1622 1302 1622 1333 1623 1319 1623 1329 1623 1334 1624 1301 1624 1320 1624 1334 1625 1317 1625 1301 1625 1334 1626 1320 1626 1330 1626 1335 1627 1316 1627 1321 1627 1336 1628 1315 1628 1337 1628 1336 1629 1337 1629 1338 1629 1336 1630 1323 1630 1315 1630 1339 1631 1313 1631 1340 1631 1339 1632 1324 1632 1313 1632 1341 1633 1312 1633 1299 1633 1342 1634 1324 1634 1339 1634 1341 1635 1299 1635 1322 1635 1342 1636 1311 1636 1324 1636 1342 1637 1329 1637 1311 1637 1343 1638 1330 1638 1323 1638 1343 1639 1323 1639 1336 1639 1344 1640 1333 1640 1329 1640 1345 1641 1334 1641 1330 1641 1082 1642 1335 1642 1321 1642 1345 1643 1330 1643 1343 1643 1082 1644 1321 1644 1332 1644 1346 1645 1331 1645 1317 1645 1346 1646 1317 1646 1334 1646 1347 1647 1332 1647 1318 1647 1347 1648 1333 1648 1344 1648 1346 1649 1334 1649 1345 1649 1347 1650 1082 1650 1332 1650 1348 1651 1322 1651 1331 1651 1347 1652 1318 1652 1333 1652 1348 1653 1341 1653 1322 1653 1349 1654 1339 1654 1340 1654 1350 1655 1338 1655 1351 1655 1352 1656 1325 1656 1316 1656 1350 1657 1336 1657 1338 1657 1352 1658 1316 1658 1335 1658 1350 1659 1343 1659 1336 1659 1352 1660 1328 1660 1325 1660 1353 1661 1326 1661 1312 1661 1352 1662 1335 1662 1082 1662 1353 1663 1312 1663 1341 1663 1352 1664 1080 1664 1328 1664 1353 1665 1354 1665 1327 1665 1353 1666 1327 1666 1326 1666 1086 1667 1342 1667 1339 1667 1355 1668 1343 1668 1350 1668 1355 1669 1345 1669 1343 1669 1356 1670 1329 1670 1342 1670 1357 1671 1345 1671 1355 1671 1356 1672 1344 1672 1329 1672 1356 1673 1342 1673 1086 1673 1357 1674 1346 1674 1345 1674 1094 1675 1347 1675 1344 1675 1358 1676 1354 1676 1353 1676 1358 1677 1353 1677 1341 1677 1358 1678 1341 1678 1348 1678 1081 1679 1352 1679 1082 1679 1081 1680 1080 1680 1352 1680 1083 1681 1082 1681 1347 1681 1083 1682 1347 1682 1094 1682 1359 1683 1348 1683 1331 1683 1359 1684 1331 1684 1346 1684 1360 1685 1351 1685 862 1685 1360 1686 862 1686 856 1686 1360 1687 856 1687 850 1687 1360 1688 1355 1688 1350 1688 1087 1689 1339 1689 1349 1689 1360 1690 1350 1690 1351 1690 1087 1691 1086 1691 1339 1691 1361 1692 1355 1692 1360 1692 1361 1693 851 1693 1357 1693 1361 1694 850 1694 851 1694 1076 1695 1340 1695 1077 1695 1361 1696 1357 1696 1355 1696 1361 1697 1360 1697 850 1697 1076 1698 1087 1698 1349 1698 1362 1699 1357 1699 851 1699 1362 1700 1346 1700 1357 1700 1076 1701 1349 1701 1340 1701 1362 1702 851 1702 904 1702 1088 1703 1356 1703 1086 1703 1362 1704 1359 1704 1346 1704 1363 1705 1354 1705 1358 1705 1363 1706 1348 1706 1359 1706 1363 1707 1358 1707 1348 1707 1363 1708 1359 1708 1362 1708 1091 1709 1344 1709 1356 1709 1363 1710 897 1710 894 1710 1363 1711 894 1711 1354 1711 1091 1712 1094 1712 1344 1712 1364 1713 1362 1713 904 1713 1364 1714 897 1714 1363 1714 1091 1715 1356 1715 1088 1715 1364 1716 904 1716 899 1716 1364 1717 899 1717 897 1717 1364 1718 1363 1718 1362 1718 1084 1719 1083 1719 1094 1719 1365 1720 1366 1720 1367 1720 1365 1721 1368 1721 1366 1721 1369 1722 1370 1722 1371 1722 1372 1723 1367 1723 1373 1723 1372 1724 1365 1724 1367 1724 1374 1725 1371 1725 1375 1725 1374 1726 1369 1726 1371 1726 1376 1727 1373 1727 1370 1727 1376 1728 1372 1728 1373 1728 1377 1729 1375 1729 1378 1729 1377 1730 1374 1730 1375 1730 1369 1731 1376 1731 1370 1731 1379 1732 1378 1732 1380 1732 1379 1733 1377 1733 1378 1733 1381 1734 1380 1734 1382 1734 1381 1735 1379 1735 1380 1735 1383 1736 1382 1736 1384 1736 1383 1737 1381 1737 1382 1737 1385 1738 1384 1738 1386 1738 1385 1739 1383 1739 1384 1739 1387 1740 1386 1740 1388 1740 1387 1741 1385 1741 1386 1741 1389 1742 1388 1742 1390 1742 1389 1743 1387 1743 1388 1743 1391 1744 1390 1744 1392 1744 1391 1745 1389 1745 1390 1745 1393 1746 1392 1746 1394 1746 1393 1747 1391 1747 1392 1747 1395 1748 1393 1748 1394 1748 1395 1749 1394 1749 1396 1749 1397 1750 1395 1750 1396 1750 1397 1751 1396 1751 1398 1751 1399 1752 1397 1752 1398 1752 1399 1753 1398 1753 1400 1753 1401 1754 1399 1754 1400 1754 1401 1755 1400 1755 1402 1755 1403 1756 1401 1756 1402 1756 1403 1757 1402 1757 1404 1757 1405 1758 1404 1758 1406 1758 1405 1759 1403 1759 1404 1759 1407 1760 1406 1760 1408 1760 1407 1761 1405 1761 1406 1761 1409 1762 1408 1762 1410 1762 1409 1763 1407 1763 1408 1763 1411 1764 1410 1764 1412 1764 1411 1765 1409 1765 1410 1765 1413 1766 1412 1766 1414 1766 1413 1767 1411 1767 1412 1767 1368 1768 1414 1768 1366 1768 1368 1769 1413 1769 1414 1769 1415 1770 1416 1770 1409 1770 1417 1771 1411 1771 1413 1771 1417 1772 1415 1772 1411 1772 1418 1773 1413 1773 1368 1773 1419 1774 1369 1774 1374 1774 1418 1775 1417 1775 1413 1775 1419 1776 1420 1776 1369 1776 1421 1777 1368 1777 1365 1777 1421 1778 1418 1778 1368 1778 1422 1779 1374 1779 1377 1779 1422 1780 1419 1780 1374 1780 1423 1781 1365 1781 1372 1781 1423 1782 1421 1782 1365 1782 1424 1783 1377 1783 1379 1783 1424 1784 1422 1784 1377 1784 1425 1785 1372 1785 1376 1785 1425 1786 1423 1786 1372 1786 1426 1787 1379 1787 1381 1787 1420 1788 1376 1788 1369 1788 1426 1789 1424 1789 1379 1789 1420 1790 1425 1790 1376 1790 1427 1791 1381 1791 1383 1791 1427 1792 1426 1792 1381 1792 1428 1793 1383 1793 1385 1793 1428 1794 1427 1794 1383 1794 1429 1795 1385 1795 1387 1795 1429 1796 1428 1796 1385 1796 1430 1797 1387 1797 1389 1797 1430 1798 1429 1798 1387 1798 1431 1799 1389 1799 1391 1799 1431 1800 1430 1800 1389 1800 1432 1801 1391 1801 1393 1801 1432 1802 1431 1802 1391 1802 1433 1803 1393 1803 1395 1803 1433 1804 1432 1804 1393 1804 1434 1805 1433 1805 1395 1805 1434 1806 1395 1806 1397 1806 1435 1807 1434 1807 1397 1807 1435 1808 1397 1808 1399 1808 1436 1809 1435 1809 1399 1809 1436 1810 1399 1810 1401 1810 1437 1811 1401 1811 1403 1811 1437 1812 1436 1812 1401 1812 1438 1813 1403 1813 1405 1813 1438 1814 1437 1814 1403 1814 1439 1815 1405 1815 1407 1815 1439 1816 1438 1816 1405 1816 1416 1817 1407 1817 1409 1817 1416 1818 1439 1818 1407 1818 1415 1819 1409 1819 1411 1819 1440 1820 1441 1820 1442 1820 1440 1821 1442 1821 1443 1821 1440 1822 1444 1822 1441 1822 1445 1823 1440 1823 1443 1823 1446 1824 1447 1824 1448 1824 1449 1825 1443 1825 1450 1825 1446 1826 1451 1826 1447 1826 1449 1827 1445 1827 1443 1827 1452 1828 1448 1828 1453 1828 1454 1829 1450 1829 1455 1829 1454 1830 1455 1830 1456 1830 1452 1831 1446 1831 1448 1831 1454 1832 1449 1832 1450 1832 1457 1833 1453 1833 1458 1833 1459 1834 1454 1834 1456 1834 1457 1835 1452 1835 1453 1835 1451 1836 1456 1836 1447 1836 1451 1837 1459 1837 1456 1837 1460 1838 1458 1838 1461 1838 1460 1839 1461 1839 1462 1839 1460 1840 1457 1840 1458 1840 1463 1841 1460 1841 1462 1841 1464 1842 1462 1842 1465 1842 1464 1843 1463 1843 1462 1843 1466 1844 1465 1844 1467 1844 1466 1845 1464 1845 1465 1845 1468 1846 1467 1846 1469 1846 1468 1847 1466 1847 1467 1847 1470 1848 1469 1848 1471 1848 1470 1849 1468 1849 1469 1849 1472 1850 1471 1850 1473 1850 1472 1851 1470 1851 1471 1851 1474 1852 1473 1852 1475 1852 1474 1853 1472 1853 1473 1853 1476 1854 1474 1854 1475 1854 1476 1855 1475 1855 1477 1855 1476 1856 1477 1856 1478 1856 1479 1857 1476 1857 1478 1857 1479 1858 1478 1858 1480 1858 1481 1859 1479 1859 1480 1859 1481 1860 1480 1860 1482 1860 1483 1861 1481 1861 1482 1861 1484 1862 1482 1862 1485 1862 1484 1863 1483 1863 1482 1863 1486 1864 1485 1864 1487 1864 1486 1865 1487 1865 1488 1865 1486 1866 1484 1866 1485 1866 1489 1867 1486 1867 1488 1867 1444 1868 1488 1868 1441 1868 1444 1869 1489 1869 1488 1869 1490 1870 1491 1870 1492 1870 1490 1871 1493 1871 1491 1871 1494 1872 1492 1872 1495 1872 1496 1873 1497 1873 1498 1873 1494 1874 1495 1874 1499 1874 1494 1875 1490 1875 1492 1875 1500 1876 1498 1876 1501 1876 1502 1877 1494 1877 1499 1877 1500 1878 1496 1878 1498 1878 1503 1879 1499 1879 1504 1879 1503 1880 1504 1880 1505 1880 1503 1881 1502 1881 1499 1881 1506 1882 1500 1882 1501 1882 1507 1883 1503 1883 1505 1883 1508 1884 1501 1884 1509 1884 1508 1885 1509 1885 1510 1885 1508 1886 1506 1886 1501 1886 1496 1887 1505 1887 1497 1887 1496 1888 1507 1888 1505 1888 1511 1889 1508 1889 1510 1889 1512 1890 1510 1890 1513 1890 1512 1891 1513 1891 1514 1891 1512 1892 1511 1892 1510 1892 1515 1893 1512 1893 1514 1893 1516 1894 1514 1894 1517 1894 1516 1895 1515 1895 1514 1895 1518 1896 1517 1896 1519 1896 1518 1897 1516 1897 1517 1897 1520 1898 1519 1898 1521 1898 1520 1899 1521 1899 1522 1899 1520 1900 1518 1900 1519 1900 1523 1901 1520 1901 1522 1901 1524 1902 1522 1902 1525 1902 1524 1903 1523 1903 1522 1903 1526 1904 1524 1904 1525 1904 1526 1905 1525 1905 1527 1905 1526 1906 1527 1906 1528 1906 1529 1907 1526 1907 1528 1907 1530 1908 1529 1908 1528 1908 1530 1909 1528 1909 1531 1909 1532 1910 1531 1910 1533 1910 1532 1911 1530 1911 1531 1911 1534 1912 1533 1912 1535 1912 1534 1913 1535 1913 1536 1913 1534 1914 1532 1914 1533 1914 1537 1915 1534 1915 1536 1915 1538 1916 1536 1916 1539 1916 1538 1917 1539 1917 1491 1917 1538 1918 1537 1918 1536 1918 1493 1919 1538 1919 1491 1919 1540 1920 1541 1920 1542 1920 1543 1921 1544 1921 1545 1921 1544 1922 1546 1922 1545 1922 1547 1923 1548 1923 1549 1923 1548 1924 1540 1924 1549 1924 1540 1925 1542 1925 1549 1925 1550 1926 1543 1926 1551 1926 1543 1927 1545 1927 1551 1927 1552 1928 1547 1928 1553 1928 1547 1929 1549 1929 1553 1929 1554 1930 1552 1930 1555 1930 1552 1931 1553 1931 1555 1931 1556 1932 1550 1932 1557 1932 1550 1933 1551 1933 1557 1933 1556 1934 1557 1934 1558 1934 1554 1935 1555 1935 1559 1935 1560 1936 1554 1936 1561 1936 1562 1937 1556 1937 1563 1937 1554 1938 1559 1938 1561 1938 1556 1939 1558 1939 1563 1939 1562 1940 1563 1940 1564 1940 1565 1941 1560 1941 1566 1941 1560 1942 1561 1942 1566 1942 1567 1943 1562 1943 1568 1943 1562 1944 1564 1944 1568 1944 1565 1945 1566 1945 1569 1945 1570 1946 1565 1946 1571 1946 1567 1947 1568 1947 1572 1947 1565 1948 1569 1948 1571 1948 1567 1949 1572 1949 1573 1949 1574 1950 1570 1950 1575 1950 1576 1951 1567 1951 1573 1951 1570 1952 1571 1952 1575 1952 1576 1953 1573 1953 1577 1953 1574 1954 1575 1954 1578 1954 1579 1955 1574 1955 1580 1955 1581 1956 1576 1956 1582 1956 1576 1957 1577 1957 1582 1957 1574 1958 1578 1958 1580 1958 1583 1959 1581 1959 1584 1959 1585 1960 1579 1960 1586 1960 1581 1961 1582 1961 1584 1961 1579 1962 1580 1962 1586 1962 1583 1963 1584 1963 1587 1963 1588 1964 1585 1964 1589 1964 1585 1965 1586 1965 1589 1965 1590 1966 1583 1966 1591 1966 1583 1967 1587 1967 1591 1967 1588 1968 1589 1968 1592 1968 1593 1969 1588 1969 1594 1969 1595 1970 1590 1970 1596 1970 1590 1971 1591 1971 1596 1971 1588 1972 1592 1972 1594 1972 1595 1973 1596 1973 1597 1973 1595 1974 1597 1974 1598 1974 1544 1975 1593 1975 1599 1975 1593 1976 1594 1976 1599 1976 1598 1977 1597 1977 1600 1977 1544 1978 1599 1978 1546 1978 1601 1979 1598 1979 1602 1979 1598 1980 1600 1980 1602 1980 1601 1981 1602 1981 1603 1981 1548 1982 1601 1982 1604 1982 1601 1983 1603 1983 1604 1983 1548 1984 1604 1984 1605 1984 1548 1985 1605 1985 1540 1985 1606 1986 1607 1986 1608 1986 1607 1987 1609 1987 1608 1987 1606 1988 1608 1988 1610 1988 1611 1989 1612 1989 1613 1989 1606 1990 1610 1990 1614 1990 1612 1991 1615 1991 1613 1991 1614 1992 1610 1992 1616 1992 1617 1993 1611 1993 1618 1993 1614 1994 1616 1994 1619 1994 1611 1995 1613 1995 1618 1995 1619 1996 1616 1996 1620 1996 1617 1997 1618 1997 1621 1997 1619 1998 1620 1998 1622 1998 1622 1999 1620 1999 1623 1999 1624 2000 1617 2000 1625 2000 1617 2001 1621 2001 1625 2001 1626 2002 1622 2002 1627 2002 1622 2003 1623 2003 1627 2003 1628 2004 1624 2004 1629 2004 1624 2005 1625 2005 1629 2005 1626 2006 1627 2006 1630 2006 1631 2007 1628 2007 1632 2007 1628 2008 1629 2008 1632 2008 1633 2009 1626 2009 1634 2009 1626 2010 1630 2010 1634 2010 1631 2011 1632 2011 1635 2011 1633 2012 1634 2012 1636 2012 1637 2013 1631 2013 1638 2013 1631 2014 1635 2014 1638 2014 1633 2015 1636 2015 1639 2015 1640 2016 1633 2016 1641 2016 1633 2017 1639 2017 1641 2017 1642 2018 1637 2018 1643 2018 1637 2019 1638 2019 1643 2019 1644 2020 1640 2020 1645 2020 1640 2021 1641 2021 1645 2021 1642 2022 1643 2022 1646 2022 1647 2023 1642 2023 1646 2023 1612 2024 1644 2024 1648 2024 1644 2025 1645 2025 1648 2025 1647 2026 1646 2026 1649 2026 1612 2027 1648 2027 1615 2027 1650 2028 1647 2028 1651 2028 1647 2029 1649 2029 1651 2029 1650 2030 1651 2030 1652 2030 1653 2031 1650 2031 1652 2031 1654 2032 1653 2032 1652 2032 1655 2033 1654 2033 1656 2033 1654 2034 1652 2034 1656 2034 1655 2035 1656 2035 1657 2035 1658 2036 1655 2036 1659 2036 1655 2037 1657 2037 1659 2037 1657 2038 1656 2038 1660 2038 1658 2039 1659 2039 1661 2039 1658 2040 1661 2040 1662 2040 1660 2041 1656 2041 1663 2041 1664 2042 1658 2042 1665 2042 1658 2043 1662 2043 1665 2043 1664 2044 1665 2044 1666 2044 1667 2045 1664 2045 1668 2045 1664 2046 1666 2046 1668 2046 1607 2047 1667 2047 1609 2047 1667 2048 1668 2048 1609 2048 1669 2049 1670 2049 1591 2049 1670 2050 1596 2050 1591 2050 1671 2051 1672 2051 1673 2051 1669 2052 1591 2052 1587 2052 1671 2053 1673 2053 1674 2053 1671 2054 1674 2054 1675 2054 1676 2055 1669 2055 1584 2055 1675 2056 1674 2056 1677 2056 1669 2057 1587 2057 1584 2057 1675 2058 1677 2058 1678 2058 1675 2059 1678 2059 1679 2059 1679 2060 1678 2060 1680 2060 1679 2061 1680 2061 1681 2061 1679 2062 1681 2062 1682 2062 1682 2063 1681 2063 1683 2063 1682 2064 1683 2064 1684 2064 1684 2065 1683 2065 1685 2065 1686 2066 1684 2066 1687 2066 1684 2067 1685 2067 1687 2067 1686 2068 1687 2068 1688 2068 1689 2069 1686 2069 1688 2069 1689 2070 1688 2070 1690 2070 1584 2071 1582 2071 1691 2071 1582 2072 1577 2072 1691 2072 1577 2073 1573 2073 1691 2073 1573 2074 1572 2074 1691 2074 1676 2075 1584 2075 1691 2075 1689 2076 1690 2076 1692 2076 1689 2077 1692 2077 1693 2077 1694 2078 1676 2078 1695 2078 1676 2079 1691 2079 1695 2079 1693 2080 1692 2080 1696 2080 1697 2081 1694 2081 1698 2081 1699 2082 1693 2082 1696 2082 1694 2083 1695 2083 1698 2083 1700 2084 1699 2084 1701 2084 1702 2085 1697 2085 1703 2085 1699 2086 1696 2086 1701 2086 1697 2087 1698 2087 1703 2087 1702 2088 1703 2088 1704 2088 1705 2089 1700 2089 1706 2089 1700 2090 1701 2090 1706 2090 1702 2091 1704 2091 1707 2091 1707 2092 1704 2092 1708 2092 1709 2093 1705 2093 1710 2093 1705 2094 1706 2094 1710 2094 1707 2095 1708 2095 1711 2095 1712 2096 1709 2096 1713 2096 1709 2097 1710 2097 1713 2097 1707 2098 1711 2098 1671 2098 1671 2099 1711 2099 1672 2099 1714 2100 1712 2100 1540 2100 1712 2101 1713 2101 1540 2101 1714 2102 1540 2102 1605 2102 1714 2103 1605 2103 1715 2103 1715 2104 1605 2104 1604 2104 1716 2105 1715 2105 1603 2105 1715 2106 1604 2106 1603 2106 1717 2107 1716 2107 1602 2107 1716 2108 1603 2108 1602 2108 1718 2109 1717 2109 1600 2109 1717 2110 1602 2110 1600 2110 1718 2111 1600 2111 1597 2111 1718 2112 1597 2112 1670 2112 1670 2113 1597 2113 1596 2113 1719 2114 1720 2114 1721 2114 1720 2115 1722 2115 1721 2115 1723 2116 1660 2116 1724 2116 1724 2117 1660 2117 1725 2117 1726 2118 1719 2118 1727 2118 1724 2119 1725 2119 1728 2119 1719 2120 1721 2120 1727 2120 1728 2121 1725 2121 1729 2121 1730 2122 1726 2122 1731 2122 1728 2123 1729 2123 1732 2123 1726 2124 1727 2124 1731 2124 1732 2125 1729 2125 1733 2125 1730 2126 1731 2126 1616 2126 1732 2127 1733 2127 1734 2127 1735 2128 1730 2128 1610 2128 1730 2129 1616 2129 1610 2129 1734 2130 1733 2130 1736 2130 1734 2131 1736 2131 1737 2131 1616 2132 1731 2132 1620 2132 1737 2133 1736 2133 1738 2133 1735 2134 1610 2134 1608 2134 1737 2135 1738 2135 1739 2135 1739 2136 1738 2136 1740 2136 1620 2137 1731 2137 1623 2137 1739 2138 1740 2138 1741 2138 1741 2139 1740 2139 1742 2139 1743 2140 1735 2140 1609 2140 1735 2141 1608 2141 1609 2141 1744 2142 1741 2142 1745 2142 1741 2143 1742 2143 1745 2143 1746 2144 1743 2144 1668 2144 1744 2145 1745 2145 1747 2145 1743 2146 1609 2146 1668 2146 1746 2147 1668 2147 1666 2147 1744 2148 1747 2148 1748 2148 1749 2149 1744 2149 1748 2149 1750 2150 1746 2150 1665 2150 1751 2151 1749 2151 1752 2151 1746 2152 1666 2152 1665 2152 1749 2153 1748 2153 1752 2153 1751 2154 1752 2154 1753 2154 1750 2155 1665 2155 1662 2155 1751 2156 1753 2156 1754 2156 1750 2157 1662 2157 1755 2157 1754 2158 1753 2158 1756 2158 1755 2159 1662 2159 1661 2159 1754 2160 1756 2160 1757 2160 1758 2161 1755 2161 1659 2161 1757 2162 1756 2162 1759 2162 1755 2163 1661 2163 1659 2163 1757 2164 1759 2164 1760 2164 1758 2165 1659 2165 1657 2165 1758 2166 1657 2166 1723 2166 1757 2167 1760 2167 1761 2167 1723 2168 1657 2168 1660 2168 1757 2169 1761 2169 1762 2169 1757 2170 1762 2170 1763 2170 1757 2171 1763 2171 1764 2171 1763 2172 1765 2172 1764 2172 1764 2173 1765 2173 1766 2173 1764 2174 1766 2174 1767 2174 1764 2175 1767 2175 1768 2175 1768 2176 1767 2176 1769 2176 1720 2177 1768 2177 1722 2177 1768 2178 1769 2178 1722 2178 1770 2179 1771 2179 1772 2179 1773 2180 1774 2180 1775 2180 1773 2181 1776 2181 1777 2181 1773 2182 1777 2182 1778 2182 1773 2183 1775 2183 1776 2183 1779 2184 1780 2184 1781 2184 1782 2185 1781 2185 1771 2185 1783 2186 1780 2186 1779 2186 1783 2187 1784 2187 1780 2187 1783 2188 1785 2188 1784 2188 1786 2189 1774 2189 1773 2189 1786 2190 1778 2190 1787 2190 1786 2191 1773 2191 1778 2191 1788 2192 1789 2192 1785 2192 1788 2193 1787 2193 1789 2193 1790 2194 1782 2194 1771 2194 1790 2195 1771 2195 1770 2195 1791 2196 1783 2196 1779 2196 1792 2197 1772 2197 1793 2197 1792 2198 1790 2198 1770 2198 1792 2199 1770 2199 1772 2199 1794 2200 1779 2200 1781 2200 1794 2201 1782 2201 1790 2201 1794 2202 1791 2202 1779 2202 1794 2203 1781 2203 1782 2203 1795 2204 1786 2204 1787 2204 1795 2205 1787 2205 1788 2205 1795 2206 1796 2206 1774 2206 1795 2207 1774 2207 1786 2207 1797 2208 1785 2208 1783 2208 1797 2209 1788 2209 1785 2209 1798 2210 1794 2210 1790 2210 1799 2211 1790 2211 1792 2211 1799 2212 1798 2212 1790 2212 1800 2213 1783 2213 1791 2213 1800 2214 1797 2214 1783 2214 1801 2215 1791 2215 1794 2215 1801 2216 1800 2216 1791 2216 1801 2217 1794 2217 1798 2217 1802 2218 1795 2218 1788 2218 1802 2219 1796 2219 1795 2219 1802 2220 1788 2220 1797 2220 1803 2221 1801 2221 1798 2221 1804 2222 1793 2222 1805 2222 1804 2223 1792 2223 1793 2223 1806 2224 1796 2224 1802 2224 1806 2225 1802 2225 1797 2225 1806 2226 1807 2226 1796 2226 1806 2227 1797 2227 1800 2227 1808 2228 1798 2228 1799 2228 1808 2229 1803 2229 1798 2229 1809 2230 1800 2230 1801 2230 1810 2231 1809 2231 1801 2231 1810 2232 1801 2232 1803 2232 1811 2233 1799 2233 1792 2233 1811 2234 1792 2234 1804 2234 1811 2235 1808 2235 1799 2235 1812 2236 1803 2236 1808 2236 1812 2237 1810 2237 1803 2237 1813 2238 1800 2238 1809 2238 1813 2239 1806 2239 1800 2239 1813 2240 1807 2240 1806 2240 1814 2241 1805 2241 1815 2241 1814 2242 1804 2242 1805 2242 1816 2243 1817 2243 1807 2243 1816 2244 1809 2244 1810 2244 1816 2245 1807 2245 1813 2245 1816 2246 1813 2246 1809 2246 1818 2247 1808 2247 1811 2247 1819 2248 1810 2248 1812 2248 1819 2249 1816 2249 1810 2249 1820 2250 1804 2250 1814 2250 1820 2251 1811 2251 1804 2251 1821 2252 1808 2252 1818 2252 1821 2253 1812 2253 1808 2253 1821 2254 1819 2254 1812 2254 1822 2255 1817 2255 1816 2255 1822 2256 1816 2256 1819 2256 1823 2257 1815 2257 1824 2257 1823 2258 1814 2258 1815 2258 1825 2259 1818 2259 1811 2259 1825 2260 1811 2260 1820 2260 1825 2261 1821 2261 1818 2261 1826 2262 1824 2262 1827 2262 1826 2263 1823 2263 1824 2263 1828 2264 1819 2264 1821 2264 1828 2265 1822 2265 1819 2265 1829 2266 1823 2266 1826 2266 1829 2267 1820 2267 1814 2267 1829 2268 1814 2268 1823 2268 1830 2269 1821 2269 1825 2269 1831 2270 1829 2270 1826 2270 1832 2271 1826 2271 1827 2271 1833 2272 1822 2272 1828 2272 1833 2273 1834 2273 1817 2273 1833 2274 1817 2274 1822 2274 1835 2275 1825 2275 1820 2275 1835 2276 1820 2276 1829 2276 1835 2277 1829 2277 1831 2277 1835 2278 1830 2278 1825 2278 1836 2279 1827 2279 1837 2279 1836 2280 1832 2280 1827 2280 1838 2281 1828 2281 1821 2281 1838 2282 1821 2282 1830 2282 1839 2283 1835 2283 1831 2283 1840 2284 1831 2284 1826 2284 1840 2285 1826 2285 1832 2285 1841 2286 1830 2286 1835 2286 1841 2287 1835 2287 1839 2287 1842 2288 1836 2288 1837 2288 1843 2289 1834 2289 1833 2289 1843 2290 1828 2290 1838 2290 1843 2291 1844 2291 1834 2291 1843 2292 1833 2292 1828 2292 1845 2293 1832 2293 1836 2293 1845 2294 1840 2294 1832 2294 1845 2295 1836 2295 1842 2295 1846 2296 1841 2296 1839 2296 1847 2297 1831 2297 1840 2297 1847 2298 1840 2298 1845 2298 1847 2299 1839 2299 1831 2299 1848 2300 1830 2300 1841 2300 1848 2301 1841 2301 1846 2301 1848 2302 1838 2302 1830 2302 1849 2303 1837 2303 1850 2303 1849 2304 1842 2304 1837 2304 1851 2305 1845 2305 1842 2305 1851 2306 1842 2306 1849 2306 1852 2307 1845 2307 1851 2307 1852 2308 1847 2308 1845 2308 1853 2309 1848 2309 1846 2309 1854 2310 1846 2310 1839 2310 1854 2311 1839 2311 1847 2311 1854 2312 1847 2312 1852 2312 1855 2313 1849 2313 1850 2313 1856 2314 1843 2314 1838 2314 1856 2315 1844 2315 1843 2315 1856 2316 1838 2316 1848 2316 1856 2317 1857 2317 1844 2317 1856 2318 1848 2318 1853 2318 1858 2319 1859 2319 1860 2319 1858 2320 1861 2320 1859 2320 1862 2321 1851 2321 1849 2321 1863 2322 1851 2322 1862 2322 1863 2323 1852 2323 1851 2323 1864 2324 1858 2324 1860 2324 1865 2325 1861 2325 1858 2325 1866 2326 1854 2326 1852 2326 1866 2327 1852 2327 1863 2327 1865 2328 1867 2328 1861 2328 1868 2329 1857 2329 1856 2329 1868 2330 1856 2330 1853 2330 1869 2331 1853 2331 1846 2331 1870 2332 1860 2332 1871 2332 1869 2333 1846 2333 1854 2333 1870 2334 1864 2334 1860 2334 1872 2335 1865 2335 1858 2335 1872 2336 1858 2336 1864 2336 1873 2337 1849 2337 1855 2337 1872 2338 1864 2338 1870 2338 1873 2339 1862 2339 1849 2339 1874 2340 1865 2340 1872 2340 1875 2341 1850 2341 1876 2341 1875 2342 1855 2342 1850 2342 1874 2343 1645 2343 1641 2343 1874 2344 1641 2344 1867 2344 1874 2345 1867 2345 1865 2345 1877 2346 1863 2346 1862 2346 1878 2347 1872 2347 1870 2347 1877 2348 1862 2348 1873 2348 1879 2349 1863 2349 1877 2349 1879 2350 1866 2350 1863 2350 1880 2351 1866 2351 1879 2351 1881 2352 1870 2352 1871 2352 1881 2353 1878 2353 1870 2353 1880 2354 1854 2354 1866 2354 1882 2355 1874 2355 1872 2355 1880 2356 1869 2356 1854 2356 1882 2357 1872 2357 1878 2357 1883 2358 1874 2358 1882 2358 1884 2359 1875 2359 1876 2359 1883 2360 1645 2360 1874 2360 1885 2361 1869 2361 1880 2361 1883 2362 1648 2362 1645 2362 1885 2363 1886 2363 1857 2363 1885 2364 1853 2364 1869 2364 1885 2365 1857 2365 1868 2365 1885 2366 1868 2366 1853 2366 1887 2367 1882 2367 1878 2367 1888 2368 1877 2368 1873 2368 1889 2369 1878 2369 1881 2369 1889 2370 1887 2370 1878 2370 1890 2371 1873 2371 1855 2371 1890 2372 1855 2372 1875 2372 1891 2373 1871 2373 1892 2373 1893 2374 1877 2374 1888 2374 1891 2375 1881 2375 1871 2375 1893 2376 1879 2376 1877 2376 1894 2377 1648 2377 1883 2377 1894 2378 1615 2378 1648 2378 1894 2379 1883 2379 1882 2379 1894 2380 1882 2380 1887 2380 1895 2381 1885 2381 1880 2381 1895 2382 1886 2382 1885 2382 1896 2383 1879 2383 1893 2383 1896 2384 1895 2384 1880 2384 1897 2385 1891 2385 1892 2385 1896 2386 1880 2386 1879 2386 1898 2387 1615 2387 1894 2387 1899 2388 1875 2388 1884 2388 1898 2389 1894 2389 1887 2389 1899 2390 1890 2390 1875 2390 1900 2391 1893 2391 1888 2391 1901 2392 1887 2392 1889 2392 1901 2393 1898 2393 1887 2393 1902 2394 1899 2394 1884 2394 1902 2395 1876 2395 1903 2395 1904 2396 1891 2396 1897 2396 1902 2397 1884 2397 1876 2397 1904 2398 1881 2398 1891 2398 1904 2399 1889 2399 1881 2399 1905 2400 1873 2400 1890 2400 1905 2401 1888 2401 1873 2401 1906 2402 1904 2402 1897 2402 1905 2403 1890 2403 1899 2403 1907 2404 1897 2404 1892 2404 1908 2405 1895 2405 1896 2405 1908 2406 1886 2406 1895 2406 1908 2407 1909 2407 1886 2407 1907 2408 1892 2408 1910 2408 1911 2409 1896 2409 1893 2409 1911 2410 1908 2410 1896 2410 1912 2411 1618 2411 1613 2411 1912 2412 1613 2412 1615 2412 1912 2413 1615 2413 1898 2413 1913 2414 1905 2414 1899 2414 1914 2415 1898 2415 1901 2415 1914 2416 1912 2416 1898 2416 1915 2417 1913 2417 1899 2417 1915 2418 1899 2418 1902 2418 1916 2419 1901 2419 1889 2419 1916 2420 1904 2420 1906 2420 1916 2421 1889 2421 1904 2421 1917 2422 1911 2422 1893 2422 1918 2423 1916 2423 1906 2423 1917 2424 1893 2424 1900 2424 1919 2425 1905 2425 1913 2425 1919 2426 1888 2426 1905 2426 1920 2427 1897 2427 1907 2427 1919 2428 1900 2428 1888 2428 1921 2429 1909 2429 1908 2429 1920 2430 1906 2430 1897 2430 1921 2431 1911 2431 1917 2431 1921 2432 1908 2432 1911 2432 1922 2433 1919 2433 1913 2433 1923 2434 1914 2434 1901 2434 1923 2435 1916 2435 1918 2435 1923 2436 1901 2436 1916 2436 1924 2437 1912 2437 1914 2437 1925 2438 1903 2438 1926 2438 1924 2439 1618 2439 1912 2439 1925 2440 1902 2440 1903 2440 1927 2441 1928 2441 1909 2441 1927 2442 1921 2442 1917 2442 1929 2443 1923 2443 1918 2443 1927 2444 1909 2444 1921 2444 1930 2445 1913 2445 1915 2445 1930 2446 1922 2446 1913 2446 1931 2447 1910 2447 1932 2447 1931 2448 1920 2448 1907 2448 1931 2449 1907 2449 1910 2449 1933 2450 1906 2450 1920 2450 1934 2451 1917 2451 1900 2451 1934 2452 1900 2452 1919 2452 1933 2453 1918 2453 1906 2453 1935 2454 1934 2454 1919 2454 1936 2455 1618 2455 1924 2455 1935 2456 1919 2456 1922 2456 1936 2457 1937 2457 1625 2457 1936 2458 1625 2458 1621 2458 1936 2459 1621 2459 1618 2459 1938 2460 1914 2460 1923 2460 1938 2461 1924 2461 1914 2461 1938 2462 1923 2462 1929 2462 1939 2463 1902 2463 1925 2463 1939 2464 1915 2464 1902 2464 1940 2465 1938 2465 1929 2465 1941 2466 1922 2466 1930 2466 1941 2467 1935 2467 1922 2467 1942 2468 1927 2468 1917 2468 1942 2469 1917 2469 1934 2469 1943 2470 1920 2470 1931 2470 1942 2471 1928 2471 1927 2471 1943 2472 1933 2472 1920 2472 1942 2473 1934 2473 1935 2473 1944 2474 1929 2474 1918 2474 1945 2475 1946 2475 1947 2475 1945 2476 1926 2476 1946 2476 1945 2477 1925 2477 1926 2477 1944 2478 1918 2478 1933 2478 1948 2479 1924 2479 1938 2479 1948 2480 1937 2480 1936 2480 1948 2481 1938 2481 1940 2481 1949 2482 1950 2482 1928 2482 1949 2483 1928 2483 1942 2483 1948 2484 1936 2484 1924 2484 1949 2485 1942 2485 1935 2485 1951 2486 1932 2486 1952 2486 1953 2487 1930 2487 1915 2487 1953 2488 1915 2488 1939 2488 1951 2489 1943 2489 1931 2489 1951 2490 1931 2490 1932 2490 1954 2491 1937 2491 1948 2491 1954 2492 1955 2492 1937 2492 1954 2493 1948 2493 1940 2493 1956 2494 1933 2494 1943 2494 1957 2495 1935 2495 1941 2495 1957 2496 1949 2496 1935 2496 1956 2497 1944 2497 1933 2497 1958 2498 1939 2498 1925 2498 1958 2499 1925 2499 1945 2499 1959 2500 1929 2500 1944 2500 1959 2501 1940 2501 1929 2501 1960 2502 1956 2502 1943 2502 1961 2503 1941 2503 1930 2503 1961 2504 1930 2504 1953 2504 1962 2505 1950 2505 1949 2505 1962 2506 1963 2506 1950 2506 1960 2507 1943 2507 1951 2507 1962 2508 1949 2508 1957 2508 1964 2509 1958 2509 1945 2509 1965 2510 1959 2510 1944 2510 1965 2511 1944 2511 1956 2511 1964 2512 1945 2512 1947 2512 1966 2513 1940 2513 1959 2513 1966 2514 1967 2514 1955 2514 1966 2515 1954 2515 1940 2515 1966 2516 1955 2516 1954 2516 1968 2517 1969 2517 1970 2517 1968 2518 1952 2518 1969 2518 1971 2519 1939 2519 1958 2519 1968 2520 1951 2520 1952 2520 1971 2521 1953 2521 1939 2521 1971 2522 1961 2522 1953 2522 1972 2523 1941 2523 1961 2523 1973 2524 1956 2524 1960 2524 1973 2525 1965 2525 1956 2525 1972 2526 1957 2526 1941 2526 1974 2527 1958 2527 1964 2527 1975 2528 1959 2528 1965 2528 1975 2529 1966 2529 1959 2529 1974 2530 1971 2530 1958 2530 1976 2531 1961 2531 1971 2531 1977 2532 1960 2532 1951 2532 1977 2533 1951 2533 1968 2533 1978 2534 1963 2534 1962 2534 1978 2535 1962 2535 1957 2535 1978 2536 1957 2536 1972 2536 1979 2537 1965 2537 1973 2537 1979 2538 1975 2538 1965 2538 1980 2539 1947 2539 1981 2539 1982 2540 1967 2540 1966 2540 1980 2541 1964 2541 1947 2541 1982 2542 1966 2542 1975 2542 1983 2543 1971 2543 1974 2543 1984 2544 1968 2544 1970 2544 1984 2545 1977 2545 1968 2545 1983 2546 1976 2546 1971 2546 1985 2547 1973 2547 1960 2547 1985 2548 1960 2548 1977 2548 1986 2549 1981 2549 1987 2549 1986 2550 1980 2550 1981 2550 1985 2551 1979 2551 1973 2551 1988 2552 1970 2552 1989 2552 1990 2553 1972 2553 1961 2553 1990 2554 1961 2554 1976 2554 1988 2555 1984 2555 1970 2555 1991 2556 1975 2556 1979 2556 1991 2557 1982 2557 1975 2557 1992 2558 1974 2558 1964 2558 1992 2559 1964 2559 1980 2559 1993 2560 1977 2560 1984 2560 1992 2561 1980 2561 1986 2561 1993 2562 1985 2562 1977 2562 1994 2563 1990 2563 1976 2563 1994 2564 1976 2564 1983 2564 1995 2565 1979 2565 1985 2565 1996 2566 1984 2566 1988 2566 1997 2567 1992 2567 1986 2567 1996 2568 1993 2568 1984 2568 1998 2569 1986 2569 1987 2569 1999 2570 1988 2570 1989 2570 2000 2571 1972 2571 1990 2571 2001 2572 2002 2572 1967 2572 2000 2573 1978 2573 1972 2573 2000 2574 2003 2574 1963 2574 2001 2575 1982 2575 1991 2575 2001 2576 1967 2576 1982 2576 2000 2577 1963 2577 1978 2577 2004 2578 1993 2578 1996 2578 2005 2579 1983 2579 1974 2579 2004 2580 1985 2580 1993 2580 2005 2581 1974 2581 1992 2581 2004 2582 1995 2582 1985 2582 2005 2583 1992 2583 1997 2583 2006 2584 2000 2584 1990 2584 2007 2585 1989 2585 2008 2585 2006 2586 1990 2586 1994 2586 2007 2587 1999 2587 1989 2587 2009 2588 1987 2588 2010 2588 2011 2589 1991 2589 1979 2589 2009 2590 1998 2590 1987 2590 2011 2591 1979 2591 1995 2591 2012 2592 2005 2592 1997 2592 2013 2593 2004 2593 1996 2593 2014 2594 1988 2594 1999 2594 2015 2595 1997 2595 1986 2595 2014 2596 1996 2596 1988 2596 2015 2597 1986 2597 1998 2597 2016 2598 1995 2598 2004 2598 2016 2599 2011 2599 1995 2599 2017 2600 2005 2600 2012 2600 2016 2601 2004 2601 2013 2601 2017 2602 1994 2602 1983 2602 2017 2603 1983 2603 2005 2603 2018 2604 2007 2604 2008 2604 2019 2605 2009 2605 2010 2605 2020 2606 2001 2606 1991 2606 2020 2607 2021 2607 2002 2607 2022 2608 2000 2608 2006 2608 2022 2609 2003 2609 2000 2609 2020 2610 2002 2610 2001 2610 2022 2611 2023 2611 2003 2611 2020 2612 1991 2612 2011 2612 2024 2613 1999 2613 2007 2613 2025 2614 1998 2614 2009 2614 2024 2615 2014 2615 1999 2615 2025 2616 2015 2616 1998 2616 2026 2617 2016 2617 2013 2617 2027 2618 2013 2618 1996 2618 2028 2619 2017 2619 2012 2619 2027 2620 1996 2620 2014 2620 2029 2621 2012 2621 1997 2621 2027 2622 2014 2622 2024 2622 2029 2623 1997 2623 2015 2623 2030 2624 2020 2624 2011 2624 2029 2625 2015 2625 2025 2625 2030 2626 2011 2626 2016 2626 2029 2627 2028 2627 2012 2627 2031 2628 2010 2628 2032 2628 2031 2629 2032 2629 2033 2629 2031 2630 2019 2630 2010 2630 2034 2631 2008 2631 2035 2631 2034 2632 2018 2632 2008 2632 2036 2633 1994 2633 2017 2633 2037 2634 2024 2634 2007 2634 2036 2635 2017 2635 2028 2635 2036 2636 2006 2636 1994 2636 2037 2637 2007 2637 2018 2637 2038 2638 2009 2638 2019 2638 2039 2639 2024 2639 2037 2639 2038 2640 2025 2640 2009 2640 2039 2641 2027 2641 2024 2641 2038 2642 2019 2642 2031 2642 1777 2643 2030 2643 2016 2643 1777 2644 2016 2644 2026 2644 2040 2645 2029 2645 2025 2645 2040 2646 2025 2646 2038 2646 2041 2647 2026 2647 2013 2647 2041 2648 2013 2648 2027 2648 2042 2649 2028 2649 2029 2649 2041 2650 2027 2650 2039 2650 2042 2651 2029 2651 2040 2651 2043 2652 2036 2652 2028 2652 2044 2653 2034 2653 2035 2653 2045 2654 2046 2654 1557 2654 2045 2655 2033 2655 2046 2655 2047 2656 2021 2656 2020 2656 2045 2657 2031 2657 2033 2657 2047 2658 1775 2658 2021 2658 2045 2659 2038 2659 2031 2659 2048 2660 2036 2660 2043 2660 2047 2661 2020 2661 2030 2661 2049 2662 2018 2662 2034 2662 2048 2663 2022 2663 2006 2663 2049 2664 2037 2664 2018 2664 2048 2665 2050 2665 2023 2665 2048 2666 2006 2666 2036 2666 2048 2667 2023 2667 2022 2667 2051 2668 2038 2668 2045 2668 2051 2669 2040 2669 2038 2669 2052 2670 2042 2670 2040 2670 1784 2671 2039 2671 2037 2671 2052 2672 2040 2672 2051 2672 1789 2673 2041 2673 2039 2673 1789 2674 2039 2674 1784 2674 2053 2675 2050 2675 2048 2675 1776 2676 2030 2676 1777 2676 2053 2677 2048 2677 2043 2677 2054 2678 2043 2678 2028 2678 1776 2679 2047 2679 2030 2679 1776 2680 1775 2680 2047 2680 1778 2681 1777 2681 2026 2681 1778 2682 2026 2682 2041 2682 2054 2683 2042 2683 2052 2683 1778 2684 2041 2684 1789 2684 2054 2685 2028 2685 2042 2685 2055 2686 1557 2686 1551 2686 2055 2687 1551 2687 1545 2687 2055 2688 2051 2688 2045 2688 2055 2689 2045 2689 1557 2689 2056 2690 2051 2690 2055 2690 1781 2691 2034 2691 2044 2691 2056 2692 1546 2692 2052 2692 1781 2693 2049 2693 2034 2693 2056 2694 1545 2694 1546 2694 2056 2695 2052 2695 2051 2695 2056 2696 2055 2696 1545 2696 1771 2697 2035 2697 1772 2697 2057 2698 2054 2698 2052 2698 2057 2699 2052 2699 1546 2699 1771 2700 1781 2700 2044 2700 2057 2701 1546 2701 1599 2701 1771 2702 2044 2702 2035 2702 2058 2703 2053 2703 2043 2703 2058 2704 2050 2704 2053 2704 1780 2705 2037 2705 2049 2705 1780 2706 1784 2706 2037 2706 2058 2707 1592 2707 1589 2707 2058 2708 1589 2708 2050 2708 1780 2709 2049 2709 1781 2709 2058 2710 2054 2710 2057 2710 2058 2711 2043 2711 2054 2711 2059 2712 2057 2712 1599 2712 2059 2713 1592 2713 2058 2713 1785 2714 1789 2714 1784 2714 2059 2715 1599 2715 1594 2715 2059 2716 1594 2716 1592 2716 2059 2717 2058 2717 2057 2717 1787 2718 1778 2718 1789 2718 2060 2719 2061 2719 2062 2719 2060 2720 2063 2720 2061 2720 2064 2721 2062 2721 2065 2721 2064 2722 2060 2722 2062 2722 2066 2723 2065 2723 2067 2723 2066 2724 2064 2724 2065 2724 2068 2725 2067 2725 2069 2725 2068 2726 2066 2726 2067 2726 2070 2727 2069 2727 2071 2727 2070 2728 2068 2728 2069 2728 2072 2729 2071 2729 2073 2729 2072 2730 2070 2730 2071 2730 2074 2731 2075 2731 2076 2731 2077 2732 2074 2732 2076 2732 2078 2733 2077 2733 2079 2733 2080 2734 2078 2734 2079 2734 2077 2735 2076 2735 2079 2735 2081 2736 2080 2736 2082 2736 2080 2737 2079 2737 2082 2737 2083 2738 2081 2738 2084 2738 2081 2739 2082 2739 2084 2739 2085 2740 2083 2740 2086 2740 2083 2741 2084 2741 2086 2741 2087 2742 2085 2742 2088 2742 2085 2743 2086 2743 2088 2743 2089 2744 2087 2744 2090 2744 2087 2745 2088 2745 2090 2745 2089 2746 2090 2746 2091 2746 2092 2747 2089 2747 2093 2747 2089 2748 2091 2748 2093 2748 2094 2749 2092 2749 2095 2749 2092 2750 2093 2750 2095 2750 2096 2751 2097 2751 2098 2751 2099 2752 2096 2752 2100 2752 2096 2753 2098 2753 2100 2753 2101 2754 2099 2754 2102 2754 2099 2755 2100 2755 2102 2755 2103 2756 2101 2756 2104 2756 2101 2757 2102 2757 2104 2757 2105 2758 2103 2758 2106 2758 2103 2759 2104 2759 2106 2759 2107 2760 2105 2760 2108 2760 2105 2761 2106 2761 2108 2761 2109 2762 2107 2762 2110 2762 2107 2763 2108 2763 2110 2763 2111 2764 2109 2764 2112 2764 2109 2765 2110 2765 2112 2765 2113 2766 2111 2766 2114 2766 2111 2767 2112 2767 2114 2767 2115 2768 2113 2768 2116 2768 2113 2769 2114 2769 2116 2769 2115 2770 2116 2770 2117 2770 2118 2771 2086 2771 2119 2771 2118 2772 2119 2772 2120 2772 2121 2773 2122 2773 2123 2773 2121 2774 2123 2774 2124 2774 2121 2775 2125 2775 2126 2775 2121 2776 2126 2776 2122 2776 2127 2777 2128 2777 2129 2777 2127 2778 2130 2778 2131 2778 2127 2779 2129 2779 2130 2779 2127 2780 2132 2780 2128 2780 2127 2781 2120 2781 2132 2781 2127 2782 2118 2782 2120 2782 2133 2783 2086 2783 2118 2783 2133 2784 2124 2784 2086 2784 2133 2785 2121 2785 2124 2785 2133 2786 2118 2786 2127 2786 2134 2787 2135 2787 2136 2787 2134 2788 2131 2788 2135 2788 2134 2789 2136 2789 2133 2789 2134 2790 2127 2790 2131 2790 2134 2791 2133 2791 2127 2791 2137 2792 2138 2792 2139 2792 2137 2793 2140 2793 2141 2793 2137 2794 2142 2794 2140 2794 2137 2795 2139 2795 2142 2795 2137 2796 2141 2796 2138 2796 2143 2797 2144 2797 2145 2797 2143 2798 2145 2798 2146 2798 2147 2799 2146 2799 2148 2799 2147 2800 2143 2800 2146 2800 2147 2801 2144 2801 2143 2801 2147 2802 2149 2802 2144 2802 2150 2803 2151 2803 2149 2803 2150 2804 2148 2804 2151 2804 2150 2805 2147 2805 2148 2805 2150 2806 2149 2806 2147 2806 2152 2807 2149 2807 2151 2807 2152 2808 2151 2808 2153 2808 2154 2809 2155 2809 2149 2809 2154 2810 2153 2810 2156 2810 2154 2811 2152 2811 2153 2811 2154 2812 2149 2812 2152 2812 2157 2813 2158 2813 2155 2813 2157 2814 2155 2814 2154 2814 2157 2815 2154 2815 2156 2815 2157 2816 2156 2816 2158 2816 2159 2817 2160 2817 2125 2817 2159 2818 2136 2818 2160 2818 2159 2819 2133 2819 2136 2819 2159 2820 2125 2820 2121 2820 2159 2821 2121 2821 2133 2821 2161 2822 2162 2822 2142 2822 2161 2823 2163 2823 2162 2823 2161 2824 2164 2824 2163 2824 2161 2825 2165 2825 2166 2825 2145 2826 2167 2826 2164 2826 2145 2827 2144 2827 2167 2827 2145 2828 2164 2828 2161 2828 2139 2829 2168 2829 2169 2829 2139 2830 2169 2830 2165 2830 2139 2831 2165 2831 2161 2831 2139 2832 2161 2832 2142 2832 2170 2833 2145 2833 2161 2833 2170 2834 2161 2834 2166 2834 2170 2835 2166 2835 2171 2835 2170 2836 2171 2836 2146 2836 2170 2837 2146 2837 2145 2837 2149 2838 2155 2838 2172 2838 2149 2839 2172 2839 2144 2839 2138 2840 2173 2840 2168 2840 2138 2841 2168 2841 2139 2841 2151 2842 2174 2842 2153 2842 2151 2843 2148 2843 2174 2843 2175 2844 2176 2844 2177 2844 2175 2845 2141 2845 2176 2845 2175 2846 2138 2846 2141 2846 2178 2847 2173 2847 2138 2847 2178 2848 2179 2848 2180 2848 2178 2849 2180 2849 2173 2849 2158 2850 2181 2850 2155 2850 2158 2851 2182 2851 2181 2851 2183 2852 2184 2852 2185 2852 2183 2853 2177 2853 2184 2853 2183 2854 2186 2854 2179 2854 2183 2855 2175 2855 2177 2855 2183 2856 2138 2856 2175 2856 2183 2857 2178 2857 2138 2857 2183 2858 2179 2858 2178 2858 2187 2859 2156 2859 2188 2859 2187 2860 2188 2860 2108 2860 2187 2861 2158 2861 2156 2861 2128 2862 2186 2862 2183 2862 2128 2863 2132 2863 2189 2863 2128 2864 2189 2864 2186 2864 2128 2865 2183 2865 2185 2865 2126 2866 2190 2866 2182 2866 2126 2867 2191 2867 2190 2867 2126 2868 2125 2868 2191 2868 2126 2869 2108 2869 2122 2869 2126 2870 2182 2870 2158 2870 2126 2871 2187 2871 2108 2871 2126 2872 2158 2872 2187 2872 2192 2873 2129 2873 2128 2873 2192 2874 2185 2874 2129 2874 2192 2875 2128 2875 2185 2875 2193 2876 58 2876 13 2876 2194 2877 2193 2877 13 2877 2195 2878 45 2878 2196 2878 45 2879 47 2879 2196 2879 2197 2880 115 2880 112 2880 2197 2881 112 2881 2198 2881 2199 2882 100 2882 108 2882 2199 2883 2200 2883 100 2883 2201 2884 64 2884 58 2884 2193 2885 2201 2885 58 2885 2198 2886 112 2886 2202 2886 112 2887 104 2887 2202 2887 2200 2888 97 2888 100 2888 2200 2889 2203 2889 97 2889 2122 2890 2100 2890 2098 2890 2122 2891 2102 2891 2100 2891 2122 2892 2104 2892 2102 2892 2122 2893 2106 2893 2104 2893 2122 2894 2098 2894 2204 2894 2123 2895 2205 2895 2206 2895 2123 2896 2207 2896 2205 2896 2123 2897 2208 2897 2207 2897 2123 2898 2204 2898 2208 2898 2123 2899 2122 2899 2204 2899 2124 2900 2206 2900 2095 2900 2124 2901 2095 2901 2093 2901 2124 2902 2123 2902 2206 2902 2091 2903 2124 2903 2093 2903 2090 2904 2124 2904 2091 2904 2088 2905 2124 2905 2090 2905 2122 2906 2108 2906 2106 2906 2086 2907 2124 2907 2088 2907 2153 2908 2209 2908 2210 2908 2153 2909 2211 2909 2209 2909 2153 2910 2212 2910 2211 2910 2213 2911 2153 2911 2210 2911 2214 2912 2153 2912 2213 2912 2156 2913 2214 2913 2215 2913 2156 2914 2153 2914 2214 2914 2216 2915 2156 2915 2215 2915 2217 2916 2156 2916 2216 2916 2218 2917 2156 2917 2217 2917 2188 2918 2156 2918 2218 2918 2117 2919 2188 2919 2218 2919 2116 2920 2188 2920 2117 2920 2114 2921 2188 2921 2116 2921 2112 2922 2188 2922 2114 2922 2110 2923 2188 2923 2112 2923 2153 2924 2174 2924 2212 2924 2108 2925 2188 2925 2110 2925 2132 2926 2219 2926 2220 2926 2132 2927 2221 2927 2222 2927 2132 2928 2223 2928 2221 2928 2132 2929 2224 2929 2223 2929 2132 2930 2220 2930 2224 2930 2120 2931 2225 2931 2219 2931 2120 2932 2226 2932 2225 2932 2120 2933 2227 2933 2226 2933 2120 2934 2228 2934 2227 2934 2120 2935 2219 2935 2132 2935 2119 2936 2076 2936 2075 2936 2119 2937 2079 2937 2076 2937 2119 2938 2082 2938 2079 2938 2119 2939 2084 2939 2082 2939 2119 2940 2075 2940 2228 2940 2119 2941 2228 2941 2120 2941 2119 2942 2086 2942 2084 2942 2189 2943 2132 2943 2222 2943 2229 2944 2171 2944 2230 2944 2231 2945 2171 2945 2229 2945 2232 2946 2171 2946 2231 2946 2233 2947 2171 2947 2232 2947 2234 2948 2146 2948 2171 2948 2234 2949 2171 2949 2233 2949 2235 2950 2148 2950 2236 2950 2237 2951 2236 2951 2148 2951 2238 2952 2148 2952 2235 2952 2239 2953 2237 2953 2148 2953 2240 2954 2146 2954 2234 2954 2241 2955 2148 2955 2146 2955 2241 2956 2239 2956 2148 2956 2242 2957 2146 2957 2240 2957 2243 2958 2241 2958 2146 2958 2243 2959 2146 2959 2242 2959 2171 2960 2166 2960 2230 2960 2174 2961 2148 2961 2238 2961 2180 2962 2244 2962 2245 2962 2180 2963 2246 2963 2244 2963 2180 2964 2247 2964 2246 2964 2180 2965 2248 2965 2247 2965 2249 2966 2248 2966 2180 2966 2179 2967 2250 2967 2249 2967 2179 2968 2251 2968 2250 2968 2179 2969 2249 2969 2180 2969 2252 2970 2251 2970 2179 2970 2253 2971 2252 2971 2179 2971 2186 2972 2254 2972 2253 2972 2186 2973 2253 2973 2179 2973 2255 2974 2254 2974 2186 2974 2256 2975 2255 2975 2186 2975 2257 2976 2256 2976 2186 2976 2258 2977 2257 2977 2186 2977 2186 2978 2189 2978 2258 2978 2173 2979 2180 2979 2245 2979 2165 2980 2259 2980 2260 2980 2165 2981 2261 2981 2259 2981 2262 2982 2261 2982 2165 2982 2072 2983 2262 2983 2165 2983 2070 2984 2165 2984 2169 2984 2070 2985 2072 2985 2165 2985 2068 2986 2070 2986 2169 2986 2066 2987 2068 2987 2169 2987 2064 2988 2066 2988 2169 2988 2060 2989 2169 2989 2168 2989 2060 2990 2064 2990 2169 2990 2063 2991 2060 2991 2168 2991 2263 2992 2063 2992 2168 2992 2264 2993 2263 2993 2168 2993 2265 2994 2264 2994 2168 2994 2266 2995 2265 2995 2168 2995 2168 2996 2173 2996 2266 2996 2166 2997 2165 2997 2260 2997 2234 2998 2233 2998 2267 2998 2234 2999 2267 2999 2268 2999 2240 3000 2268 3000 2269 3000 2240 3001 2234 3001 2268 3001 2242 3002 2269 3002 2270 3002 2242 3003 2240 3003 2269 3003 2243 3004 2270 3004 2271 3004 2243 3005 2242 3005 2270 3005 2241 3006 2271 3006 2272 3006 2241 3007 2243 3007 2271 3007 2239 3008 2272 3008 2273 3008 2239 3009 2241 3009 2272 3009 2274 3010 2213 3010 2210 3010 2275 3011 2274 3011 2210 3011 2276 3012 2275 3012 2209 3012 2275 3013 2210 3013 2209 3013 2277 3014 2276 3014 2211 3014 2276 3015 2209 3015 2211 3015 2278 3016 2277 3016 2212 3016 2277 3017 2211 3017 2212 3017 2279 3018 2278 3018 2174 3018 2278 3019 2212 3019 2174 3019 2280 3020 2279 3020 2238 3020 2279 3021 2174 3021 2238 3021 2281 3022 2280 3022 2235 3022 2280 3023 2238 3023 2235 3023 2282 3024 2281 3024 2236 3024 2281 3025 2235 3025 2236 3025 2283 3026 2282 3026 2237 3026 2273 3027 2283 3027 2237 3027 2282 3028 2236 3028 2237 3028 2273 3029 2237 3029 2239 3029 2214 3030 2213 3030 2274 3030 2214 3031 2284 3031 2285 3031 2214 3032 2274 3032 2284 3032 2215 3033 2285 3033 2286 3033 2215 3034 2214 3034 2285 3034 2216 3035 2215 3035 2286 3035 2217 3036 2287 3036 2288 3036 2217 3037 2286 3037 2287 3037 2217 3038 2216 3038 2286 3038 2218 3039 2288 3039 2115 3039 2218 3040 2217 3040 2288 3040 2117 3041 2218 3041 2115 3041 2204 3042 2098 3042 2097 3042 2204 3043 2289 3043 2290 3043 2204 3044 2097 3044 2289 3044 2208 3045 2204 3045 2290 3045 2207 3046 2290 3046 2291 3046 2207 3047 2208 3047 2290 3047 2205 3048 2291 3048 2292 3048 2205 3049 2207 3049 2291 3049 2206 3050 2292 3050 2293 3050 2206 3051 2205 3051 2292 3051 2095 3052 2293 3052 2094 3052 2095 3053 2206 3053 2293 3053 2075 3054 2074 3054 2294 3054 2228 3055 2294 3055 2295 3055 2228 3056 2075 3056 2294 3056 2227 3057 2295 3057 2296 3057 2227 3058 2228 3058 2295 3058 2226 3059 2227 3059 2296 3059 2225 3060 2297 3060 2298 3060 2225 3061 2296 3061 2297 3061 2225 3062 2226 3062 2296 3062 2219 3063 2298 3063 2299 3063 2219 3064 2225 3064 2298 3064 2220 3065 2219 3065 2299 3065 2300 3066 2254 3066 2255 3066 2301 3067 2300 3067 2255 3067 2302 3068 2301 3068 2256 3068 2301 3069 2255 3069 2256 3069 2303 3070 2302 3070 2257 3070 2302 3071 2256 3071 2257 3071 2304 3072 2303 3072 2258 3072 2303 3073 2257 3073 2258 3073 2305 3074 2304 3074 2189 3074 2304 3075 2258 3075 2189 3075 2306 3076 2305 3076 2222 3076 2305 3077 2189 3077 2222 3077 2307 3078 2306 3078 2221 3078 2306 3079 2222 3079 2221 3079 2308 3080 2307 3080 2223 3080 2307 3081 2221 3081 2223 3081 2309 3082 2308 3082 2224 3082 2308 3083 2223 3083 2224 3083 2299 3084 2309 3084 2220 3084 2309 3085 2224 3085 2220 3085 2254 3086 2300 3086 2310 3086 2253 3087 2310 3087 2311 3087 2253 3088 2254 3088 2310 3088 2252 3089 2311 3089 2312 3089 2252 3090 2253 3090 2311 3090 2251 3091 2312 3091 2313 3091 2251 3092 2252 3092 2312 3092 2250 3093 2313 3093 2314 3093 2250 3094 2251 3094 2313 3094 2249 3095 2314 3095 2315 3095 2249 3096 2250 3096 2314 3096 2248 3097 2249 3097 2315 3097 2316 3098 2061 3098 2063 3098 2317 3099 2316 3099 2263 3099 2316 3100 2063 3100 2263 3100 2317 3101 2263 3101 2264 3101 2318 3102 2317 3102 2265 3102 2317 3103 2264 3103 2265 3103 2319 3104 2318 3104 2266 3104 2318 3105 2265 3105 2266 3105 2320 3106 2319 3106 2173 3106 2319 3107 2266 3107 2173 3107 2321 3108 2320 3108 2245 3108 2320 3109 2173 3109 2245 3109 2322 3110 2321 3110 2244 3110 2321 3111 2245 3111 2244 3111 2323 3112 2322 3112 2246 3112 2322 3113 2244 3113 2246 3113 2324 3114 2323 3114 2247 3114 2315 3115 2324 3115 2247 3115 2323 3116 2246 3116 2247 3116 2315 3117 2247 3117 2248 3117 2325 3118 2267 3118 2233 3118 2325 3119 2233 3119 2232 3119 2326 3120 2325 3120 2231 3120 2325 3121 2232 3121 2231 3121 2327 3122 2326 3122 2229 3122 2326 3123 2231 3123 2229 3123 2328 3124 2327 3124 2230 3124 2327 3125 2229 3125 2230 3125 2329 3126 2328 3126 2166 3126 2328 3127 2230 3127 2166 3127 2330 3128 2329 3128 2260 3128 2329 3129 2166 3129 2260 3129 2331 3130 2330 3130 2259 3130 2330 3131 2260 3131 2259 3131 2332 3132 2331 3132 2261 3132 2331 3133 2259 3133 2261 3133 2333 3134 2332 3134 2262 3134 2332 3135 2261 3135 2262 3135 2073 3136 2333 3136 2072 3136 2333 3137 2262 3137 2072 3137 2288 3138 2287 3138 2290 3138 2288 3139 2290 3139 2289 3139 2288 3140 2289 3140 2097 3140 2298 3141 2310 3141 2299 3141 2298 3142 2311 3142 2310 3142 2115 3143 2288 3143 2097 3143 2094 3144 2074 3144 2078 3144 2332 3145 2333 3145 2073 3145 2099 3146 2097 3146 2096 3146 2113 3147 2115 3147 2097 3147 2094 3148 2294 3148 2074 3148 2094 3149 2078 3149 2080 3149 2094 3150 2080 3150 2081 3150 2315 3151 2317 3151 2318 3151 2094 3152 2081 3152 2083 3152 2315 3153 2318 3153 2319 3153 2094 3154 2083 3154 2085 3154 2315 3155 2319 3155 2320 3155 2094 3156 2085 3156 2087 3156 2331 3157 2332 3157 2073 3157 2315 3158 2320 3158 2321 3158 2094 3159 2087 3159 2089 3159 2315 3160 2321 3160 2322 3160 2094 3161 2089 3161 2092 3161 2315 3162 2322 3162 2323 3162 2315 3163 2323 3163 2324 3163 2101 3164 2097 3164 2099 3164 2330 3165 2331 3165 2073 3165 2111 3166 2113 3166 2097 3166 2316 3167 2317 3167 2315 3167 2297 3168 2311 3168 2298 3168 2297 3169 2312 3169 2311 3169 2293 3170 2294 3170 2094 3170 2061 3171 2316 3171 2315 3171 2103 3172 2097 3172 2101 3172 2293 3173 2295 3173 2294 3173 2109 3174 2111 3174 2097 3174 2329 3175 2330 3175 2073 3175 2292 3176 2295 3176 2293 3176 2105 3177 2097 3177 2103 3177 2292 3178 2296 3178 2295 3178 2107 3179 2109 3179 2097 3179 2328 3180 2329 3180 2073 3180 2107 3181 2097 3181 2105 3181 2296 3182 2312 3182 2297 3182 2291 3183 2296 3183 2292 3183 2327 3184 2328 3184 2073 3184 2291 3185 2270 3185 2296 3185 2326 3186 2327 3186 2073 3186 2325 3187 2326 3187 2073 3187 2267 3188 2325 3188 2073 3188 2062 3189 2061 3189 2315 3189 2062 3190 2315 3190 2314 3190 2062 3191 2314 3191 2313 3191 2268 3192 2073 3192 2071 3192 2285 3193 2272 3193 2271 3193 2268 3194 2267 3194 2073 3194 2286 3195 2285 3195 2271 3195 2286 3196 2271 3196 2270 3196 2286 3197 2270 3197 2291 3197 2065 3198 2313 3198 2312 3198 2284 3199 2272 3199 2285 3199 2269 3200 2071 3200 2069 3200 2065 3201 2062 3201 2313 3201 2279 3202 2280 3202 2281 3202 2269 3203 2268 3203 2071 3203 2279 3204 2281 3204 2282 3204 2279 3205 2282 3205 2283 3205 2287 3206 2286 3206 2291 3206 2078 3207 2074 3207 2077 3207 2287 3208 2291 3208 2290 3208 2274 3209 2273 3209 2272 3209 2274 3210 2272 3210 2284 3210 2067 3211 2065 3211 2312 3211 2270 3212 2069 3212 2067 3212 2270 3213 2067 3213 2312 3213 2299 3214 2310 3214 2300 3214 2275 3215 2273 3215 2274 3215 2270 3216 2312 3216 2296 3216 2299 3217 2300 3217 2301 3217 2275 3218 2279 3218 2283 3218 2299 3219 2301 3219 2302 3219 2299 3220 2302 3220 2303 3220 2270 3221 2269 3221 2069 3221 2299 3222 2303 3222 2304 3222 2275 3223 2283 3223 2273 3223 2299 3224 2304 3224 2305 3224 2299 3225 2305 3225 2306 3225 2299 3226 2306 3226 2307 3226 2299 3227 2307 3227 2308 3227 2277 3228 2278 3228 2279 3228 2299 3229 2308 3229 2309 3229 2276 3230 2279 3230 2275 3230 2276 3231 2277 3231 2279 3231 2334 3232 2335 3232 2336 3232 2337 3233 2336 3233 2338 3233 2339 3234 2340 3234 2341 3234 2339 3235 2341 3235 2342 3235 2339 3236 2343 3236 2340 3236 2337 3237 2334 3237 2336 3237 2344 3238 2345 3238 2346 3238 2347 3239 2348 3239 2349 3239 2347 3240 2349 3240 2350 3240 2351 3241 1740 3241 1738 3241 525 3242 527 3242 2352 3242 525 3243 2352 3243 2353 3243 1663 3244 1729 3244 1725 3244 2354 3245 2355 3245 2343 3245 1663 3246 1733 3246 1729 3246 2354 3247 2356 3247 2355 3247 1663 3248 1736 3248 1733 3248 1663 3249 1738 3249 1736 3249 2354 3250 2343 3250 2339 3250 1663 3251 2351 3251 1738 3251 2357 3252 2358 3252 555 3252 2359 3253 2360 3253 2361 3253 2359 3254 2361 3254 2362 3254 2363 3255 2364 3255 2365 3255 541 3256 2366 3256 2367 3256 483 3257 569 3257 490 3257 541 3258 2368 3258 2366 3258 541 3259 2369 3259 2368 3259 2370 3260 2363 3260 2365 3260 541 3261 2371 3261 2369 3261 483 3262 567 3262 569 3262 2372 3263 2370 3263 2365 3263 2373 3264 2374 3264 2375 3264 2373 3265 2376 3265 2374 3265 2377 3266 2372 3266 2365 3266 2378 3267 2379 3267 2380 3267 2381 3268 2356 3268 2354 3268 2382 3269 2348 3269 2347 3269 2382 3270 2383 3270 2348 3270 2381 3271 2384 3271 2385 3271 535 3272 541 3272 2367 3272 535 3273 2367 3273 2386 3273 2381 3274 2385 3274 2356 3274 535 3275 2386 3275 2387 3275 2388 3276 1663 3276 2389 3276 545 3277 2365 3277 2390 3277 571 3278 573 3278 2391 3278 545 3279 2371 3279 541 3279 571 3280 2391 3280 2392 3280 571 3281 2392 3281 2393 3281 545 3282 2394 3282 2371 3282 545 3283 2395 3283 2394 3283 545 3284 2396 3284 2395 3284 2397 3285 2362 3285 2398 3285 545 3286 2390 3286 2396 3286 545 3287 2399 3287 2365 3287 2397 3288 2359 3288 2362 3288 2400 3289 2337 3289 2338 3289 2401 3290 1663 3290 2388 3290 2402 3291 2398 3291 2403 3291 2402 3292 2397 3292 2398 3292 2399 3293 2377 3293 2365 3293 2404 3294 1663 3294 2401 3294 2405 3295 2383 3295 2382 3295 2406 3296 2403 3296 2407 3296 2408 3297 2409 3297 2384 3297 2406 3298 2402 3298 2403 3298 2408 3299 2384 3299 2381 3299 523 3300 525 3300 2353 3300 523 3301 2383 3301 2405 3301 523 3302 2353 3302 2383 3302 2410 3303 2409 3303 2408 3303 2411 3304 1663 3304 2404 3304 532 3305 535 3305 2387 3305 2410 3306 2412 3306 2409 3306 2410 3307 2413 3307 2412 3307 2414 3308 1663 3308 2411 3308 532 3309 2415 3309 2416 3309 532 3310 2387 3310 2415 3310 2417 3311 1663 3311 2414 3311 2418 3312 2357 3312 555 3312 488 3313 567 3313 483 3313 488 3314 565 3314 567 3314 2419 3315 1663 3315 2417 3315 2420 3316 2413 3316 2410 3316 2419 3317 2351 3317 1663 3317 549 3318 2399 3318 545 3318 2421 3319 2422 3319 2423 3319 2421 3320 2423 3320 2424 3320 2425 3321 2406 3321 2407 3321 2420 3322 2426 3322 2413 3322 2420 3323 2427 3323 2426 3323 2428 3324 2429 3324 2376 3324 2428 3325 2376 3325 2373 3325 2430 3326 2431 3326 2344 3326 2428 3327 2432 3327 2433 3327 2430 3328 2434 3328 2431 3328 2428 3329 2435 3329 2432 3329 2430 3330 2436 3330 2434 3330 2428 3331 2437 3331 2435 3331 2430 3332 2438 3332 2436 3332 2428 3333 2433 3333 2429 3333 2439 3334 2438 3334 2430 3334 1541 3335 2440 3335 2425 3335 1541 3336 2407 3336 2441 3336 1541 3337 2441 3337 2442 3337 2443 3338 2437 3338 2428 3338 1541 3339 1713 3339 1710 3339 1541 3340 2425 3340 2407 3340 1706 3341 1541 3341 1710 3341 2444 3342 2439 3342 2445 3342 2446 3343 2443 3343 2428 3343 2447 3344 2439 3344 2444 3344 2448 3345 2449 3345 2443 3345 2448 3346 2443 3346 2446 3346 2450 3347 2418 3347 555 3347 2451 3348 2437 3348 2443 3348 2452 3349 2439 3349 2447 3349 2452 3350 2453 3350 2438 3350 2451 3351 2454 3351 2437 3351 2452 3352 2438 3352 2439 3352 2455 3353 2456 3353 2457 3353 2455 3354 2424 3354 2456 3354 2458 3355 2457 3355 2400 3355 2458 3356 2455 3356 2457 3356 521 3357 523 3357 2405 3357 521 3358 2459 3358 2460 3358 521 3359 2405 3359 2459 3359 2461 3360 2424 3360 2455 3360 491 3361 565 3361 488 3361 491 3362 563 3362 565 3362 2462 3363 2458 3363 2400 3363 529 3364 532 3364 2416 3364 2463 3365 2464 3365 2465 3365 2466 3366 2450 3366 555 3366 529 3367 2467 3367 2454 3367 529 3368 2468 3368 2467 3368 529 3369 2469 3369 2468 3369 2466 3370 559 3370 561 3370 529 3371 2416 3371 2469 3371 2466 3372 557 3372 559 3372 529 3373 2454 3373 2451 3373 2466 3374 555 3374 557 3374 1701 3375 1541 3375 1706 3375 2470 3376 2465 3376 2464 3376 1696 3377 1541 3377 1701 3377 2471 3378 2424 3378 2461 3378 2471 3379 2421 3379 2424 3379 2471 3380 2472 3380 2473 3380 2474 3381 2464 3381 2463 3381 2471 3382 2473 3382 2421 3382 2475 3383 2470 3383 2464 3383 2476 3384 2462 3384 2400 3384 519 3385 2477 3385 2478 3385 519 3386 2479 3386 2477 3386 519 3387 2460 3387 2479 3387 519 3388 521 3388 2460 3388 2480 3389 2464 3389 2474 3389 2476 3390 2400 3390 2338 3390 493 3391 561 3391 563 3391 2481 3392 2482 3392 2483 3392 2481 3393 2484 3393 2482 3393 540 3394 2399 3394 549 3394 493 3395 563 3395 491 3395 2481 3396 2485 3396 2484 3396 2481 3397 2486 3397 2485 3397 2481 3398 2487 3398 2486 3398 2488 3399 2475 3399 2464 3399 517 3400 519 3400 2478 3400 2489 3401 2488 3401 2464 3401 517 3402 2490 3402 2491 3402 517 3403 2478 3403 2490 3403 495 3404 561 3404 493 3404 2492 3405 2493 3405 2472 3405 2492 3406 2472 3406 2471 3406 2494 3407 2464 3407 2480 3407 2495 3408 2440 3408 1541 3408 2496 3409 2338 3409 2497 3409 2495 3410 1541 3410 1696 3410 2495 3411 1696 3411 1692 3411 2498 3412 2487 3412 2481 3412 2496 3413 2476 3413 2338 3413 2499 3414 2464 3414 2494 3414 2495 3415 2500 3415 2440 3415 2499 3416 2501 3416 2464 3416 515 3417 517 3417 2491 3417 515 3418 2491 3418 2502 3418 2503 3419 2489 3419 2464 3419 2504 3420 2505 3420 2493 3420 2504 3421 2506 3421 2505 3421 2504 3422 2493 3422 2492 3422 2507 3423 2508 3423 2453 3423 2507 3424 2509 3424 2508 3424 2507 3425 2510 3425 2511 3425 2507 3426 2511 3426 2509 3426 2512 3427 2513 3427 2500 3427 2507 3428 2453 3428 2452 3428 2512 3429 2502 3429 2513 3429 2512 3430 2500 3430 2495 3430 2514 3431 2515 3431 2510 3431 2514 3432 2516 3432 2515 3432 2517 3433 2514 3433 2510 3433 2518 3434 2519 3434 2520 3434 530 3435 2451 3435 2521 3435 530 3436 2521 3436 2522 3436 2523 3437 515 3437 2502 3437 2524 3438 2518 3438 2520 3438 530 3439 2522 3439 2525 3439 2523 3440 2502 3440 2512 3440 530 3441 529 3441 2451 3441 2526 3442 2501 3442 2499 3442 2527 3443 2506 3443 2504 3443 2526 3444 2524 3444 2520 3444 2527 3445 2528 3445 2506 3445 2526 3446 2520 3446 2501 3446 2529 3447 2530 3447 2519 3447 2531 3448 2523 3448 2532 3448 2533 3449 2534 3449 2517 3449 2529 3450 2519 3450 2518 3450 537 3451 2399 3451 540 3451 2535 3452 2526 3452 2499 3452 2535 3453 2499 3453 2536 3453 2537 3454 2481 3454 2538 3454 2539 3455 2528 3455 2527 3455 2539 3456 2540 3456 2528 3456 2541 3457 2523 3457 2531 3457 2542 3458 2481 3458 2537 3458 2543 3459 2530 3459 2529 3459 2543 3460 2544 3460 2530 3460 2542 3461 2498 3461 2481 3461 2543 3462 2419 3462 2544 3462 2545 3463 2523 3463 2541 3463 2546 3464 2542 3464 2547 3464 2548 3465 2523 3465 2545 3465 2549 3466 2550 3466 2540 3466 2549 3467 2540 3467 2539 3467 2551 3468 2542 3468 2546 3468 2549 3469 2552 3469 2550 3469 2551 3470 2498 3470 2542 3470 2553 3471 2390 3471 2351 3471 2554 3472 515 3472 2523 3472 2553 3473 2351 3473 2419 3473 2553 3474 2419 3474 2543 3474 2555 3475 2533 3475 2517 3475 2554 3476 2523 3476 2548 3476 2556 3477 2535 3477 2536 3477 2554 3478 513 3478 515 3478 2554 3479 511 3479 513 3479 2556 3480 2536 3480 2557 3480 2554 3481 509 3481 511 3481 2554 3482 507 3482 509 3482 2558 3483 2466 3483 561 3483 577 3484 2525 3484 2559 3484 577 3485 2560 3485 2552 3485 577 3486 2559 3486 2560 3486 577 3487 530 3487 2525 3487 2558 3488 561 3488 495 3488 2558 3489 497 3489 499 3489 2561 3490 2390 3490 2553 3490 2558 3491 495 3491 497 3491 2562 3492 2510 3492 2507 3492 2562 3493 2555 3493 2517 3493 2562 3494 2517 3494 2510 3494 2563 3495 2516 3495 2514 3495 2564 3496 2556 3496 2557 3496 2565 3497 2566 3497 2496 3497 2567 3498 2558 3498 499 3498 2565 3499 2568 3499 2566 3499 2565 3500 2569 3500 2568 3500 2564 3501 2557 3501 2570 3501 2563 3502 2571 3502 2516 3502 2563 3503 2572 3503 2571 3503 2573 3504 2567 3504 499 3504 2574 3505 2569 3505 2565 3505 2574 3506 2575 3506 2569 3506 2576 3507 2564 3507 2570 3507 2577 3508 2573 3508 499 3508 2578 3509 2574 3509 2579 3509 2580 3510 507 3510 2554 3510 2581 3511 2564 3511 2576 3511 2580 3512 505 3512 507 3512 2580 3513 503 3513 505 3513 2580 3514 501 3514 503 3514 2580 3515 499 3515 501 3515 2582 3516 2574 3516 2578 3516 2583 3517 2577 3517 499 3517 2584 3518 499 3518 2580 3518 2585 3519 2574 3519 2582 3519 2584 3520 2583 3520 499 3520 2586 3521 2574 3521 2585 3521 1660 3522 1663 3522 1725 3522 2586 3523 2575 3523 2574 3523 1663 3524 1541 3524 2587 3524 1663 3525 2587 3525 2588 3525 1663 3526 2588 3526 2589 3526 2590 3527 2564 3527 2581 3527 1663 3528 2589 3528 2591 3528 1663 3529 2591 3529 2592 3529 1663 3530 2592 3530 2389 3530 2593 3531 2594 3531 2595 3531 2587 3532 1541 3532 2596 3532 2597 3533 577 3533 2552 3533 2596 3534 1541 3534 2598 3534 2597 3535 2552 3535 2549 3535 2598 3536 1541 3536 2497 3536 2497 3537 1541 3537 2599 3537 2497 3538 2599 3538 2600 3538 2497 3539 2600 3539 2601 3539 2602 3540 2562 3540 2507 3540 2497 3541 2601 3541 2603 3541 2497 3542 2603 3542 2537 3542 2497 3543 2537 3543 2538 3543 2497 3544 2538 3544 2430 3544 2604 3545 2496 3545 2497 3545 2605 3546 2564 3546 2590 3546 2497 3547 2430 3547 2344 3547 2497 3548 2344 3548 2346 3548 2599 3549 1541 3549 2606 3549 2607 3550 2399 3550 543 3550 2608 3551 2609 3551 2610 3551 2606 3552 1541 3552 2442 3552 2608 3553 2611 3553 2609 3553 1541 3554 1540 3554 1713 3554 2608 3555 2612 3555 2611 3555 2608 3556 2489 3556 2503 3556 2604 3557 2565 3557 2496 3557 2608 3558 2613 3558 2612 3558 2608 3559 2503 3559 2614 3559 2607 3560 553 3560 555 3560 2608 3561 2614 3561 2613 3561 2607 3562 551 3562 553 3562 2608 3563 2610 3563 2615 3563 2616 3564 2564 3564 2605 3564 2607 3565 547 3565 551 3565 2563 3566 2352 3566 527 3566 2607 3567 543 3567 547 3567 2617 3568 2378 3568 2380 3568 543 3569 2399 3569 537 3569 2617 3570 2380 3570 2618 3570 2619 3571 2593 3571 2595 3571 2608 3572 2615 3572 2620 3572 2621 3573 2575 3573 2586 3573 2622 3574 2623 3574 2624 3574 2622 3575 2620 3575 2623 3575 2622 3576 2608 3576 2620 3576 2346 3577 2604 3577 2497 3577 2625 3578 2498 3578 2551 3578 2625 3579 2626 3579 2498 3579 2627 3580 2626 3580 2625 3580 2628 3581 2622 3581 2624 3581 2629 3582 2607 3582 555 3582 2630 3583 2626 3583 2627 3583 2630 3584 2631 3584 2626 3584 2632 3585 2595 3585 2603 3585 2633 3586 2619 3586 2595 3586 2633 3587 2595 3587 2632 3587 2634 3588 2635 3588 2636 3588 2637 3589 2632 3589 2603 3589 2634 3590 2621 3590 2586 3590 2634 3591 2638 3591 2621 3591 2634 3592 2636 3592 2638 3592 575 3593 2639 3593 2640 3593 575 3594 2597 3594 2639 3594 2641 3595 2619 3595 2633 3595 575 3596 577 3596 2597 3596 2396 3597 2390 3597 2561 3597 2642 3598 2630 3598 2627 3598 2642 3599 2643 3599 2630 3599 2642 3600 2644 3600 2643 3600 2642 3601 2645 3601 2644 3601 2646 3602 2642 3602 2627 3602 2647 3603 2637 3603 2603 3603 2648 3604 2649 3604 2650 3604 2648 3605 2624 3605 2649 3605 2648 3606 2628 3606 2624 3606 2648 3607 2651 3607 2628 3607 2652 3608 2653 3608 2635 3608 2654 3609 2655 3609 2619 3609 2648 3610 2656 3610 2651 3610 2654 3611 2619 3611 2641 3611 2648 3612 2657 3612 2656 3612 2652 3613 2635 3613 2634 3613 479 3614 2658 3614 2659 3614 479 3615 2660 3615 2661 3615 479 3616 2659 3616 2660 3616 2662 3617 2657 3617 2648 3617 2662 3618 2663 3618 2657 3618 2662 3619 2664 3619 2663 3619 2665 3620 2647 3620 2603 3620 2666 3621 2662 3621 2667 3621 482 3622 2572 3622 2563 3622 482 3623 2661 3623 2572 3623 482 3624 479 3624 2661 3624 2668 3625 2662 3625 2666 3625 2669 3626 2664 3626 2662 3626 2669 3627 2670 3627 2664 3627 2671 3628 2655 3628 2654 3628 2669 3629 2672 3629 2670 3629 2671 3630 2673 3630 2655 3630 2669 3631 2662 3631 2668 3631 486 3632 2420 3632 2658 3632 486 3633 2427 3633 2420 3633 486 3634 2658 3634 479 3634 486 3635 2674 3635 2675 3635 486 3636 2675 3636 2427 3636 2676 3637 2653 3637 2652 3637 2676 3638 2677 3638 2653 3638 2676 3639 2678 3639 2677 3639 2679 3640 2646 3640 2627 3640 2679 3641 2352 3641 2646 3641 2680 3642 2673 3642 2671 3642 2681 3643 2673 3643 2680 3643 573 3644 575 3644 2640 3644 2335 3645 2650 3645 2336 3645 2358 3646 2629 3646 555 3646 573 3647 2682 3647 2683 3647 2335 3648 2648 3648 2650 3648 573 3649 2640 3649 2682 3649 2684 3650 2352 3650 2679 3650 2685 3651 2352 3651 2684 3651 2686 3652 2685 3652 2684 3652 527 3653 482 3653 2563 3653 2687 3654 2688 3654 2678 3654 2687 3655 2678 3655 2676 3655 2687 3656 2689 3656 2690 3656 2353 3657 2352 3657 2685 3657 2687 3658 2676 3658 2689 3658 2691 3659 2692 3659 2693 3659 2694 3660 2687 3660 2690 3660 2695 3661 2692 3661 2691 3661 490 3662 2674 3662 486 3662 490 3663 571 3663 2393 3663 490 3664 569 3664 571 3664 490 3665 2393 3665 2674 3665 2391 3666 2696 3666 2688 3666 2391 3667 2683 3667 2696 3667 2697 3668 2698 3668 2699 3668 2616 3669 2700 3669 2701 3669 2697 3670 2699 3670 2702 3670 2616 3671 2605 3671 2700 3671 2697 3672 2702 3672 2665 3672 2391 3673 2688 3673 2687 3673 2391 3674 573 3674 2683 3674 2703 3675 2701 3675 2704 3675 2703 3676 2616 3676 2701 3676 2705 3677 2706 3677 2707 3677 2705 3678 2707 3678 2708 3678 2709 3679 2704 3679 2710 3679 2711 3680 2712 3680 2713 3680 2350 3681 2673 3681 2681 3681 2711 3682 2714 3682 2712 3682 2709 3683 2703 3683 2704 3683 2618 3684 2695 3684 2691 3684 2715 3685 2711 3685 2713 3685 2715 3686 2713 3686 2716 3686 2601 3687 2697 3687 2665 3687 2601 3688 2665 3688 2603 3688 2717 3689 2710 3689 2718 3689 2717 3690 2709 3690 2710 3690 2719 3691 2720 3691 2714 3691 2719 3692 2721 3692 2720 3692 2719 3693 2714 3693 2711 3693 2722 3694 2717 3694 2718 3694 2722 3695 2718 3695 2723 3695 2719 3696 2724 3696 2721 3696 2725 3697 2705 3697 2708 3697 2726 3698 2723 3698 2429 3698 2725 3699 2708 3699 2727 3699 2728 3700 2715 3700 2716 3700 2726 3701 2722 3701 2723 3701 2728 3702 2729 3702 2730 3702 2728 3703 2716 3703 2729 3703 2433 3704 2726 3704 2429 3704 2349 3705 2673 3705 2350 3705 2342 3706 2724 3706 2719 3706 2342 3707 2731 3707 2724 3707 2342 3708 2341 3708 2731 3708 2375 3709 2374 3709 2672 3709 2375 3710 2672 3710 2669 3710 2348 3711 2732 3711 2349 3711 2343 3712 2725 3712 2727 3712 2617 3713 2618 3713 2691 3713 2348 3714 2733 3714 2732 3714 2343 3715 2727 3715 2340 3715 2345 3716 2730 3716 2346 3716 2617 3717 2691 3717 2335 3717 2345 3718 2728 3718 2730 3718 2334 3719 2617 3719 2335 3719 2734 3720 2735 3720 2736 3720 2734 3721 2736 3721 2737 3721 2738 3722 2734 3722 2739 3722 2734 3723 2737 3723 2739 3723 2740 3724 2738 3724 2741 3724 2738 3725 2739 3725 2741 3725 2742 3726 2743 3726 2744 3726 2742 3727 2744 3727 2745 3727 2746 3728 2742 3728 2747 3728 2742 3729 2745 3729 2747 3729 2748 3730 2746 3730 2749 3730 2746 3731 2747 3731 2749 3731 2750 3732 2751 3732 2752 3732 2751 3733 2753 3733 2752 3733 2754 3734 2755 3734 2756 3734 2757 3735 2758 3735 2759 3735 2760 3736 2757 3736 2759 3736 2761 3737 2760 3737 2762 3737 2760 3738 2759 3738 2762 3738 2763 3739 2761 3739 2764 3739 2761 3740 2762 3740 2764 3740 2765 3741 2763 3741 2766 3741 2763 3742 2764 3742 2766 3742 2767 3743 2765 3743 2768 3743 2765 3744 2766 3744 2768 3744 2769 3745 2767 3745 2770 3745 2767 3746 2768 3746 2770 3746 2771 3747 2769 3747 2772 3747 2769 3748 2770 3748 2772 3748 2773 3749 2771 3749 2774 3749 2771 3750 2772 3750 2774 3750 2775 3751 2773 3751 2776 3751 2773 3752 2774 3752 2776 3752 2777 3753 2775 3753 2778 3753 2775 3754 2776 3754 2778 3754 2779 3755 2777 3755 2780 3755 2777 3756 2778 3756 2780 3756 2781 3757 2779 3757 2782 3757 2779 3758 2780 3758 2782 3758 2783 3759 2781 3759 2784 3759 2781 3760 2782 3760 2784 3760 2785 3761 2783 3761 2786 3761 2783 3762 2784 3762 2786 3762 2785 3763 2786 3763 2787 3763 2788 3764 2785 3764 2787 3764 2788 3765 2787 3765 2789 3765 2790 3766 2788 3766 2789 3766 2790 3767 2789 3767 2791 3767 2755 3768 2790 3768 2791 3768 2755 3769 2791 3769 2756 3769 2792 3770 2793 3770 2794 3770 2793 3771 2795 3771 2794 3771 2796 3772 2797 3772 2798 3772 2797 3773 2799 3773 2798 3773 2800 3774 2801 3774 2802 3774 2803 3775 2800 3775 2802 3775 2804 3776 2803 3776 2805 3776 2803 3777 2802 3777 2805 3777 2806 3778 2804 3778 2807 3778 2808 3779 2806 3779 2807 3779 2804 3780 2805 3780 2807 3780 2798 3781 2808 3781 2809 3781 2808 3782 2807 3782 2809 3782 2798 3783 2809 3783 2796 3783 2810 3784 2811 3784 2812 3784 2813 3785 2810 3785 2814 3785 2810 3786 2812 3786 2814 3786 2813 3787 2814 3787 2815 3787 2816 3788 2813 3788 2817 3788 2818 3789 2816 3789 2817 3789 2813 3790 2815 3790 2817 3790 2819 3791 2818 3791 2820 3791 2818 3792 2817 3792 2820 3792 2800 3793 2819 3793 2821 3793 2819 3794 2820 3794 2821 3794 2800 3795 2821 3795 2801 3795 2822 3796 2823 3796 2824 3796 2825 3797 2823 3797 2822 3797 2826 3798 2827 3798 2828 3798 2829 3799 2826 3799 2830 3799 2826 3800 2828 3800 2830 3800 2831 3801 2829 3801 2832 3801 2829 3802 2830 3802 2832 3802 2833 3803 2831 3803 2834 3803 2831 3804 2832 3804 2834 3804 2835 3805 2833 3805 2836 3805 2833 3806 2834 3806 2836 3806 2837 3807 2835 3807 2838 3807 2835 3808 2836 3808 2838 3808 2837 3809 2838 3809 2839 3809 2825 3810 2822 3810 2840 3810 2841 3811 2825 3811 2840 3811 2842 3812 2841 3812 2843 3812 2841 3813 2840 3813 2843 3813 2844 3814 2842 3814 2845 3814 2842 3815 2843 3815 2845 3815 2846 3816 2844 3816 2847 3816 2844 3817 2845 3817 2847 3817 2827 3818 2846 3818 2828 3818 2846 3819 2847 3819 2828 3819 2848 3820 2824 3820 2823 3820 2848 3821 2823 3821 2849 3821 2850 3822 2849 3822 2851 3822 2850 3823 2848 3823 2849 3823 2852 3824 2851 3824 2853 3824 2852 3825 2850 3825 2851 3825 2741 3826 2853 3826 2740 3826 2741 3827 2852 3827 2853 3827 2744 3828 2743 3828 2854 3828 2855 3829 2854 3829 2856 3829 2855 3830 2744 3830 2854 3830 2857 3831 2856 3831 2858 3831 2857 3832 2855 3832 2856 3832 2859 3833 2858 3833 2799 3833 2859 3834 2857 3834 2858 3834 2797 3835 2859 3835 2799 3835 2736 3836 2735 3836 2860 3836 2861 3837 2860 3837 2862 3837 2861 3838 2736 3838 2860 3838 2863 3839 2862 3839 2753 3839 2863 3840 2861 3840 2862 3840 2751 3841 2863 3841 2753 3841 2792 3842 2794 3842 2864 3842 2865 3843 2864 3843 2866 3843 2865 3844 2792 3844 2864 3844 2867 3845 2866 3845 2748 3845 2867 3846 2865 3846 2866 3846 2749 3847 2867 3847 2748 3847 2754 3848 2756 3848 2868 3848 2869 3849 2754 3849 2868 3849 2870 3850 2869 3850 2871 3850 2869 3851 2868 3851 2871 3851 2752 3852 2870 3852 2750 3852 2870 3853 2871 3853 2750 3853 2795 3854 2793 3854 2872 3854 2873 3855 2795 3855 2872 3855 2874 3856 2873 3856 2875 3856 2873 3857 2872 3857 2875 3857 2757 3858 2874 3858 2758 3858 2874 3859 2875 3859 2758 3859 1542 3860 1541 3860 1663 3860 1553 3861 1549 3861 1656 3861 1549 3862 1542 3862 1656 3862 1542 3863 1663 3863 1656 3863 1555 3864 1553 3864 1652 3864 1553 3865 1656 3865 1652 3865 1561 3866 1559 3866 1651 3866 1559 3867 1555 3867 1651 3867 1555 3868 1652 3868 1651 3868 1566 3869 1561 3869 1649 3869 1561 3870 1651 3870 1649 3870 1571 3871 1569 3871 1646 3871 1569 3872 1566 3872 1646 3872 1566 3873 1649 3873 1646 3873 1575 3874 1571 3874 1643 3874 1571 3875 1646 3875 1643 3875 1578 3876 1575 3876 1638 3876 1575 3877 1643 3877 1638 3877 1578 3878 1638 3878 1635 3878 2876 3879 2877 3879 2878 3879 2879 3880 2880 3880 2881 3880 2876 3881 2878 3881 2882 3881 2879 3882 2883 3882 2880 3882 2884 3883 2885 3883 2886 3883 2887 3884 2888 3884 2889 3884 2887 3885 2889 3885 2033 3885 2884 3886 2890 3886 2885 3886 2882 3887 2878 3887 2891 3887 2892 3888 2882 3888 2891 3888 2893 3889 2894 3889 2895 3889 2896 3890 2897 3890 2898 3890 2893 3891 2895 3891 2890 3891 2892 3892 2891 3892 2899 3892 2900 3893 2901 3893 2902 3893 2892 3894 2899 3894 2903 3894 2904 3895 2033 3895 2032 3895 2904 3896 2032 3896 2892 3896 2893 3897 2890 3897 2884 3897 2904 3898 2892 3898 2903 3898 2904 3899 2903 3899 2888 3899 2904 3900 2887 3900 2033 3900 2900 3901 2902 3901 2905 3901 2904 3902 2888 3902 2887 3902 2906 3903 2886 3903 2907 3903 2906 3904 2884 3904 2886 3904 2908 3905 2905 3905 2909 3905 2908 3906 2900 3906 2905 3906 2910 3907 2911 3907 2912 3907 2913 3908 1698 3908 1695 3908 2914 3909 2881 3909 2915 3909 2914 3910 2915 3910 1568 3910 2916 3911 2893 3911 2884 3911 2917 3912 2901 3912 2900 3912 2918 3913 2884 3913 2906 3913 2918 3914 2916 3914 2884 3914 2917 3915 2919 3915 2901 3915 2917 3916 2920 3916 2919 3916 2921 3917 2913 3917 1695 3917 2922 3918 2881 3918 2914 3918 2922 3919 2879 3919 2881 3919 2923 3920 2909 3920 2924 3920 2925 3921 2921 3921 1695 3921 2926 3922 2927 3922 2928 3922 2926 3923 2929 3923 2927 3923 2926 3924 2930 3924 2929 3924 2931 3925 2932 3925 1698 3925 2923 3926 2924 3926 2933 3926 2923 3927 2933 3927 2883 3927 2931 3928 1698 3928 2913 3928 2934 3929 2920 3929 2917 3929 2934 3930 2898 3930 2920 3930 2935 3931 2898 3931 2934 3931 2936 3932 2894 3932 2893 3932 2936 3933 2937 3933 2927 3933 2936 3934 2927 3934 2894 3934 2938 3935 2879 3935 2922 3935 2939 3936 2912 3936 2897 3936 2939 3937 2897 3937 2896 3937 2940 3938 2941 3938 2942 3938 2939 3939 2910 3939 2912 3939 2943 3940 2917 3940 2900 3940 2943 3941 2900 3941 2908 3941 2940 3942 2932 3942 2931 3942 2940 3943 2942 3943 2932 3943 2944 3944 2917 3944 2943 3944 2945 3945 2931 3945 2913 3945 2944 3946 2934 3946 2917 3946 2945 3947 2913 3947 2921 3947 2946 3948 2935 3948 2934 3948 2946 3949 2934 3949 2944 3949 2947 3950 2939 3950 2896 3950 2948 3951 2941 3951 2940 3951 2949 3952 2931 3952 2945 3952 2949 3953 2940 3953 2931 3953 2950 3954 2935 3954 2946 3954 2951 3955 2923 3955 2883 3955 2951 3956 2883 3956 2879 3956 2952 3957 2953 3957 2941 3957 2952 3958 2941 3958 2948 3958 2951 3959 2879 3959 2938 3959 2954 3960 2945 3960 2921 3960 2955 3961 1568 3961 1564 3961 2954 3962 2921 3962 2925 3962 2956 3963 2936 3963 2893 3963 2955 3964 2914 3964 1568 3964 2956 3965 2893 3965 2916 3965 2957 3966 2922 3966 2914 3966 2957 3967 2914 3967 2955 3967 2958 3968 2909 3968 2923 3968 2959 3969 2960 3969 2953 3969 2959 3970 2907 3970 2960 3970 2959 3971 2953 3971 2952 3971 2961 3972 2962 3972 2956 3972 2961 3973 2956 3973 2916 3973 2961 3974 2963 3974 2962 3974 2961 3975 2916 3975 2918 3975 2964 3976 2949 3976 2945 3976 2965 3977 2938 3977 2922 3977 2965 3978 2922 3978 2957 3978 2964 3979 2945 3979 2954 3979 2966 3980 2955 3980 1564 3980 2967 3981 2907 3981 2959 3981 2966 3982 2957 3982 2955 3982 2967 3983 2906 3983 2907 3983 2968 3984 2948 3984 2940 3984 2969 3985 2908 3985 2909 3985 2969 3986 2909 3986 2958 3986 2968 3987 2940 3987 2949 3987 2970 3988 2952 3988 2948 3988 2971 3989 2951 3989 2938 3989 2970 3990 2948 3990 2968 3990 2972 3991 2965 3991 2957 3991 2972 3992 2957 3992 2966 3992 2973 3993 2949 3993 2964 3993 2974 3994 2975 3994 2976 3994 2974 3995 2976 3995 2911 3995 2973 3996 2968 3996 2949 3996 2977 3997 2952 3997 2970 3997 2977 3998 2959 3998 2952 3998 2978 3999 2943 3999 2908 3999 2978 4000 2908 4000 2969 4000 2979 4001 2954 4001 2925 4001 2980 4002 2923 4002 2951 4002 2979 4003 2925 4003 1695 4003 2981 4004 1673 4004 1672 4004 2980 4005 2958 4005 2923 4005 2981 4006 1672 4006 1711 4006 2982 4007 2959 4007 2977 4007 2980 4008 2951 4008 2971 4008 2982 4009 2967 4009 2959 4009 2983 4010 2981 4010 1711 4010 2984 4011 2939 4011 2947 4011 2983 4012 2985 4012 1673 4012 2983 4013 1673 4013 2981 4013 2984 4014 2910 4014 2939 4014 2986 4015 2944 4015 2943 4015 2987 4016 2985 4016 2983 4016 2988 4017 2989 4017 2985 4017 2990 4018 2970 4018 2968 4018 2990 4019 2968 4019 2973 4019 2988 4020 2985 4020 2987 4020 2986 4021 2943 4021 2978 4021 2991 4022 2969 4022 2958 4022 2992 4023 2977 4023 2970 4023 2992 4024 2970 4024 2990 4024 2993 4025 2983 4025 1711 4025 2993 4026 2987 4026 2983 4026 2994 4027 2982 4027 2977 4027 2995 4028 2993 4028 1711 4028 2991 4029 2958 4029 2980 4029 2995 4030 1711 4030 1708 4030 2994 4031 2977 4031 2992 4031 2996 4032 2997 4032 2989 4032 2996 4033 2989 4033 2988 4033 2998 4034 2946 4034 2944 4034 2998 4035 2950 4035 2946 4035 2999 4036 2979 4036 1695 4036 2998 4037 2944 4037 2986 4037 3000 4038 1708 4038 1704 4038 3001 4039 2950 4039 2998 4039 3002 4040 2954 4040 2979 4040 3003 4041 1708 4041 3000 4041 3002 4042 2964 4042 2954 4042 3003 4043 2995 4043 1708 4043 3004 4044 2966 4044 1564 4044 3005 4045 2996 4045 2988 4045 3005 4046 2987 4046 2993 4046 3005 4047 2988 4047 2987 4047 3006 4048 2898 4048 2935 4048 3007 4049 2964 4049 3002 4049 3008 4050 3000 4050 1704 4050 3006 4051 2935 4051 2950 4051 3006 4052 2896 4052 2898 4052 3007 4053 2973 4053 2964 4053 3009 4054 3010 4054 2984 4054 3009 4055 2984 4055 2947 4055 3011 4056 3000 4056 3008 4056 3011 4057 3003 4057 3000 4057 3012 4058 2906 4058 2967 4058 3013 4059 2938 4059 2965 4059 3014 4060 2993 4060 2995 4060 3013 4061 2971 4061 2938 4061 3015 4062 2991 4062 2980 4062 3015 4063 2980 4063 2971 4063 3014 4064 3005 4064 2993 4064 3016 4065 3002 4065 2979 4065 3016 4066 2979 4066 2999 4066 3017 4067 2997 4067 2996 4067 3017 4068 2996 4068 3005 4068 3018 4069 2966 4069 3004 4069 3019 4070 3008 4070 1704 4070 3020 4071 2990 4071 2973 4071 3018 4072 2972 4072 2966 4072 3021 4073 2974 4073 2911 4073 3021 4074 2910 4074 2984 4074 3021 4075 2984 4075 3010 4075 3020 4076 2973 4076 3007 4076 3021 4077 2911 4077 2910 4077 3022 4078 1564 4078 1563 4078 2962 4079 2937 4079 2936 4079 3023 4080 3019 4080 1704 4080 2962 4081 2936 4081 2956 4081 3022 4082 3004 4082 1564 4082 3024 4083 2992 4083 2990 4083 3025 4084 3008 4084 3019 4084 3025 4085 3019 4085 3023 4085 3024 4086 2990 4086 3020 4086 3026 4087 2978 4087 2969 4087 3026 4088 2969 4088 2991 4088 3027 4089 3002 4089 3016 4089 3028 4090 3011 4090 3008 4090 3028 4091 3008 4091 3025 4091 3029 4092 3026 4092 2991 4092 3027 4093 3007 4093 3002 4093 3029 4094 2991 4094 3015 4094 3030 4095 3025 4095 3023 4095 3031 4096 2967 4096 2982 4096 3032 4097 3013 4097 2965 4097 3033 4098 2995 4098 3003 4098 3032 4099 2965 4099 2972 4099 3031 4100 3012 4100 2967 4100 3033 4101 3014 4101 2995 4101 3034 4102 3022 4102 1563 4102 3034 4103 3004 4103 3022 4103 3034 4104 3018 4104 3004 4104 3035 4105 2994 4105 2992 4105 3036 4106 2986 4106 2978 4106 3036 4107 2978 4107 3026 4107 3035 4108 2992 4108 3024 4108 3037 4109 3028 4109 3025 4109 3037 4110 3025 4110 3030 4110 3038 4111 2994 4111 3035 4111 3039 4112 3031 4112 2982 4112 3040 4113 3005 4113 3014 4113 3040 4114 3017 4114 3005 4114 3039 4115 2982 4115 2994 4115 3039 4116 2994 4116 3038 4116 3041 4117 3006 4117 2950 4117 3042 4118 3003 4118 3011 4118 3043 4119 2998 4119 2986 4119 3042 4120 3033 4120 3003 4120 3043 4121 2986 4121 3036 4121 3044 4122 2906 4122 3012 4122 3045 4123 3014 4123 3033 4123 3044 4124 2918 4124 2906 4124 3045 4125 3040 4125 3014 4125 3046 4126 1695 4126 1691 4126 3047 4127 3033 4127 3042 4127 3048 4128 3001 4128 2998 4128 3047 4129 3045 4129 3033 4129 3048 4130 2998 4130 3043 4130 3049 4131 3020 4131 3007 4131 3050 4132 2896 4132 3006 4132 3049 4133 3024 4133 3020 4133 3051 4134 3017 4134 3040 4134 3049 4135 3007 4135 3027 4135 3051 4136 3040 4136 3045 4136 3050 4137 3006 4137 3041 4137 3050 4138 2947 4138 2896 4138 3052 4139 3011 4139 3028 4139 3052 4140 3042 4140 3011 4140 3052 4141 3047 4141 3042 4141 3053 4142 3026 4142 3029 4142 3054 4143 3024 4143 3049 4143 3053 4144 3036 4144 3026 4144 3055 4145 3043 4145 3036 4145 3056 4146 2999 4146 1695 4146 3056 4147 3016 4147 2999 4147 3057 4148 3028 4148 3037 4148 3057 4149 3052 4149 3028 4149 3056 4150 1695 4150 3046 4150 3055 4151 3036 4151 3053 4151 3058 4152 3024 4152 3054 4152 3059 4153 3051 4153 3045 4153 3060 4154 3015 4154 2971 4154 3058 4155 3035 4155 3024 4155 3060 4156 3029 4156 3015 4156 3061 4157 3035 4157 3058 4157 3062 4158 1704 4158 1703 4158 3060 4159 2971 4159 3013 4159 3062 4160 3023 4160 1704 4160 3061 4161 3038 4161 3035 4161 3063 4162 3034 4162 1563 4162 3064 4163 3047 4163 3052 4163 3065 4164 3012 4164 3031 4164 3066 4165 3043 4165 3055 4165 3065 4166 3044 4166 3012 4166 3067 4167 3045 4167 3047 4167 3066 4168 3048 4168 3043 4168 3067 4169 3059 4169 3045 4169 3068 4170 3065 4170 3031 4170 3069 4171 3052 4171 3057 4171 3069 4172 3064 4172 3052 4172 3068 4173 3031 4173 3039 4173 3070 4174 3048 4174 3066 4174 3071 4175 2972 4175 3018 4175 3072 4176 3056 4176 3046 4176 3071 4177 3032 4177 2972 4177 3073 4178 3027 4178 3016 4178 3073 4179 3056 4179 3072 4179 3074 4180 3023 4180 3062 4180 3075 4181 3053 4181 3029 4181 3075 4182 3029 4182 3060 4182 3073 4183 3016 4183 3056 4183 3076 4184 2963 4184 2961 4184 3077 4185 3023 4185 3074 4185 3076 4186 2961 4186 2918 4186 3078 4187 3050 4187 3041 4187 3076 4188 2918 4188 3044 4188 3079 4189 3027 4189 3073 4189 3080 4190 3062 4190 1703 4190 3081 4191 3060 4191 3013 4191 3081 4192 3013 4192 3032 4192 3079 4193 3049 4193 3027 4193 3082 4194 3037 4194 3030 4194 3082 4195 3030 4195 3023 4195 3082 4196 3023 4196 3077 4196 3083 4197 3018 4197 3034 4197 3083 4198 3034 4198 3063 4198 3084 4199 3046 4199 1691 4199 3083 4200 3071 4200 3018 4200 3085 4201 3075 4201 3060 4201 3086 4202 3046 4202 3084 4202 3087 4203 3037 4203 3082 4203 3085 4204 3060 4204 3081 4204 3088 4205 3038 4205 3061 4205 3089 4206 3080 4206 1703 4206 3088 4207 3068 4207 3039 4207 3090 4208 3053 4208 3075 4208 3088 4209 3039 4209 3038 4209 3090 4210 3075 4210 3085 4210 3091 4211 2950 4211 3001 4211 3092 4212 3072 4212 3046 4212 3093 4213 3074 4213 3062 4213 3092 4214 3046 4214 3086 4214 3091 4215 3041 4215 2950 4215 3093 4216 3062 4216 3080 4216 3094 4217 3086 4217 3084 4217 3094 4218 3084 4218 1691 4218 3093 4219 3080 4219 3089 4219 3095 4220 3053 4220 3090 4220 3096 4221 3086 4221 3094 4221 3096 4222 3092 4222 3086 4222 3097 4223 3077 4223 3074 4223 3097 4224 3074 4224 3093 4224 3098 4225 3044 4225 3065 4225 3095 4226 3055 4226 3053 4226 3099 4227 3093 4227 3089 4227 3100 4228 3090 4228 3085 4228 3098 4229 3076 4229 3044 4229 3101 4230 3073 4230 3072 4230 3099 4231 3097 4231 3093 4231 3102 4232 3097 4232 3099 4232 3103 4233 3055 4233 3095 4233 3101 4234 3079 4234 3073 4234 3103 4235 3066 4235 3055 4235 3104 4236 3049 4236 3079 4236 3105 4237 3082 4237 3077 4237 3105 4238 3097 4238 3102 4238 3106 4239 3066 4239 3103 4239 3104 4240 3054 4240 3049 4240 3105 4241 3077 4241 3097 4241 3106 4242 3070 4242 3066 4242 3107 4243 3082 4243 3105 4243 3108 4244 3054 4244 3104 4244 3109 4245 3083 4245 3063 4245 3108 4246 3058 4246 3054 4246 3110 4247 3092 4247 3096 4247 3107 4248 3087 4248 3082 4248 3111 4249 3105 4249 3102 4249 3112 4250 3095 4250 3090 4250 3112 4251 3090 4251 3100 4251 3113 4252 3098 4252 3065 4252 3113 4253 3065 4253 3068 4253 3113 4254 3114 4254 3098 4254 3111 4255 3107 4255 3105 4255 3115 4256 3107 4256 3111 4256 3116 4257 3032 4257 3071 4257 3117 4258 3104 4258 3079 4258 3116 4259 3081 4259 3032 4259 3117 4260 3079 4260 3101 4260 3118 4261 2947 4261 3050 4261 3118 4262 3119 4262 3010 4262 3118 4263 3009 4263 2947 4263 3120 4264 3047 4264 3064 4264 3118 4265 3010 4265 3009 4265 3120 4266 3067 4266 3047 4266 3121 4267 3088 4267 3061 4267 3122 4268 3123 4268 3124 4268 3118 4269 3050 4269 3078 4269 3125 4270 3061 4270 3058 4270 3122 4271 3120 4271 3064 4271 3126 4272 3103 4272 3095 4272 3122 4273 3064 4273 3069 4273 3127 4274 3059 4274 3128 4274 3127 4275 3051 4275 3059 4275 3125 4276 3058 4276 3108 4276 3127 4277 3017 4277 3051 4277 3127 4278 2997 4278 3017 4278 3126 4279 3095 4279 3112 4279 3129 4280 3061 4280 3125 4280 3130 4281 3106 4281 3103 4281 3129 4282 3121 4282 3061 4282 3131 4283 1703 4283 1698 4283 3130 4284 3103 4284 3126 4284 3132 4285 3113 4285 3068 4285 3133 4286 3085 4286 3081 4286 3132 4287 3068 4287 3088 4287 3133 4288 3081 4288 3116 4288 3134 4289 3104 4289 3117 4289 3134 4290 3108 4290 3104 4290 3135 4291 3089 4291 1703 4291 3135 4292 1703 4292 3131 4292 3128 4293 3067 4293 3120 4293 3136 4294 3083 4294 3109 4294 3128 4295 3059 4295 3067 4295 3128 4296 3120 4296 3124 4296 3136 4297 3116 4297 3071 4297 3136 4298 3071 4298 3083 4298 3137 4299 3125 4299 3108 4299 3137 4300 3108 4300 3134 4300 3138 4301 3057 4301 3037 4301 3139 4302 3072 4302 3092 4302 3139 4303 3101 4303 3072 4303 3138 4304 3037 4304 3087 4304 3139 4305 3092 4305 3110 4305 3140 4306 3001 4306 3048 4306 3140 4307 3048 4307 3070 4307 3140 4308 3091 4308 3001 4308 3141 4309 3089 4309 3135 4309 3142 4310 3116 4310 3136 4310 3141 4311 3099 4311 3089 4311 3142 4312 3133 4312 3116 4312 3143 4313 3129 4313 3125 4313 3144 4314 1558 4314 1557 4314 3143 4315 3125 4315 3137 4315 3144 4316 1563 4316 1558 4316 3145 4317 3111 4317 3102 4317 3146 4318 3041 4318 3091 4318 3145 4319 3099 4319 3141 4319 3147 4320 3129 4320 3143 4320 3148 4321 3132 4321 3088 4321 3145 4322 3102 4322 3099 4322 3149 4323 3131 4323 1698 4323 3146 4324 3078 4324 3041 4324 3148 4325 3088 4325 3121 4325 3149 4326 3135 4326 3131 4326 3150 4327 1563 4327 3144 4327 3151 4328 3111 4328 3145 4328 3150 4329 3144 4329 1557 4329 3152 4330 3139 4330 3110 4330 3153 4331 3118 4331 3078 4331 2963 4332 3076 4332 3098 4332 3154 4333 3115 4333 3111 4333 3154 4334 3111 4334 3151 4334 3155 4335 3085 4335 3133 4335 3156 4336 3101 4336 3139 4336 3156 4337 3139 4337 3152 4337 3155 4338 3100 4338 3085 4338 3157 4339 1557 4339 2046 4339 3156 4340 3117 4340 3101 4340 3157 4341 3109 4341 3063 4341 3157 4342 3063 4342 1563 4342 3157 4343 1563 4343 3150 4343 3157 4344 3150 4344 1557 4344 3158 4345 3087 4345 3107 4345 3158 4346 3107 4346 3115 4346 3159 4347 3112 4347 3100 4347 3160 4348 3094 4348 1691 4348 3158 4349 3138 4349 3087 4349 3160 4350 1691 4350 1572 4350 3159 4351 3100 4351 3155 4351 3161 4352 3158 4352 3115 4352 3162 4353 3132 4353 3148 4353 3163 4354 3140 4354 3070 4354 3162 4355 3113 4355 3132 4355 3164 4356 3135 4356 3149 4356 3165 4357 3136 4357 3109 4357 3166 4358 3134 4358 3117 4358 3167 4359 3057 4359 3138 4359 3165 4360 3142 4360 3136 4360 3166 4361 3117 4361 3156 4361 3167 4362 3069 4362 3057 4362 3168 4363 3141 4363 3135 4363 3169 4364 3133 4364 3142 4364 3169 4365 3155 4365 3133 4365 3170 4366 3094 4366 3160 4366 3170 4367 3096 4367 3094 4367 3168 4368 3135 4368 3164 4368 3171 4369 3126 4369 3112 4369 3172 4370 3156 4370 3152 4370 3173 4371 3141 4371 3168 4371 3171 4372 3112 4372 3159 4372 3172 4373 3166 4373 3156 4373 3173 4374 3145 4374 3141 4374 3174 4375 3126 4375 3171 4375 3175 4376 3096 4376 3170 4376 3124 4377 3120 4377 3122 4377 3174 4378 3130 4378 3126 4378 3176 4379 3159 4379 3155 4379 3176 4380 3155 4380 3169 4380 3177 4381 3121 4381 3129 4381 3178 4382 3158 4382 3161 4382 3178 4383 3167 4383 3138 4383 3177 4384 3129 4384 3147 4384 3178 4385 3138 4385 3158 4385 3177 4386 3148 4386 3121 4386 3114 4387 2963 4387 3098 4387 3179 4388 3142 4388 3165 4388 3179 4389 3169 4389 3142 4389 3180 4390 3151 4390 3145 4390 2902 4391 3166 4391 3172 4391 3180 4392 3145 4392 3173 4392 3181 4393 3146 4393 3091 4393 3181 4394 3091 4394 3140 4394 3181 4395 3140 4395 3163 4395 3182 4396 3096 4396 3175 4396 3183 4397 3154 4397 3151 4397 3182 4398 3110 4398 3096 4398 3183 4399 3151 4399 3180 4399 3184 4400 3171 4400 3159 4400 3185 4401 3170 4401 3160 4401 3184 4402 3159 4402 3176 4402 3186 4403 3178 4403 3161 4403 3185 4404 3160 4404 1572 4404 3187 4405 3174 4405 3171 4405 2976 4406 3162 4406 3148 4406 3188 4407 3149 4407 1698 4407 3187 4408 3171 4408 3184 4408 3189 4409 3176 4409 3169 4409 3189 4410 3169 4410 3179 4410 3190 4411 3137 4411 3134 4411 3191 4412 3122 4412 3069 4412 3190 4413 3166 4413 2902 4413 3190 4414 3134 4414 3166 4414 3191 4415 3069 4415 3167 4415 3192 4416 3114 4416 3113 4416 3193 4417 3181 4417 3163 4417 3192 4418 3162 4418 2975 4418 3192 4419 3113 4419 3162 4419 3194 4420 3176 4420 3189 4420 3195 4421 3164 4421 3149 4421 3196 4422 3175 4422 3170 4422 3194 4423 3184 4423 3176 4423 3196 4424 3170 4424 3185 4424 3195 4425 3149 4425 3188 4425 3197 4426 3137 4426 3190 4426 3198 4427 3165 4427 3109 4427 3198 4428 3109 4428 3157 4428 3199 4429 3115 4429 3154 4429 3198 4430 3157 4430 2046 4430 3197 4431 3143 4431 3137 4431 3200 4432 3070 4432 3106 4432 3199 4433 3161 4433 3115 4433 3200 4434 3163 4434 3070 4434 3201 4435 3182 4435 3175 4435 3201 4436 3175 4436 3196 4436 3202 4437 3168 4437 3164 4437 3203 4438 3187 4438 3184 4438 3202 4439 3164 4439 3195 4439 3203 4440 3184 4440 3194 4440 3204 4441 3143 4441 3197 4441 3204 4442 3147 4442 3143 4442 3205 4443 3167 4443 3178 4443 3206 4444 3078 4444 3146 4444 2901 4445 3190 4445 2902 4445 3205 4446 3178 4446 3186 4446 3206 4447 3153 4447 3078 4447 3205 4448 3191 4448 3167 4448 3207 4449 3173 4449 3168 4449 3208 4450 3187 4450 3203 4450 2901 4451 3197 4451 3190 4451 3207 4452 3168 4452 3202 4452 3209 4453 3106 4453 3130 4453 3210 4454 3147 4454 3204 4454 3211 4455 3188 4455 1698 4455 3209 4456 3200 4456 3106 4456 2933 4457 3182 4457 3201 4457 3119 4458 3153 4458 3212 4458 3119 4459 3118 4459 3153 4459 2930 4460 2926 4460 3213 4460 3214 4461 3181 4461 3193 4461 3214 4462 3206 4462 3146 4462 2930 4463 3205 4463 3186 4463 3214 4464 3146 4464 3181 4464 3215 4465 3147 4465 3210 4465 3215 4466 3177 4466 3147 4466 3216 4467 3193 4467 3163 4467 3216 4468 3163 4468 3200 4468 2932 4469 3211 4469 1698 4469 2919 4470 3204 4470 3197 4470 2919 4471 3197 4471 2901 4471 3217 4472 3180 4472 3173 4472 3218 4473 3148 4473 3177 4473 3217 4474 3173 4474 3207 4474 3219 4475 3165 4475 3198 4475 3218 4476 3177 4476 3215 4476 3218 4477 2976 4477 3148 4477 2885 4478 3180 4478 3217 4478 3219 4479 3198 4479 2046 4479 3219 4480 3179 4480 3165 4480 2885 4481 3183 4481 3180 4481 2920 4482 3204 4482 2919 4482 2920 4483 3210 4483 3204 4483 3220 4484 3188 4484 3211 4484 3221 4485 3130 4485 3174 4485 3220 4486 3195 4486 3188 4486 3221 4487 3209 4487 3130 4487 3221 4488 3174 4488 3187 4488 3222 4489 3200 4489 3209 4489 3222 4490 3216 4490 3200 4490 2942 4491 3220 4491 3211 4491 2898 4492 3210 4492 2920 4492 2942 4493 3211 4493 2932 4493 3212 4494 3153 4494 3206 4494 3223 4495 3189 4495 3179 4495 3224 4496 3152 4496 3110 4496 3225 4497 2930 4497 3186 4497 3223 4498 3179 4498 3219 4498 3224 4499 3110 4499 3182 4499 3224 4500 3182 4500 2933 4500 3223 4501 3219 4501 2046 4501 3225 4502 3186 4502 3161 4502 3225 4503 3161 4503 3199 4503 3226 4504 3214 4504 3193 4504 2912 4505 3218 4505 3215 4505 3227 4506 3187 4506 3208 4506 2895 4507 3199 4507 3154 4507 2895 4508 3154 4508 3183 4508 3228 4509 3185 4509 1572 4509 3227 4510 3221 4510 3187 4510 3229 4511 3195 4511 3220 4511 3230 4512 3223 4512 2046 4512 3230 4513 3189 4513 3223 4513 3229 4514 3202 4514 3195 4514 3231 4515 3194 4515 3189 4515 3232 4516 3207 4516 3202 4516 2924 4517 3224 4517 2933 4517 3233 4518 3196 4518 3185 4518 3232 4519 3202 4519 3229 4519 3231 4520 3230 4520 2046 4520 3231 4521 3189 4521 3230 4521 3233 4522 3185 4522 3228 4522 3234 4523 3203 4523 3194 4523 2941 4524 3229 4524 3220 4524 2880 4525 3201 4525 3196 4525 2941 4526 3220 4526 2942 4526 3234 4527 3194 4527 3231 4527 3234 4528 3231 4528 2046 4528 3235 4529 3222 4529 3209 4529 2880 4530 3196 4530 3233 4530 2883 4531 2933 4531 3201 4531 3235 4532 3209 4532 3221 4532 2883 4533 3201 4533 2880 4533 2953 4534 3232 4534 3229 4534 2975 4535 3162 4535 2976 4535 2953 4536 3229 4536 2941 4536 3236 4537 3208 4537 3203 4537 3237 4538 3172 4538 3152 4538 3236 4539 3234 4539 2046 4539 3238 4540 3207 4540 3232 4540 3236 4541 3203 4541 3234 4541 3239 4542 3227 4542 3208 4542 3237 4543 3152 4543 3224 4543 3238 4544 3232 4544 2953 4544 3238 4545 3217 4545 3207 4545 3237 4546 3224 4546 2924 4546 3240 4547 3227 4547 3239 4547 3240 4548 3221 4548 3227 4548 3241 4549 1572 4549 1568 4549 3241 4550 3228 4550 1572 4550 3240 4551 3235 4551 3221 4551 2886 4552 3217 4552 3238 4552 2886 4553 2885 4553 3217 4553 2877 4554 3226 4554 3193 4554 2960 4555 3238 4555 2953 4555 2911 4556 3218 4556 2912 4556 2877 4557 3193 4557 3216 4557 2911 4558 2976 4558 3218 4558 2878 4559 2877 4559 3216 4559 2905 4560 3172 4560 3237 4560 2878 4561 3216 4561 3222 4561 2907 4562 2886 4562 3238 4562 2907 4563 3238 4563 2960 4563 2905 4564 2902 4564 3172 4564 2888 4565 3240 4565 3239 4565 2894 4566 3225 4566 3199 4566 2894 4567 3199 4567 2895 4567 3242 4568 3214 4568 3226 4568 2915 4569 3228 4569 3241 4569 3242 4570 3212 4570 3206 4570 3242 4571 3206 4571 3214 4571 2915 4572 3233 4572 3228 4572 2915 4573 3241 4573 1568 4573 3123 4574 3122 4574 3191 4574 3123 4575 3191 4575 3205 4575 2891 4576 3222 4576 3235 4576 2929 4577 2930 4577 3225 4577 2891 4578 2878 4578 3222 4578 2881 4579 3233 4579 2915 4579 2881 4580 2880 4580 3233 4580 2890 4581 2895 4581 3183 4581 2890 4582 3183 4582 2885 4582 2899 4583 3235 4583 3240 4583 2899 4584 3240 4584 2888 4584 2899 4585 2891 4585 3235 4585 2889 4586 2046 4586 2033 4586 2897 4587 3215 4587 3210 4587 2897 4588 3210 4588 2898 4588 2889 4589 3208 4589 3236 4589 2897 4590 2912 4590 3215 4590 3213 4591 3205 4591 2930 4591 2889 4592 3236 4592 2046 4592 3213 4593 3123 4593 3205 4593 2889 4594 3239 4594 3208 4594 2889 4595 2888 4595 3239 4595 2927 4596 2937 4596 2928 4596 2927 4597 3225 4597 2894 4597 2927 4598 2929 4598 3225 4598 2903 4599 2899 4599 2888 4599 2909 4600 2905 4600 3237 4600 2909 4601 3237 4601 2924 4601 2876 4602 3242 4602 3226 4602 2876 4603 3226 4603 2877 4603 3243 4604 3244 4604 3245 4604 3246 4605 3247 4605 3248 4605 3249 4606 3250 4606 3251 4606 3249 4607 3251 4607 3252 4607 3253 4608 3254 4608 3255 4608 3253 4609 3255 4609 3256 4609 3257 4610 3258 4610 3259 4610 3260 4611 3261 4611 3262 4611 3263 4612 1731 4612 1727 4612 3264 4613 3265 4613 3258 4613 3264 4614 3258 4614 3257 4614 3263 4615 3245 4615 1731 4615 3264 4616 3266 4616 3267 4616 3264 4617 3268 4617 3265 4617 3264 4618 3267 4618 3268 4618 3269 4619 3259 4619 3270 4619 3271 4620 3272 4620 3273 4620 3269 4621 3257 4621 3259 4621 3271 4622 3262 4622 3272 4622 3271 4623 3273 4623 3274 4623 3275 4624 3243 4624 3245 4624 3276 4625 3253 4625 3256 4625 3276 4626 3256 4626 3247 4626 3275 4627 3245 4627 3263 4627 3276 4628 3247 4628 3246 4628 3277 4629 3278 4629 3261 4629 3277 4630 3279 4630 3278 4630 3277 4631 3280 4631 3279 4631 3281 4632 3270 4632 3254 4632 3281 4633 3254 4633 3253 4633 3282 4634 3283 4634 3250 4634 3284 4635 3253 4635 3276 4635 3282 4636 3250 4636 3249 4636 3284 4637 3281 4637 3253 4637 3285 4638 3276 4638 3246 4638 3285 4639 3284 4639 3276 4639 3286 4640 3287 4640 3283 4640 3288 4641 3289 4641 1721 4641 3286 4642 3283 4642 3282 4642 3290 4643 3291 4643 3289 4643 3292 4644 3243 4644 3275 4644 3292 4645 3252 4645 3243 4645 3292 4646 3249 4646 3252 4646 3290 4647 3289 4647 3288 4647 3293 4648 3269 4648 3270 4648 3293 4649 3270 4649 3281 4649 3294 4650 3271 4650 3274 4650 3295 4651 3296 4651 3291 4651 3297 4652 3298 4652 3287 4652 3295 4653 3291 4653 3290 4653 3297 4654 3287 4654 3286 4654 3299 4655 3300 4655 3266 4655 3301 4656 3271 4656 3294 4656 3299 4657 3302 4657 3300 4657 3299 4658 3264 4658 3257 4658 3299 4659 3266 4659 3264 4659 3301 4660 3260 4660 3262 4660 3301 4661 3262 4661 3271 4661 3303 4662 3248 4662 3296 4662 3303 4663 3246 4663 3248 4663 3304 4664 3275 4664 3263 4664 3303 4665 3296 4665 3295 4665 3305 4666 3298 4666 3297 4666 3306 4667 3288 4667 1721 4667 3305 4668 3274 4668 3298 4668 3307 4669 3277 4669 3261 4669 3308 4670 3288 4670 3306 4670 3308 4671 3290 4671 3288 4671 3307 4672 3309 4672 3280 4672 3308 4673 3295 4673 3290 4673 3307 4674 3280 4674 3277 4674 3307 4675 3261 4675 3260 4675 3310 4676 3304 4676 3263 4676 3311 4677 3284 4677 3285 4677 3310 4678 3263 4678 1727 4678 3312 4679 3246 4679 3303 4679 3313 4680 3274 4680 3305 4680 3314 4681 3257 4681 3269 4681 3313 4682 3294 4682 3274 4682 3314 4683 3315 4683 3302 4683 3314 4684 3299 4684 3257 4684 3316 4685 3249 4685 3292 4685 3314 4686 3302 4686 3299 4686 3317 4687 3295 4687 3308 4687 3316 4688 3282 4688 3249 4688 3318 4689 3284 4689 3311 4689 3318 4690 3281 4690 3284 4690 3318 4691 3293 4691 3281 4691 3319 4692 3303 4692 3295 4692 3320 4693 3282 4693 3316 4693 3320 4694 3286 4694 3282 4694 3319 4695 3295 4695 3317 4695 3321 4696 3292 4696 3275 4696 3321 4697 3275 4697 3304 4697 3322 4698 1721 4698 1722 4698 3322 4699 3306 4699 1721 4699 3323 4700 3308 4700 3306 4700 3323 4701 3306 4701 3322 4701 3324 4702 3301 4702 3294 4702 3325 4703 3286 4703 3320 4703 3325 4704 3297 4704 3286 4704 3326 4705 3303 4705 3319 4705 3326 4706 3312 4706 3303 4706 3327 4707 3323 4707 3322 4707 3327 4708 1722 4708 1769 4708 3327 4709 3322 4709 1722 4709 3328 4710 3305 4710 3297 4710 3329 4711 3308 4711 3323 4711 3328 4712 3297 4712 3325 4712 3329 4713 3317 4713 3308 4713 3330 4714 3321 4714 3304 4714 3331 4715 3319 4715 3317 4715 3331 4716 3317 4716 3329 4716 3330 4717 3304 4717 3310 4717 3331 4718 3326 4718 3319 4718 3332 4719 3318 4719 3311 4719 3333 4720 3305 4720 3328 4720 3333 4721 3313 4721 3305 4721 3334 4722 3323 4722 3327 4722 3334 4723 3327 4723 1769 4723 3334 4724 3329 4724 3323 4724 3335 4725 3330 4725 3310 4725 3336 4726 3326 4726 3331 4726 3337 4727 3316 4727 3292 4727 3338 4728 3331 4728 3329 4728 3338 4729 3334 4729 1769 4729 3337 4730 3292 4730 3321 4730 3338 4731 3329 4731 3334 4731 3337 4732 3321 4732 3330 4732 3339 4733 3336 4733 3331 4733 3339 4734 3331 4734 3338 4734 3340 4735 3246 4735 3312 4735 3341 4736 3325 4736 3320 4736 3341 4737 3320 4737 3316 4737 3341 4738 3316 4738 3337 4738 3342 4739 1639 4739 1636 4739 3340 4740 3285 4740 3246 4740 3342 4741 1641 4741 1639 4741 3343 4742 3260 4742 3301 4742 3340 4743 3311 4743 3285 4743 3343 4744 3307 4744 3260 4744 3344 4745 1641 4745 3342 4745 3345 4746 3346 4746 3315 4746 3345 4747 3315 4747 3314 4747 3345 4748 3314 4748 3269 4748 3347 4749 1641 4749 3344 4749 3345 4750 3269 4750 3293 4750 3348 4751 3340 4751 3312 4751 3349 4752 3325 4752 3341 4752 3350 4753 1641 4753 3347 4753 3350 4754 1867 4754 1641 4754 3351 4755 3301 4755 3324 4755 3352 4756 1636 4756 1634 4756 3348 4757 3312 4757 3326 4757 3351 4758 3343 4758 3301 4758 3352 4759 3342 4759 1636 4759 3352 4760 3344 4760 3342 4760 3353 4761 3347 4761 3344 4761 3354 4762 3311 4762 3340 4762 3355 4763 3328 4763 3325 4763 3355 4764 3325 4764 3349 4764 3356 4765 3293 4765 3318 4765 3353 4766 3352 4766 1634 4766 3353 4767 3344 4767 3352 4767 3356 4768 3318 4768 3332 4768 3357 4769 3330 4769 3335 4769 3356 4770 3345 4770 3293 4770 3356 4771 3346 4771 3345 4771 3357 4772 3337 4772 3330 4772 3358 4773 3350 4773 3347 4773 3357 4774 3341 4774 3337 4774 3358 4775 3347 4775 3353 4775 3359 4776 3326 4776 3336 4776 3359 4777 3348 4777 3326 4777 3360 4778 3349 4778 3341 4778 3361 4779 1867 4779 3350 4779 3360 4780 3341 4780 3357 4780 3362 4781 3353 4781 1634 4781 3362 4782 1634 4782 1630 4782 3362 4783 3358 4783 3353 4783 3363 4784 3340 4784 3348 4784 3363 4785 3354 4785 3340 4785 3364 4786 3357 4786 3335 4786 3364 4787 3360 4787 3357 4787 3365 4788 3359 4788 3336 4788 3366 4789 3361 4789 3350 4789 3366 4790 3350 4790 3358 4790 3365 4791 3336 4791 3339 4791 3367 4792 3360 4792 3364 4792 3346 4793 3368 4793 3369 4793 3370 4794 1867 4794 3361 4794 3370 4795 3361 4795 3366 4795 3369 4796 3346 4796 3356 4796 3369 4797 3356 4797 3332 4797 3371 4798 3328 4798 3355 4798 3371 4799 3333 4799 3328 4799 3372 4800 1867 4800 3370 4800 3373 4801 3348 4801 3359 4801 3374 4802 3366 4802 3358 4802 3373 4803 3363 4803 3348 4803 3375 4804 3294 4804 3313 4804 3374 4805 3358 4805 3362 4805 3375 4806 3324 4806 3294 4806 3376 4807 3311 4807 3354 4807 3377 4808 1867 4808 3372 4808 3378 4809 1867 4809 3377 4809 3376 4810 3332 4810 3311 4810 3379 4811 3355 4811 3349 4811 3380 4812 3359 4812 3365 4812 3379 4813 3349 4813 3360 4813 3380 4814 3373 4814 3359 4814 3379 4815 3360 4815 3367 4815 3381 4816 3371 4816 3355 4816 3382 4817 3338 4817 1769 4817 3382 4818 3339 4818 3338 4818 3383 4819 3370 4819 3366 4819 3381 4820 3355 4820 3379 4820 3384 4821 3379 4821 3367 4821 3384 4822 3381 4822 3379 4822 3385 4823 3370 4823 3383 4823 3386 4824 3365 4824 3339 4824 3386 4825 3339 4825 3382 4825 3387 4826 3381 4826 3384 4826 3385 4827 3372 4827 3370 4827 3388 4828 3371 4828 3381 4828 3389 4829 3354 4829 3363 4829 3388 4830 3381 4830 3387 4830 3390 4831 1867 4831 3378 4831 3389 4832 3376 4832 3354 4832 3391 4833 3377 4833 3372 4833 3392 4834 3363 4834 3373 4834 3391 4835 3372 4835 3385 4835 3392 4836 3389 4836 3363 4836 3393 4837 3388 4837 3387 4837 3394 4838 3382 4838 1769 4838 3394 4839 3386 4839 3382 4839 3395 4840 3377 4840 3391 4840 3396 4841 3373 4841 3380 4841 3397 4842 3351 4842 3324 4842 3395 4843 3378 4843 3377 4843 3397 4844 3324 4844 3375 4844 3396 4845 3392 4845 3373 4845 3398 4846 3375 4846 3313 4846 3398 4847 3313 4847 3333 4847 3399 4848 3394 4848 1769 4848 3400 4849 3366 4849 3374 4849 3401 4850 1769 4850 1767 4850 3402 4851 3390 4851 3378 4851 3309 4852 3307 4852 3343 4852 3402 4853 3378 4853 3395 4853 3401 4854 3399 4854 1769 4854 3403 4855 3375 4855 3398 4855 3404 4856 3368 4856 3369 4856 3404 4857 3369 4857 3332 4857 3404 4858 3332 4858 3376 4858 3405 4859 3362 4859 1630 4859 3405 4860 3374 4860 3362 4860 3403 4861 3397 4861 3375 4861 3406 4862 3371 4862 3388 4862 3406 4863 3398 4863 3333 4863 3407 4864 3366 4864 3400 4864 3407 4865 3383 4865 3366 4865 3408 4866 3380 4866 3365 4866 3406 4867 3333 4867 3371 4867 3408 4868 3365 4868 3386 4868 3406 4869 3403 4869 3398 4869 3409 4870 3410 4870 3309 4870 3411 4871 3404 4871 3376 4871 3409 4872 3309 4872 3343 4872 3411 4873 3368 4873 3404 4873 3411 4874 3412 4874 3368 4874 3409 4875 3343 4875 3351 4875 3413 4876 3351 4876 3397 4876 3411 4877 3376 4877 3389 4877 3414 4878 1767 4878 1766 4878 3415 4879 3383 4879 3407 4879 3414 4880 3401 4880 1767 4880 3413 4881 3409 4881 3351 4881 3416 4882 3388 4882 3393 4882 3415 4883 3385 4883 3383 4883 3416 4884 3406 4884 3388 4884 3417 4885 3396 4885 3380 4885 3418 4886 1867 4886 3390 4886 3417 4887 3380 4887 3408 4887 3418 4888 1861 4888 1867 4888 3419 4889 3416 4889 3393 4889 3420 4890 3394 4890 3399 4890 3420 4891 3408 4891 3386 4891 3420 4892 3386 4892 3394 4892 3421 4893 3391 4893 3385 4893 3422 4894 3406 4894 3416 4894 3421 4895 3385 4895 3415 4895 3423 4896 3395 4896 3391 4896 3422 4897 3403 4897 3406 4897 3424 4898 3411 4898 3389 4898 3424 4899 3412 4899 3411 4899 3424 4900 3389 4900 3392 4900 3423 4901 3391 4901 3421 4901 3424 4902 3425 4902 3412 4902 3426 4903 3310 4903 1727 4903 3427 4904 3400 4904 3374 4904 3426 4905 3335 4905 3310 4905 3427 4906 3374 4906 3405 4906 3428 4907 3420 4907 3399 4907 3429 4908 3413 4908 3397 4908 3430 4909 3402 4909 3395 4909 3431 4910 3424 4910 3392 4910 3431 4911 3425 4911 3424 4911 3431 4912 3392 4912 3396 4912 3430 4913 3395 4913 3423 4913 3432 4914 3399 4914 3401 4914 3429 4915 3397 4915 3403 4915 3433 4916 1630 4916 1627 4916 3434 4917 3426 4917 1727 4917 3432 4918 3428 4918 3399 4918 3435 4919 3390 4919 3402 4919 3436 4920 3408 4920 3420 4920 3436 4921 3417 4921 3408 4921 3435 4922 3402 4922 3430 4922 3435 4923 3418 4923 3390 4923 3437 4924 3422 4924 3416 4924 3438 4925 3405 4925 1630 4925 3437 4926 3416 4926 3419 4926 3439 4927 3436 4927 3420 4927 3438 4928 1630 4928 3433 4928 3440 4929 3437 4929 3419 4929 3439 4930 3420 4930 3428 4930 3441 4931 1861 4931 3418 4931 3442 4932 3431 4932 3396 4932 3442 4933 3396 4933 3417 4933 3443 4934 3407 4934 3400 4934 3444 4935 3335 4935 3426 4935 3443 4936 3400 4936 3427 4936 3444 4937 3364 4937 3335 4937 3445 4938 3401 4938 3414 4938 3445 4939 3432 4939 3401 4939 3446 4940 3407 4940 3443 4940 3446 4941 3415 4941 3407 4941 3447 4942 3428 4942 3432 4942 3447 4943 3439 4943 3428 4943 3448 4944 3421 4944 3415 4944 3449 4945 3417 4945 3436 4945 3450 4946 3364 4946 3444 4946 3448 4947 3423 4947 3421 4947 3449 4948 3442 4948 3417 4948 3450 4949 3367 4949 3364 4949 3448 4950 3415 4950 3446 4950 3451 4951 3434 4951 1727 4951 3452 4952 3447 4952 3432 4952 3453 4953 3418 4953 3435 4953 3452 4954 3432 4954 3445 4954 3453 4955 3441 4955 3418 4955 3454 4956 1627 4956 1623 4956 3455 4957 3436 4957 3439 4957 3455 4958 3449 4958 3436 4958 3456 4959 3367 4959 3450 4959 3456 4960 3384 4960 3367 4960 3457 4961 3423 4961 3448 4961 3458 4962 3444 4962 3426 4962 3459 4963 3439 4963 3447 4963 3457 4964 3430 4964 3423 4964 3458 4965 3434 4965 3451 4965 3459 4966 3455 4966 3439 4966 3458 4967 3426 4967 3434 4967 3460 4968 1765 4968 1763 4968 3461 4969 3433 4969 1627 4969 3462 4970 3403 4970 3422 4970 3461 4971 1627 4971 3454 4971 3462 4972 3429 4972 3403 4972 3463 4973 3414 4973 1766 4973 3463 4974 3445 4974 3414 4974 3464 4975 3430 4975 3457 4975 3465 4976 3450 4976 3444 4976 3466 4977 1766 4977 1765 4977 3465 4978 3444 4978 3458 4978 3467 4979 3387 4979 3384 4979 3467 4980 3384 4980 3456 4980 3468 4981 1762 4981 1761 4981 3468 4982 1763 4982 1762 4982 3469 4983 3427 4983 3405 4983 3468 4984 3460 4984 1763 4984 3469 4985 3405 4985 3438 4985 3425 4986 3470 4986 3471 4986 3431 4987 3425 4987 3471 4987 3472 4988 3393 4988 3387 4988 3472 4989 3387 4989 3467 4989 3471 4990 3431 4990 3442 4990 3473 4991 3454 4991 1623 4991 3474 4992 3466 4992 1765 4992 3474 4993 1765 4993 3460 4993 3474 4994 3460 4994 3468 4994 3475 4995 3433 4995 3461 4995 3475 4996 3438 4996 3433 4996 3476 4997 3447 4997 3452 4997 3476 4998 3459 4998 3447 4998 3477 4999 3450 4999 3465 4999 3477 5000 3456 5000 3450 5000 3478 5001 1761 5001 3479 5001 3480 5002 3435 5002 3430 5002 3478 5003 3468 5003 1761 5003 3478 5004 3474 5004 3468 5004 3481 5005 3482 5005 3410 5005 3483 5006 3452 5006 3445 5006 3484 5007 1859 5007 1861 5007 3481 5008 3409 5008 3413 5008 3484 5009 1861 5009 3441 5009 3483 5010 3445 5010 3463 5010 3481 5011 3410 5011 3409 5011 3485 5012 3442 5012 3449 5012 3486 5013 3454 5013 3473 5013 3486 5014 3461 5014 3454 5014 3485 5015 3470 5015 3471 5015 3487 5016 3475 5016 3461 5016 3485 5017 3471 5017 3442 5017 3488 5018 3467 5018 3456 5018 3487 5019 3461 5019 3486 5019 3489 5020 3485 5020 3449 5020 3488 5021 3456 5021 3477 5021 3489 5022 3470 5022 3485 5022 3489 5023 3490 5023 3470 5023 3489 5024 3449 5024 3455 5024 3491 5025 3422 5025 3437 5025 3492 5026 3489 5026 3455 5026 3491 5027 3462 5027 3422 5027 3492 5028 3493 5028 3490 5028 3494 5029 3427 5029 3469 5029 3494 5030 3446 5030 3443 5030 3492 5031 3490 5031 3489 5031 3494 5032 3443 5032 3427 5032 3492 5033 3455 5033 3459 5033 3495 5034 3437 5034 3440 5034 3492 5035 3459 5035 3476 5035 3495 5036 3491 5036 3437 5036 3496 5037 1766 5037 3466 5037 3496 5038 3463 5038 1766 5038 3497 5039 3458 5039 3451 5039 3497 5040 3465 5040 3458 5040 3498 5041 3446 5041 3494 5041 3499 5042 3496 5042 3466 5042 3499 5043 3466 5043 3474 5043 3500 5044 3465 5044 3497 5044 3499 5045 3474 5045 3478 5045 3501 5046 3499 5046 3478 5046 3500 5047 3477 5047 3465 5047 3501 5048 3478 5048 3479 5048 3502 5049 3492 5049 3476 5049 3503 5050 3475 5050 3487 5050 3502 5051 3504 5051 3493 5051 3502 5052 3493 5052 3492 5052 3505 5053 1859 5053 3484 5053 3502 5054 3476 5054 3452 5054 3505 5055 3484 5055 3441 5055 3502 5056 3452 5056 3483 5056 3506 5057 3472 5057 3467 5057 3505 5058 3441 5058 3453 5058 3507 5059 3463 5059 3496 5059 3506 5060 3467 5060 3488 5060 3508 5061 3477 5061 3500 5061 3509 5062 3435 5062 3480 5062 3509 5063 3453 5063 3435 5063 3507 5064 3483 5064 3463 5064 3510 5065 3499 5065 3501 5065 3508 5066 3488 5066 3477 5066 3511 5067 3446 5067 3498 5067 3512 5068 3488 5068 3508 5068 3510 5069 3507 5069 3496 5069 3511 5070 3457 5070 3448 5070 3510 5071 3496 5071 3499 5071 3513 5072 3501 5072 3479 5072 3513 5073 3510 5073 3501 5073 3512 5074 3506 5074 3488 5074 3511 5075 3448 5075 3446 5075 3513 5076 3479 5076 3514 5076 3515 5077 3438 5077 3475 5077 3516 5078 3504 5078 3502 5078 3516 5079 3502 5079 3483 5079 3482 5080 3517 5080 3518 5080 3516 5081 3483 5081 3507 5081 3518 5082 3413 5082 3429 5082 3518 5083 3482 5083 3481 5083 3518 5084 3481 5084 3413 5084 3515 5085 3475 5085 3503 5085 3519 5086 3504 5086 3516 5086 3520 5087 3506 5087 3512 5087 3519 5088 3507 5088 3510 5088 3515 5089 3469 5089 3438 5089 3519 5090 3516 5090 3507 5090 3521 5091 3514 5091 3504 5091 3521 5092 3510 5092 3513 5092 3522 5093 3457 5093 3511 5093 3521 5094 3513 5094 3514 5094 3521 5095 3519 5095 3510 5095 3521 5096 3504 5096 3519 5096 3523 5097 3451 5097 1727 5097 3523 5098 3497 5098 3451 5098 3524 5099 3457 5099 3522 5099 3524 5100 3464 5100 3457 5100 3525 5101 3473 5101 1623 5101 3526 5102 3419 5102 3393 5102 3525 5103 3486 5103 3473 5103 3526 5104 3393 5104 3472 5104 3527 5105 3518 5105 3429 5105 3527 5106 3528 5106 3517 5106 3527 5107 3517 5107 3518 5107 3529 5108 3480 5108 3430 5108 3529 5109 3430 5109 3464 5109 3527 5110 3429 5110 3462 5110 3530 5111 3523 5111 1727 5111 3531 5112 3486 5112 3525 5112 3531 5113 3487 5113 3486 5113 3531 5114 3503 5114 3487 5114 3532 5115 3526 5115 3472 5115 3533 5116 3515 5116 3503 5116 3532 5117 3506 5117 3520 5117 3532 5118 3472 5118 3506 5118 3534 5119 3523 5119 3530 5119 3535 5120 3525 5120 1623 5120 3534 5121 3497 5121 3523 5121 3535 5122 3531 5122 3525 5122 3534 5123 3500 5123 3497 5123 3536 5124 3500 5124 3534 5124 3537 5125 3469 5125 3515 5125 3536 5126 3508 5126 3500 5126 3537 5127 3515 5127 3533 5127 3537 5128 3494 5128 3469 5128 3538 5129 3498 5129 3494 5129 3538 5130 3494 5130 3537 5130 3539 5131 3419 5131 3526 5131 3539 5132 3440 5132 3419 5132 3540 5133 3503 5133 3531 5133 3541 5134 3542 5134 3528 5134 3541 5135 3527 5135 3462 5135 3541 5136 3528 5136 3527 5136 3543 5137 3531 5137 3535 5137 3541 5138 3462 5138 3491 5138 3543 5139 3540 5139 3531 5139 3544 5140 3541 5140 3491 5140 3544 5141 3542 5141 3541 5141 3545 5142 1859 5142 3505 5142 3545 5143 3453 5143 3509 5143 3544 5144 3491 5144 3495 5144 3545 5145 3505 5145 3453 5145 3546 5146 3508 5146 3536 5146 3547 5147 3509 5147 3480 5147 3547 5148 3480 5148 3529 5148 3546 5149 3512 5149 3508 5149 3548 5150 3511 5150 3498 5150 3549 5151 3534 5151 3530 5151 3550 5152 3536 5152 3534 5152 3548 5153 3498 5153 3538 5153 3550 5154 3534 5154 3549 5154 3551 5155 3520 5155 3512 5155 3551 5156 3512 5156 3546 5156 3552 5157 3540 5157 3543 5157 3553 5158 3522 5158 3511 5158 3553 5159 3511 5159 3548 5159 3554 5160 3532 5160 3520 5160 3555 5161 3539 5161 3526 5161 3556 5162 3537 5162 3533 5162 3555 5163 3526 5163 3532 5163 3556 5164 3538 5164 3537 5164 3555 5165 3532 5165 3554 5165 3557 5166 3520 5166 3551 5166 3558 5167 3548 5167 3538 5167 3558 5168 3538 5168 3556 5168 3557 5169 3554 5169 3520 5169 3559 5170 3546 5170 3536 5170 3559 5171 3536 5171 3550 5171 3560 5172 3522 5172 3553 5172 3560 5173 3524 5173 3522 5173 3561 5174 3546 5174 3559 5174 3561 5175 3551 5175 3546 5175 3561 5176 3557 5176 3551 5176 3562 5177 3533 5177 3503 5177 3562 5178 3503 5178 3540 5178 3562 5179 3540 5179 3552 5179 3255 5180 3557 5180 3561 5180 3563 5181 3530 5181 1727 5181 3564 5182 3553 5182 3548 5182 3564 5183 3548 5183 3558 5183 3565 5184 3464 5184 3524 5184 3565 5185 3529 5185 3464 5185 3566 5186 3555 5186 3554 5186 3567 5187 3553 5187 3564 5187 3567 5188 3560 5188 3553 5188 3568 5189 3440 5189 3539 5189 3272 5190 3560 5190 3567 5190 3568 5191 3495 5191 3440 5191 3265 5192 3555 5192 3566 5192 3265 5193 3539 5193 3555 5193 3251 5194 3562 5194 3552 5194 3265 5195 3568 5195 3539 5195 3569 5196 1727 5196 1721 5196 3569 5197 3563 5197 1727 5197 3570 5198 3549 5198 3530 5198 3571 5199 3545 5199 3509 5199 3571 5200 3280 5200 1859 5200 3571 5201 3509 5201 3547 5201 3571 5202 1859 5202 3545 5202 3570 5203 3530 5203 3563 5203 3572 5204 3562 5204 3251 5204 3570 5205 3563 5205 3569 5205 3573 5206 3550 5206 3549 5206 3572 5207 3533 5207 3562 5207 3572 5208 3556 5208 3533 5208 3573 5209 3549 5209 3570 5209 3574 5210 3558 5210 3556 5210 3574 5211 3556 5211 3572 5211 3575 5212 3554 5212 3557 5212 3575 5213 3557 5213 3255 5213 3575 5214 3566 5214 3554 5214 3574 5215 3564 5215 3558 5215 3278 5216 3529 5216 3565 5216 3576 5217 3550 5217 3573 5217 3278 5218 3547 5218 3529 5218 3577 5219 1623 5219 1731 5219 3576 5220 3559 5220 3550 5220 3577 5221 3535 5221 1623 5221 3577 5222 3543 5222 3535 5222 3250 5223 3574 5223 3572 5223 3578 5224 3559 5224 3576 5224 3250 5225 3572 5225 3251 5225 3578 5226 3561 5226 3559 5226 3258 5227 3265 5227 3566 5227 3579 5228 3564 5228 3574 5228 3579 5229 3567 5229 3564 5229 3283 5230 3574 5230 3250 5230 3580 5231 3569 5231 1721 5231 3283 5232 3579 5232 3574 5232 3580 5233 3570 5233 3569 5233 3580 5234 3573 5234 3570 5234 3256 5235 3561 5235 3578 5235 3581 5236 3567 5236 3579 5236 3256 5237 3255 5237 3561 5237 3244 5238 3543 5238 3577 5238 3582 5239 3573 5239 3580 5239 3244 5240 3552 5240 3543 5240 3254 5241 3575 5241 3255 5241 3583 5242 3565 5242 3524 5242 3583 5243 3524 5243 3560 5243 3583 5244 3560 5244 3272 5244 3259 5245 3258 5245 3566 5245 3273 5246 3272 5246 3567 5246 3273 5247 3567 5247 3581 5247 3259 5248 3566 5248 3575 5248 3584 5249 3573 5249 3582 5249 3584 5250 3576 5250 3573 5250 3287 5251 3581 5251 3579 5251 3287 5252 3579 5252 3283 5252 3585 5253 3578 5253 3576 5253 3585 5254 3256 5254 3578 5254 3585 5255 3576 5255 3584 5255 3252 5256 3552 5256 3244 5256 3252 5257 3251 5257 3552 5257 3247 5258 3256 5258 3585 5258 3298 5259 3273 5259 3581 5259 3289 5260 3580 5260 1721 5260 3298 5261 3581 5261 3287 5261 3289 5262 3582 5262 3580 5262 3291 5263 3584 5263 3582 5263 3291 5264 3582 5264 3289 5264 3274 5265 3273 5265 3298 5265 3262 5266 3583 5266 3272 5266 3586 5267 3542 5267 3544 5267 3542 5268 3267 5268 3586 5268 3586 5269 3544 5269 3495 5269 3586 5270 3495 5270 3568 5270 3270 5271 3575 5271 3254 5271 3270 5272 3259 5272 3575 5272 3261 5273 3565 5273 3583 5273 3261 5274 3583 5274 3262 5274 3261 5275 3278 5275 3565 5275 3279 5276 3571 5276 3547 5276 3279 5277 3547 5277 3278 5277 3296 5278 3585 5278 3584 5278 3279 5279 3280 5279 3571 5279 3296 5280 3584 5280 3291 5280 3245 5281 3244 5281 3577 5281 3268 5282 3267 5282 3586 5282 3268 5283 3586 5283 3568 5283 3245 5284 3577 5284 1731 5284 3268 5285 3568 5285 3265 5285 3248 5286 3247 5286 3585 5286 3248 5287 3585 5287 3296 5287 3243 5288 3252 5288 3244 5288 3587 5289 3588 5289 3589 5289 3590 5290 3591 5290 3592 5290 3590 5291 3593 5291 3591 5291 3594 5292 3595 5292 3596 5292 3597 5293 3598 5293 3599 5293 3600 5294 3601 5294 3602 5294 3597 5295 3603 5295 3598 5295 3600 5296 3587 5296 3601 5296 3600 5297 3596 5297 3588 5297 3600 5298 3588 5298 3587 5298 3604 5299 1680 5299 3595 5299 3605 5300 3592 5300 3606 5300 3605 5301 3590 5301 3592 5301 3607 5302 3595 5302 3594 5302 3608 5303 1677 5303 1674 5303 3608 5304 1674 5304 3593 5304 3607 5305 3604 5305 3595 5305 3609 5306 3600 5306 3602 5306 3609 5307 3594 5307 3596 5307 3608 5308 3593 5308 3590 5308 3609 5309 3596 5309 3600 5309 3610 5310 3611 5310 3601 5310 3610 5311 3612 5311 3611 5311 3613 5312 1681 5312 1680 5312 3610 5313 3614 5313 3612 5313 3610 5314 3615 5314 3614 5314 3613 5315 1680 5315 3604 5315 3616 5316 3604 5316 3607 5316 3616 5317 1681 5317 3613 5317 3616 5318 3613 5318 3604 5318 3617 5319 3606 5319 3618 5319 3619 5320 3609 5320 3602 5320 3617 5321 3605 5321 3606 5321 3619 5322 3607 5322 3594 5322 3619 5323 3594 5323 3609 5323 3620 5324 3605 5324 3617 5324 3620 5325 3590 5325 3605 5325 3620 5326 3608 5326 3590 5326 3621 5327 3619 5327 3602 5327 3622 5328 3617 5328 3618 5328 3621 5329 3616 5329 3607 5329 3621 5330 3607 5330 3619 5330 3623 5331 1683 5331 1681 5331 3623 5332 3621 5332 3602 5332 3622 5333 3603 5333 3597 5333 3623 5334 3602 5334 1683 5334 3622 5335 3618 5335 3603 5335 3623 5336 1681 5336 3616 5336 3623 5337 3616 5337 3621 5337 3624 5338 3599 5338 3625 5338 3624 5339 3597 5339 3599 5339 3626 5340 3624 5340 3625 5340 3626 5341 3625 5341 3615 5341 3627 5342 3620 5342 3617 5342 1685 5343 1683 5343 3602 5343 3628 5344 1678 5344 1677 5344 3629 5345 2989 5345 2997 5345 3628 5346 3608 5346 3620 5346 3629 5347 2985 5347 2989 5347 3628 5348 3620 5348 3627 5348 3628 5349 1677 5349 3608 5349 3629 5350 2997 5350 3630 5350 3631 5351 3622 5351 3597 5351 3631 5352 3597 5352 3624 5352 3632 5353 3629 5353 3630 5353 3633 5354 3617 5354 3622 5354 3634 5355 3632 5355 3630 5355 3635 5356 3628 5356 3627 5356 3598 5357 3634 5357 3630 5357 3635 5358 1678 5358 3628 5358 3636 5359 3631 5359 3624 5359 3636 5360 3624 5360 3626 5360 3637 5361 3630 5361 3638 5361 3639 5362 3627 5362 3617 5362 3639 5363 3617 5363 3633 5363 3639 5364 3635 5364 3627 5364 3640 5365 2985 5365 3629 5365 3641 5366 3615 5366 3610 5366 3641 5367 3610 5367 3601 5367 3614 5368 3637 5368 3638 5368 3641 5369 3636 5369 3626 5369 3641 5370 3626 5370 3615 5370 3642 5371 3622 5371 3631 5371 3591 5372 1673 5372 2985 5372 3642 5373 3633 5373 3622 5373 3591 5374 2985 5374 3640 5374 3643 5375 3629 5375 3632 5375 3643 5376 3640 5376 3629 5376 3644 5377 3635 5377 3639 5377 3589 5378 3631 5378 3636 5378 3589 5379 3642 5379 3631 5379 3599 5380 3598 5380 3630 5380 3599 5381 3630 5381 3637 5381 3645 5382 3639 5382 3633 5382 3645 5383 3633 5383 3642 5383 3646 5384 3643 5384 3632 5384 3647 5385 3641 5385 3601 5385 3646 5386 3632 5386 3634 5386 3647 5387 3636 5387 3641 5387 3611 5388 3638 5388 3612 5388 3638 5389 3614 5389 3612 5389 3588 5390 3642 5390 3589 5390 3588 5391 3645 5391 3642 5391 3648 5392 1680 5392 1678 5392 3592 5393 3591 5393 3640 5393 3592 5394 3640 5394 3643 5394 3648 5395 3635 5395 3644 5395 3603 5396 3634 5396 3598 5396 3648 5397 1678 5397 3635 5397 3603 5398 3646 5398 3634 5398 3649 5399 3639 5399 3645 5399 3593 5400 1674 5400 1673 5400 3649 5401 3644 5401 3639 5401 3593 5402 1673 5402 3591 5402 3649 5403 3648 5403 3644 5403 3625 5404 3637 5404 3614 5404 3625 5405 3599 5405 3637 5405 3596 5406 3649 5406 3645 5406 3596 5407 3645 5407 3588 5407 3650 5408 3647 5408 3601 5408 3650 5409 3589 5409 3636 5409 3650 5410 3636 5410 3647 5410 3615 5411 3625 5411 3614 5411 3595 5412 1680 5412 3648 5412 3606 5413 3643 5413 3646 5413 3595 5414 3648 5414 3649 5414 3606 5415 3592 5415 3643 5415 3606 5416 3646 5416 3603 5416 3595 5417 3649 5417 3596 5417 3587 5418 3650 5418 3601 5418 3618 5419 3606 5419 3603 5419 3587 5420 3589 5420 3650 5420 3651 5421 3652 5421 3653 5421 3651 5422 3653 5422 3654 5422 3651 5423 3654 5423 3655 5423 3656 5424 3657 5424 3658 5424 3656 5425 3659 5425 3657 5425 3660 5426 3651 5426 3655 5426 3660 5427 3655 5427 3661 5427 3662 5428 3663 5428 3664 5428 3662 5429 3664 5429 3652 5429 3665 5430 3663 5430 3662 5430 3665 5431 3658 5431 3663 5431 3666 5432 3659 5432 3656 5432 3667 5433 3652 5433 3651 5433 3667 5434 3662 5434 3652 5434 3667 5435 3651 5435 3660 5435 3668 5436 3667 5436 3660 5436 3669 5437 3661 5437 3670 5437 3669 5438 3660 5438 3661 5438 3671 5439 3656 5439 3658 5439 3671 5440 3658 5440 3665 5440 3672 5441 3673 5441 3659 5441 1748 5442 3673 5442 1752 5442 3674 5443 3675 5443 3676 5443 3677 5444 3669 5444 3670 5444 3674 5445 3676 5445 3678 5445 3677 5446 3679 5446 3479 5446 3677 5447 3670 5447 3679 5447 3680 5448 3662 5448 3667 5448 3681 5449 3674 5449 3678 5449 3680 5450 3667 5450 3668 5450 3680 5451 3665 5451 3662 5451 3682 5452 3666 5452 3656 5452 3682 5453 3656 5453 3671 5453 3683 5454 3675 5454 3674 5454 3684 5455 3680 5455 3668 5455 3654 5456 3678 5456 3685 5456 3686 5457 3673 5457 3672 5457 3654 5458 3681 5458 3678 5458 3686 5459 1752 5459 3673 5459 3687 5460 3674 5460 3681 5460 3688 5461 3660 5461 3669 5461 3688 5462 3668 5462 3660 5462 3688 5463 3669 5463 3677 5463 3687 5464 3683 5464 3674 5464 3689 5465 3671 5465 3665 5465 3689 5466 3665 5466 3680 5466 3689 5467 3680 5467 3684 5467 3690 5468 3675 5468 3683 5468 3690 5469 3683 5469 3687 5469 3691 5470 3666 5470 3682 5470 3691 5471 3672 5471 3659 5471 3691 5472 3682 5472 1753 5472 3655 5473 3654 5473 3685 5473 3691 5474 3659 5474 3666 5474 3692 5475 3689 5475 3684 5475 3661 5476 3655 5476 3685 5476 3693 5477 3682 5477 3671 5477 3693 5478 3671 5478 3689 5478 3693 5479 3689 5479 3692 5479 3664 5480 3690 5480 3687 5480 3694 5481 3479 5481 1761 5481 3694 5482 3677 5482 3479 5482 3695 5483 3675 5483 3690 5483 3694 5484 3688 5484 3677 5484 3696 5485 1759 5485 1756 5485 3696 5486 3693 5486 3692 5486 3697 5487 1753 5487 1752 5487 3653 5488 3681 5488 3654 5488 3697 5489 3691 5489 1753 5489 3653 5490 3687 5490 3681 5490 3697 5491 1752 5491 3686 5491 3697 5492 3686 5492 3672 5492 3697 5493 3672 5493 3691 5493 3698 5494 3688 5494 3694 5494 3698 5495 3684 5495 3668 5495 3698 5496 3668 5496 3688 5496 3699 5497 3675 5497 3695 5497 3700 5498 1756 5498 1753 5498 3700 5499 1753 5499 3682 5499 3700 5500 3696 5500 1756 5500 3700 5501 3693 5501 3696 5501 3700 5502 3682 5502 3693 5502 3701 5503 1760 5503 1759 5503 3657 5504 3675 5504 3699 5504 3701 5505 3698 5505 1760 5505 3701 5506 3692 5506 3684 5506 3670 5507 3685 5507 3504 5507 3701 5508 3696 5508 3692 5508 3701 5509 3684 5509 3698 5509 3701 5510 1759 5510 3696 5510 3670 5511 3661 5511 3685 5511 3702 5512 3698 5512 3694 5512 3702 5513 1761 5513 1760 5513 3702 5514 1760 5514 3698 5514 3702 5515 3694 5515 1761 5515 3663 5516 3690 5516 3664 5516 3663 5517 3695 5517 3690 5517 3652 5518 3687 5518 3653 5518 3652 5519 3664 5519 3687 5519 3658 5520 3699 5520 3695 5520 3658 5521 3657 5521 3699 5521 3658 5522 3695 5522 3663 5522 3679 5523 3514 5523 3479 5523 3679 5524 3504 5524 3514 5524 3679 5525 3670 5525 3504 5525 3659 5526 3673 5526 3675 5526 3659 5527 3675 5527 3657 5527 2758 5528 2875 5528 3703 5528 3704 5529 2758 5529 3703 5529 2875 5530 2872 5530 3705 5530 2872 5531 2793 5531 3705 5531 2793 5532 3706 5532 3705 5532 3703 5533 2875 5533 3705 5533 3707 5534 2834 5534 3708 5534 3708 5535 2834 5535 2832 5535 3708 5536 2832 5536 3709 5536 3709 5537 2832 5537 2830 5537 3709 5538 2830 5538 3710 5538 3710 5539 2830 5539 2828 5539 3710 5540 2828 5540 2847 5540 3710 5541 2847 5541 3711 5541 3711 5542 2847 5542 2845 5542 3711 5543 2845 5543 2843 5543 2843 5544 2840 5544 3712 5544 3711 5545 2843 5545 3712 5545 3712 5546 2840 5546 2822 5546 3713 5547 3712 5547 340 5547 340 5548 3712 5548 338 5548 3712 5549 2822 5549 338 5549 3713 5550 340 5550 342 5550 2822 5551 2824 5551 336 5551 338 5552 2822 5552 336 5552 3713 5553 342 5553 344 5553 336 5554 2824 5554 335 5554 2824 5555 2848 5555 335 5555 3713 5556 344 5556 3714 5556 3714 5557 344 5557 297 5557 2848 5558 2850 5558 332 5558 335 5559 2848 5559 332 5559 2850 5560 2852 5560 332 5560 3714 5561 297 5561 296 5561 332 5562 2852 5562 330 5562 330 5563 2852 5563 2741 5563 3714 5564 296 5564 300 5564 330 5565 2741 5565 328 5565 328 5566 2741 5566 2739 5566 328 5567 2739 5567 2737 5567 328 5568 2737 5568 326 5568 3714 5569 300 5569 3715 5569 300 5570 306 5570 3715 5570 326 5571 2737 5571 2736 5571 3715 5572 306 5572 310 5572 326 5573 2736 5573 2861 5573 324 5574 326 5574 2861 5574 3715 5575 310 5575 314 5575 324 5576 2861 5576 2863 5576 322 5577 324 5577 2863 5577 320 5578 322 5578 2751 5578 322 5579 2863 5579 2751 5579 320 5580 2751 5580 318 5580 318 5581 2751 5581 316 5581 303 5582 302 5582 3716 5582 3715 5583 314 5583 3716 5583 314 5584 303 5584 3716 5584 302 5585 308 5585 3717 5585 3716 5586 302 5586 3717 5586 308 5587 312 5587 2750 5587 312 5588 316 5588 2750 5588 316 5589 2751 5589 2750 5589 3717 5590 308 5590 2750 5590 3718 5591 3717 5591 2750 5591 3718 5592 2750 5592 2871 5592 3718 5593 2871 5593 2868 5593 3718 5594 2868 5594 3719 5594 3719 5595 2868 5595 2756 5595 3719 5596 2756 5596 3720 5596 3720 5597 2756 5597 2791 5597 3720 5598 2791 5598 3721 5598 3721 5599 2791 5599 2789 5599 3721 5600 2789 5600 3722 5600 3722 5601 2789 5601 2787 5601 3722 5602 2787 5602 3723 5602 3723 5603 2787 5603 2786 5603 3723 5604 2786 5604 3724 5604 3724 5605 2786 5605 2784 5605 3724 5606 2784 5606 3725 5606 3725 5607 2784 5607 2782 5607 3725 5608 2782 5608 3726 5608 3726 5609 2782 5609 2780 5609 3726 5610 2780 5610 3727 5610 3727 5611 2780 5611 2778 5611 3727 5612 2778 5612 3728 5612 3728 5613 2778 5613 2776 5613 3728 5614 2776 5614 3729 5614 2820 5615 2817 5615 3730 5615 2817 5616 3731 5616 3730 5616 3729 5617 2776 5617 3732 5617 2776 5618 2774 5618 3732 5618 2867 5619 2749 5619 287 5619 2749 5620 2747 5620 287 5620 287 5621 2747 5621 285 5621 2745 5622 2744 5622 285 5622 2747 5623 2745 5623 285 5623 2865 5624 2867 5624 288 5624 2867 5625 287 5625 288 5625 285 5626 2744 5626 283 5626 2744 5627 2855 5627 283 5627 2820 5628 3730 5628 3733 5628 2821 5629 2820 5629 3733 5629 2774 5630 2772 5630 3734 5630 3732 5631 2774 5631 3734 5631 2792 5632 2865 5632 290 5632 2865 5633 288 5633 290 5633 2855 5634 2857 5634 282 5634 2857 5635 2859 5635 282 5635 283 5636 2855 5636 282 5636 2792 5637 290 5637 292 5637 2859 5638 2797 5638 279 5638 282 5639 2859 5639 279 5639 2792 5640 292 5640 294 5640 2797 5641 2796 5641 277 5641 279 5642 2797 5642 277 5642 2821 5643 3733 5643 3735 5643 2802 5644 2801 5644 3735 5644 2801 5645 2821 5645 3735 5645 2772 5646 2770 5646 3736 5646 3734 5647 2772 5647 3736 5647 2792 5648 294 5648 247 5648 277 5649 2796 5649 275 5649 2802 5650 3735 5650 3737 5650 2805 5651 2802 5651 3737 5651 2807 5652 2805 5652 3737 5652 2770 5653 2768 5653 3738 5653 3736 5654 2770 5654 3738 5654 3738 5655 2768 5655 3739 5655 2768 5656 2766 5656 3739 5656 275 5657 2796 5657 3740 5657 2807 5658 3737 5658 3740 5658 272 5659 275 5659 3740 5659 2809 5660 2807 5660 3740 5660 2796 5661 2809 5661 3740 5661 272 5662 3740 5662 3741 5662 269 5663 271 5663 3741 5663 271 5664 272 5664 3741 5664 3739 5665 2766 5665 3742 5665 2766 5666 2764 5666 3742 5666 247 5667 246 5667 2793 5667 246 5668 253 5668 2793 5668 2792 5669 247 5669 2793 5669 262 5670 264 5670 3743 5670 264 5671 266 5671 3743 5671 266 5672 269 5672 3743 5672 269 5673 3741 5673 3743 5673 3742 5674 2764 5674 3744 5674 2764 5675 2762 5675 3744 5675 250 5676 257 5676 3745 5676 257 5677 260 5677 3745 5677 260 5678 262 5678 3745 5678 262 5679 3743 5679 3745 5679 2762 5680 2759 5680 3746 5680 3744 5681 2762 5681 3746 5681 2759 5682 2758 5682 3704 5682 3746 5683 2759 5683 3704 5683 251 5684 250 5684 3747 5684 255 5685 251 5685 3747 5685 250 5686 3745 5686 3747 5686 2793 5687 253 5687 3706 5687 253 5688 255 5688 3706 5688 255 5689 3747 5689 3706 5689 3748 5690 3749 5690 3750 5690 3749 5691 3751 5691 3750 5691 3504 5692 3685 5692 3752 5692 3753 5693 3754 5693 3755 5693 3755 5694 3756 5694 3757 5694 3755 5695 3757 5695 3758 5695 3753 5696 3755 5696 3759 5696 3755 5697 3758 5697 3759 5697 3760 5698 3761 5698 3762 5698 3685 5699 3678 5699 3763 5699 3678 5700 3676 5700 3763 5700 3752 5701 3685 5701 3763 5701 3676 5702 3761 5702 3764 5702 3763 5703 3676 5703 3764 5703 3752 5704 3763 5704 3764 5704 3760 5705 3752 5705 3765 5705 3764 5706 3761 5706 3765 5706 3752 5707 3764 5707 3765 5707 3761 5708 3760 5708 3765 5708 3676 5709 3766 5709 3767 5709 3768 5710 3761 5710 3767 5710 3761 5711 3676 5711 3767 5711 3766 5712 3769 5712 3770 5712 3769 5713 3754 5713 3770 5713 3753 5714 3768 5714 3770 5714 3767 5715 3766 5715 3770 5715 3768 5716 3767 5716 3770 5716 3754 5717 3753 5717 3770 5717 3771 5718 3757 5718 3756 5718 3771 5719 3758 5719 3757 5719 3771 5720 3759 5720 3758 5720 3772 5721 3771 5721 3756 5721 3773 5722 3771 5722 3772 5722 3774 5723 3775 5723 3773 5723 3774 5724 3773 5724 3772 5724 3776 5725 3775 5725 3774 5725 3777 5726 3776 5726 3774 5726 3778 5727 3776 5727 3777 5727 3779 5728 3778 5728 3777 5728 3780 5729 3778 5729 3779 5729 3781 5730 3782 5730 3783 5730 3750 5731 3751 5731 3781 5731 3784 5732 3781 5732 3783 5732 3784 5733 3750 5733 3781 5733 3785 5734 3783 5734 3786 5734 3785 5735 3784 5735 3783 5735 3787 5736 3786 5736 3788 5736 3787 5737 3785 5737 3786 5737 3789 5738 3788 5738 3790 5738 3789 5739 3787 5739 3788 5739 3791 5740 3790 5740 3792 5740 3791 5741 3789 5741 3790 5741 2607 5742 3792 5742 2399 5742 2607 5743 3791 5743 3792 5743 3793 5744 3782 5744 3794 5744 3795 5745 3794 5745 3796 5745 3795 5746 3793 5746 3794 5746 3797 5747 3796 5747 3780 5747 3797 5748 3795 5748 3796 5748 3798 5749 3783 5749 3782 5749 3798 5750 3782 5750 3793 5750 3799 5751 3793 5751 3795 5751 3799 5752 3798 5752 3793 5752 3800 5753 3786 5753 3783 5753 3800 5754 3783 5754 3798 5754 3801 5755 3780 5755 3779 5755 3801 5756 3797 5756 3780 5756 3802 5757 3797 5757 3801 5757 3802 5758 3799 5758 3795 5758 3802 5759 3795 5759 3797 5759 3803 5760 3798 5760 3799 5760 3803 5761 3800 5761 3798 5761 3804 5762 3803 5762 3799 5762 3804 5763 3799 5763 3802 5763 3805 5764 3801 5764 3779 5764 3806 5765 3786 5765 3800 5765 3807 5766 3806 5766 3800 5766 3807 5767 3800 5767 3803 5767 3808 5768 3807 5768 3803 5768 3808 5769 3803 5769 3804 5769 3809 5770 3802 5770 3801 5770 3809 5771 3801 5771 3805 5771 3810 5772 3788 5772 3786 5772 3810 5773 3786 5773 3806 5773 3811 5774 3804 5774 3802 5774 3811 5775 3802 5775 3809 5775 3812 5776 3806 5776 3807 5776 3812 5777 3810 5777 3806 5777 3813 5778 3809 5778 3805 5778 3814 5779 3779 5779 3777 5779 3814 5780 3805 5780 3779 5780 3815 5781 3807 5781 3808 5781 3815 5782 3812 5782 3807 5782 3816 5783 3809 5783 3813 5783 3816 5784 3811 5784 3809 5784 3817 5785 3814 5785 3777 5785 3818 5786 3788 5786 3810 5786 3818 5787 3810 5787 3812 5787 3819 5788 3812 5788 3815 5788 3819 5789 3818 5789 3812 5789 3820 5790 3819 5790 3815 5790 3821 5791 3804 5791 3811 5791 3821 5792 3808 5792 3804 5792 3822 5793 3821 5793 3811 5793 3822 5794 3811 5794 3816 5794 3823 5795 3788 5795 3818 5795 3823 5796 3790 5796 3788 5796 3823 5797 3818 5797 3819 5797 3824 5798 3815 5798 3808 5798 3824 5799 3808 5799 3821 5799 3825 5800 3813 5800 3805 5800 3825 5801 3805 5801 3814 5801 3825 5802 3814 5802 3817 5802 3826 5803 3819 5803 3820 5803 3826 5804 3823 5804 3819 5804 3827 5805 3825 5805 3817 5805 3828 5806 3826 5806 3820 5806 3829 5807 3816 5807 3813 5807 3829 5808 3825 5808 3827 5808 3829 5809 3813 5809 3825 5809 3830 5810 3824 5810 3821 5810 3830 5811 3821 5811 3822 5811 3831 5812 3829 5812 3827 5812 3832 5813 3790 5813 3823 5813 3833 5814 3777 5814 3774 5814 3833 5815 3817 5815 3777 5815 3834 5816 3823 5816 3826 5816 3834 5817 3832 5817 3823 5817 3835 5818 3833 5818 3774 5818 3836 5819 3834 5819 3826 5819 3836 5820 3826 5820 3828 5820 3837 5821 3824 5821 3830 5821 3837 5822 3820 5822 3815 5822 3837 5823 3815 5823 3824 5823 3838 5824 3837 5824 3830 5824 3839 5825 3816 5825 3829 5825 3839 5826 3822 5826 3816 5826 3839 5827 3829 5827 3831 5827 3840 5828 3792 5828 3790 5828 3840 5829 3790 5829 3832 5829 3841 5830 3839 5830 3831 5830 3842 5831 3820 5831 3837 5831 3842 5832 3828 5832 3820 5832 3843 5833 3832 5833 3834 5833 3843 5834 3840 5834 3832 5834 3844 5835 2399 5835 3792 5835 3844 5836 3792 5836 3840 5836 3845 5837 3834 5837 3836 5837 3845 5838 3843 5838 3834 5838 3846 5839 3830 5839 3822 5839 3846 5840 3822 5840 3839 5840 3846 5841 3839 5841 3841 5841 3847 5842 3827 5842 3817 5842 3847 5843 3817 5843 3833 5843 3848 5844 3842 5844 3837 5844 3848 5845 3837 5845 3838 5845 3849 5846 2399 5846 3844 5846 3849 5847 3840 5847 3843 5847 3849 5848 3844 5848 3840 5848 3850 5849 3846 5849 3841 5849 3851 5850 2377 5850 2399 5850 3851 5851 3843 5851 3845 5851 3851 5852 3849 5852 3843 5852 3851 5853 2399 5853 3849 5853 3852 5854 3847 5854 3833 5854 3852 5855 3833 5855 3835 5855 3853 5856 3831 5856 3827 5856 3853 5857 3827 5857 3847 5857 3854 5858 3836 5858 3828 5858 3854 5859 3828 5859 3842 5859 3855 5860 3774 5860 3772 5860 3855 5861 3835 5861 3774 5861 3855 5862 3852 5862 3835 5862 3856 5863 3847 5863 3852 5863 3856 5864 3853 5864 3847 5864 3857 5865 3842 5865 3848 5865 3857 5866 3854 5866 3842 5866 3858 5867 3855 5867 3772 5867 3859 5868 3830 5868 3846 5868 3859 5869 3846 5869 3850 5869 3859 5870 3838 5870 3830 5870 3860 5871 3859 5871 3850 5871 3861 5872 3836 5872 3854 5872 3861 5873 3845 5873 3836 5873 3862 5874 3831 5874 3853 5874 3862 5875 3841 5875 3831 5875 3863 5876 3772 5876 3756 5876 3863 5877 3858 5877 3772 5877 3864 5878 3857 5878 3848 5878 3864 5879 3859 5879 3860 5879 3864 5880 3848 5880 3838 5880 3864 5881 3838 5881 3859 5881 3865 5882 3853 5882 3856 5882 3865 5883 3862 5883 3853 5883 3866 5884 2377 5884 3851 5884 3866 5885 3851 5885 3845 5885 3866 5886 3845 5886 3861 5886 3867 5887 3854 5887 3857 5887 3867 5888 3861 5888 3854 5888 3868 5889 3864 5889 3860 5889 3869 5890 3850 5890 3841 5890 3869 5891 3841 5891 3862 5891 3870 5892 3856 5892 3852 5892 3870 5893 3852 5893 3855 5893 3870 5894 3855 5894 3858 5894 3871 5895 2377 5895 3866 5895 3871 5896 3866 5896 3861 5896 3871 5897 3861 5897 3867 5897 3872 5898 3862 5898 3865 5898 3872 5899 3869 5899 3862 5899 3873 5900 3865 5900 3856 5900 3873 5901 3856 5901 3870 5901 3874 5902 3864 5902 3868 5902 3874 5903 3857 5903 3864 5903 3875 5904 3858 5904 3863 5904 3875 5905 3870 5905 3858 5905 3876 5906 3874 5906 3868 5906 3877 5907 3873 5907 3870 5907 3877 5908 3870 5908 3875 5908 3878 5909 3860 5909 3850 5909 3878 5910 3850 5910 3869 5910 3878 5911 3869 5911 3872 5911 3879 5912 3878 5912 3872 5912 3880 5913 3756 5913 3881 5913 3880 5914 3863 5914 3756 5914 3880 5915 3875 5915 3863 5915 3880 5916 3877 5916 3875 5916 3882 5917 3874 5917 3876 5917 3882 5918 3867 5918 3857 5918 3882 5919 3871 5919 3867 5919 3882 5920 3857 5920 3874 5920 3883 5921 3877 5921 3880 5921 3883 5922 3880 5922 3881 5922 3884 5923 3865 5923 3873 5923 3884 5924 3872 5924 3865 5924 3885 5925 3882 5925 3876 5925 3886 5926 3868 5926 3860 5926 3886 5927 3860 5927 3878 5927 3887 5928 3871 5928 3882 5928 3887 5929 3882 5929 3885 5929 3888 5930 3884 5930 3873 5930 3888 5931 3873 5931 3877 5931 3889 5932 3887 5932 3885 5932 3890 5933 3886 5933 3878 5933 3890 5934 3878 5934 3879 5934 3891 5935 3872 5935 3884 5935 3891 5936 3884 5936 3888 5936 3891 5937 3879 5937 3872 5937 3892 5938 3876 5938 3868 5938 3892 5939 3868 5939 3886 5939 3893 5940 3891 5940 3888 5940 3894 5941 3892 5941 3886 5941 3894 5942 3886 5942 3890 5942 3895 5943 3883 5943 3881 5943 3895 5944 3881 5944 3896 5944 3895 5945 3888 5945 3877 5945 3895 5946 3877 5946 3883 5946 3897 5947 3879 5947 3891 5947 3897 5948 3891 5948 3893 5948 3897 5949 3890 5949 3879 5949 3898 5950 3897 5950 3893 5950 3899 5951 3895 5951 3896 5951 3899 5952 3893 5952 3888 5952 3899 5953 3888 5953 3895 5953 2372 5954 3887 5954 3889 5954 2372 5955 2377 5955 3871 5955 2372 5956 3871 5956 3887 5956 3900 5957 3885 5957 3876 5957 3900 5958 3876 5958 3892 5958 3901 5959 3892 5959 3894 5959 3901 5960 3900 5960 3892 5960 3902 5961 3894 5961 3890 5961 3902 5962 3890 5962 3897 5962 3903 5963 3889 5963 3885 5963 3903 5964 3885 5964 3900 5964 3904 5965 2370 5965 3903 5965 3904 5966 3900 5966 3901 5966 3904 5967 3903 5967 3900 5967 3905 5968 3897 5968 3898 5968 3905 5969 3902 5969 3897 5969 3906 5970 3905 5970 3898 5970 3906 5971 3896 5971 3907 5971 3906 5972 3898 5972 3893 5972 3906 5973 3893 5973 3899 5973 3906 5974 3899 5974 3896 5974 3908 5975 3901 5975 3894 5975 3908 5976 3894 5976 3902 5976 3909 5977 3902 5977 3905 5977 3909 5978 3908 5978 3902 5978 3910 5979 3905 5979 3906 5979 3910 5980 3906 5980 3907 5980 2370 5981 2372 5981 3889 5981 2370 5982 3889 5982 3903 5982 3911 5983 3901 5983 3908 5983 3911 5984 3904 5984 3901 5984 3912 5985 3910 5985 3907 5985 3912 5986 3907 5986 3913 5986 3912 5987 3909 5987 3905 5987 3912 5988 3905 5988 3910 5988 3914 5989 3904 5989 3911 5989 3915 5990 3908 5990 3909 5990 3915 5991 3911 5991 3908 5991 3916 5992 3914 5992 3911 5992 3916 5993 3911 5993 3915 5993 3917 5994 3912 5994 3913 5994 3917 5995 3909 5995 3912 5995 3917 5996 3915 5996 3909 5996 3918 5997 3915 5997 3917 5997 3918 5998 3913 5998 2365 5998 3918 5999 2365 5999 2364 5999 3918 6000 3916 6000 3915 6000 3918 6001 3917 6001 3913 6001 2363 6002 3916 6002 2364 6002 2363 6003 2370 6003 3904 6003 2363 6004 3914 6004 3916 6004 2363 6005 3904 6005 3914 6005 2364 6006 3916 6006 3918 6006 3919 6007 3920 6007 3921 6007 3919 6008 3921 6008 3922 6008 3919 6009 3922 6009 3923 6009 3924 6010 3923 6010 2466 6010 3924 6011 3919 6011 3923 6011 2558 6012 3924 6012 2466 6012 3925 6013 3926 6013 3927 6013 3928 6014 3927 6014 3929 6014 3928 6015 3930 6015 3925 6015 3928 6016 3925 6016 3927 6016 3931 6017 3929 6017 3932 6017 3931 6018 3928 6018 3929 6018 3933 6019 3932 6019 3934 6019 3933 6020 3931 6020 3932 6020 3935 6021 3934 6021 3936 6021 3935 6022 3933 6022 3934 6022 3937 6023 3936 6023 3938 6023 3939 6024 3935 6024 3936 6024 3939 6025 3936 6025 3937 6025 3940 6026 3939 6026 3937 6026 3748 6027 3750 6027 3941 6027 3942 6028 3941 6028 3943 6028 3942 6029 3944 6029 3748 6029 3942 6030 3748 6030 3941 6030 3945 6031 3943 6031 3946 6031 3945 6032 3942 6032 3943 6032 3947 6033 3946 6033 3948 6033 3947 6034 3945 6034 3946 6034 3949 6035 3948 6035 3950 6035 3949 6036 3947 6036 3948 6036 3951 6037 3950 6037 3952 6037 3953 6038 3949 6038 3950 6038 3953 6039 3950 6039 3951 6039 3954 6040 3953 6040 3951 6040 3955 6041 3956 6041 3957 6041 3958 6042 2358 6042 2357 6042 3959 6043 3960 6043 3961 6043 3958 6044 2357 6044 3962 6044 3958 6045 3962 6045 3963 6045 3964 6046 3948 6046 3946 6046 3964 6047 3965 6047 3948 6047 3964 6048 3966 6048 3965 6048 3967 6049 3957 6049 3968 6049 3969 6050 3921 6050 3970 6050 3967 6051 3955 6051 3957 6051 3969 6052 3922 6052 3921 6052 3969 6053 3923 6053 3922 6053 3971 6054 3787 6054 3789 6054 3969 6055 2450 6055 3923 6055 3971 6056 3972 6056 3787 6056 3971 6057 3973 6057 3972 6057 3971 6058 3968 6058 3973 6058 3974 6059 3959 6059 3961 6059 3975 6060 2358 6060 3958 6060 3974 6061 3961 6061 3976 6061 3975 6062 3963 6062 3955 6062 3977 6063 3978 6063 3960 6063 3975 6064 3958 6064 3963 6064 3977 6065 3960 6065 3959 6065 3979 6066 3971 6066 3789 6066 3980 6067 3946 6067 3943 6067 3979 6068 3967 6068 3968 6068 3979 6069 3968 6069 3971 6069 3980 6070 3964 6070 3946 6070 3981 6071 2629 6071 2358 6071 3981 6072 2358 6072 3975 6072 3981 6073 3955 6073 3967 6073 3981 6074 3975 6074 3955 6074 3982 6075 3789 6075 3791 6075 3983 6076 3976 6076 3984 6076 3982 6077 2629 6077 3981 6077 3982 6078 3979 6078 3789 6078 3983 6079 3984 6079 3966 6079 3982 6080 3967 6080 3979 6080 3983 6081 3974 6081 3976 6081 3982 6082 3981 6082 3967 6082 3982 6083 3791 6083 2629 6083 3985 6084 3966 6084 3964 6084 3985 6085 3964 6085 3980 6085 3986 6086 3970 6086 3978 6086 3986 6087 2418 6087 2450 6087 3986 6088 2450 6088 3969 6088 3986 6089 3969 6089 3970 6089 3987 6090 3978 6090 3977 6090 3987 6091 3959 6091 3974 6091 3987 6092 3977 6092 3959 6092 3988 6093 3980 6093 3943 6093 2450 6094 2466 6094 3923 6094 3989 6095 3985 6095 3980 6095 3990 6096 2418 6096 3986 6096 3990 6097 3986 6097 3978 6097 3784 6098 3941 6098 3750 6098 3991 6099 3974 6099 3983 6099 3992 6100 3991 6100 3983 6100 3992 6101 3985 6101 3989 6101 3992 6102 3966 6102 3985 6102 3992 6103 3983 6103 3966 6103 3993 6104 3980 6104 3988 6104 3993 6105 3989 6105 3980 6105 3994 6106 3990 6106 3978 6106 3994 6107 2357 6107 2418 6107 3994 6108 2418 6108 3990 6108 3994 6109 3978 6109 3987 6109 3995 6110 3943 6110 3941 6110 3995 6111 3988 6111 3943 6111 3995 6112 3941 6112 3784 6112 3996 6113 3987 6113 3974 6113 3996 6114 3974 6114 3991 6114 3996 6115 3994 6115 3987 6115 3997 6116 3992 6116 3989 6116 2607 6117 2629 6117 3791 6117 3956 6118 3991 6118 3992 6118 3998 6119 3999 6119 4000 6119 3998 6120 4000 6120 3952 6120 3998 6121 3952 6121 3950 6121 4001 6122 3784 6122 3785 6122 4001 6123 3988 6123 3995 6123 4002 6124 3998 6124 3950 6124 4001 6125 3995 6125 3784 6125 4001 6126 3993 6126 3988 6126 4003 6127 4004 6127 3999 6127 3973 6128 3989 6128 3993 6128 4003 6129 3999 6129 3998 6129 3973 6130 3997 6130 3989 6130 3973 6131 3993 6131 4001 6131 3984 6132 3998 6132 4002 6132 3984 6133 4003 6133 3998 6133 3957 6134 3956 6134 3992 6134 3957 6135 3992 6135 3997 6135 3961 6136 3960 6136 4004 6136 3962 6137 2357 6137 3994 6137 3961 6138 4004 6138 4003 6138 3962 6139 3994 6139 3996 6139 3963 6140 3991 6140 3956 6140 3963 6141 3996 6141 3991 6141 3965 6142 3950 6142 3948 6142 3963 6143 3962 6143 3996 6143 3965 6144 3984 6144 4002 6144 3965 6145 4002 6145 3950 6145 3972 6146 3785 6146 3787 6146 3972 6147 3973 6147 4001 6147 3972 6148 4001 6148 3785 6148 3976 6149 4003 6149 3984 6149 3976 6150 3961 6150 4003 6150 3968 6151 3997 6151 3973 6151 3968 6152 3957 6152 3997 6152 3966 6153 3984 6153 3965 6153 3955 6154 3963 6154 3956 6154 4005 6155 4006 6155 4007 6155 4005 6156 4008 6156 4009 6156 4005 6157 4010 6157 4008 6157 4011 6158 4012 6158 4006 6158 4013 6159 4014 6159 4015 6159 4016 6160 2577 6160 2583 6160 4013 6161 4017 6161 4014 6161 4016 6162 4018 6162 4019 6162 4013 6163 4015 6163 4020 6163 4016 6164 4019 6164 4021 6164 4016 6165 2583 6165 4018 6165 4022 6166 4020 6166 3932 6166 4023 6167 4021 6167 4024 6167 4023 6168 4024 6168 4025 6168 4023 6169 4016 6169 4021 6169 4026 6170 4027 6170 4028 6170 4029 6171 4030 6171 4031 6171 4029 6172 4005 6172 4030 6172 4029 6173 4006 6173 4005 6173 4026 6174 4028 6174 4032 6174 4029 6175 4011 6175 4006 6175 4033 6176 4025 6176 4012 6176 4033 6177 4012 6177 4011 6177 4034 6178 4013 6178 4020 6178 4035 6179 2577 6179 4016 6179 4035 6180 4016 6180 4023 6180 4036 6181 4032 6181 4017 6181 4036 6182 4013 6182 4034 6182 4037 6183 4031 6183 4038 6183 4036 6184 4026 6184 4032 6184 4037 6185 4038 6185 4033 6185 4037 6186 4029 6186 4031 6186 4037 6187 4011 6187 4029 6187 4036 6188 4017 6188 4013 6188 4037 6189 4033 6189 4011 6189 4039 6190 4038 6190 4040 6190 4039 6191 4033 6191 4038 6191 4039 6192 4025 6192 4033 6192 4039 6193 4023 6193 4025 6193 4039 6194 4035 6194 4023 6194 4041 6195 4034 6195 4020 6195 4041 6196 4020 6196 4022 6196 4042 6197 2573 6197 2577 6197 4042 6198 2577 6198 4035 6198 4042 6199 4035 6199 4039 6199 4043 6200 3932 6200 3929 6200 4044 6201 2573 6201 4042 6201 4044 6202 4039 6202 4040 6202 4043 6203 4022 6203 3932 6203 4044 6204 4042 6204 4039 6204 4045 6205 4046 6205 4027 6205 4047 6206 4040 6206 4048 6206 4047 6207 2567 6207 2573 6207 4047 6208 4044 6208 4040 6208 4047 6209 2573 6209 4044 6209 4045 6210 4027 6210 4026 6210 4049 6211 3919 6211 3924 6211 4049 6212 4047 6212 4048 6212 4049 6213 2567 6213 4047 6213 4049 6214 4048 6214 3919 6214 4050 6215 4036 6215 4034 6215 4049 6216 3924 6216 2567 6216 4051 6217 4026 6217 4036 6217 4051 6218 4045 6218 4026 6218 4052 6219 4034 6219 4041 6219 4052 6220 4050 6220 4034 6220 4053 6221 2584 6221 2580 6221 4053 6222 2580 6222 4046 6222 4053 6223 4046 6223 4045 6223 4054 6224 4041 6224 4022 6224 4054 6225 4022 6225 4043 6225 4055 6226 4036 6226 4050 6226 4055 6227 4051 6227 4036 6227 4056 6228 4045 6228 4051 6228 4007 6229 3929 6229 3927 6229 4007 6230 4043 6230 3929 6230 4024 6231 4050 6231 4052 6231 4024 6232 4055 6232 4050 6232 4012 6233 4052 6233 4041 6233 3919 6234 4048 6234 3920 6234 4012 6235 4041 6235 4054 6235 4010 6236 3927 6236 3926 6236 4010 6237 4007 6237 3927 6237 4019 6238 4056 6238 4051 6238 2558 6239 2567 6239 3924 6239 4019 6240 4051 6240 4055 6240 4014 6241 3938 6241 3936 6241 4014 6242 4057 6242 3938 6242 4058 6243 4053 6243 4045 6243 4058 6244 2583 6244 2584 6244 4058 6245 4045 6245 4056 6245 4058 6246 2584 6246 4053 6246 4017 6247 4059 6247 4057 6247 4006 6248 4054 6248 4043 6248 4006 6249 4043 6249 4007 6249 4006 6250 4012 6250 4054 6250 4017 6251 4057 6251 4014 6251 4008 6252 3926 6252 4060 6252 4008 6253 4060 6253 4009 6253 4015 6254 3936 6254 3934 6254 4008 6255 4010 6255 3926 6255 4021 6256 4055 6256 4024 6256 4015 6257 4014 6257 3936 6257 4021 6258 4019 6258 4055 6258 4032 6259 4028 6259 4059 6259 4025 6260 4052 6260 4012 6260 4032 6261 4059 6261 4017 6261 4025 6262 4024 6262 4052 6262 4018 6263 4056 6263 4019 6263 4020 6264 3934 6264 3932 6264 4018 6265 2583 6265 4058 6265 4018 6266 4058 6266 4056 6266 4005 6267 4009 6267 4030 6267 4020 6268 4015 6268 3934 6268 4005 6269 4007 6269 4010 6269 4061 6270 4062 6270 4063 6270 4064 6271 4062 6271 4061 6271 4065 6272 4064 6272 4061 6272 4066 6273 4067 6273 4064 6273 4066 6274 4064 6274 4065 6274 4068 6275 4069 6275 4067 6275 4068 6276 4067 6276 4066 6276 4070 6277 4069 6277 4068 6277 4071 6278 4069 6278 4070 6278 4072 6279 4071 6279 4070 6279 4073 6280 4072 6280 4070 6280 4074 6281 4073 6281 4070 6281 4075 6282 4076 6282 4077 6282 4075 6283 2554 6283 4076 6283 4078 6284 4075 6284 4077 6284 4078 6285 4079 6285 2554 6285 4078 6286 4077 6286 4080 6286 4078 6287 4080 6287 4079 6287 4078 6288 2554 6288 4075 6288 2548 6289 4081 6289 4082 6289 2548 6290 2545 6290 4081 6290 2548 6291 4082 6291 4076 6291 4083 6292 4074 6292 4070 6292 4084 6293 4070 6293 4068 6293 4084 6294 4083 6294 4070 6294 4085 6295 4084 6295 4068 6295 4086 6296 4087 6296 4074 6296 4086 6297 4074 6297 4083 6297 4088 6298 4087 6298 4086 6298 4089 6299 4083 6299 4084 6299 4089 6300 4084 6300 4085 6300 4089 6301 4086 6301 4083 6301 4090 6302 4088 6302 4086 6302 4090 6303 4086 6303 4089 6303 4091 6304 4089 6304 4085 6304 4092 6305 4068 6305 4066 6305 4092 6306 4085 6306 4068 6306 4093 6307 4090 6307 4089 6307 4093 6308 4089 6308 4091 6308 4094 6309 4095 6309 4087 6309 4094 6310 4087 6310 4088 6310 4094 6311 4088 6311 4090 6311 4096 6312 4092 6312 4066 6312 4097 6313 4095 6313 4094 6313 4098 6314 4090 6314 4093 6314 4098 6315 4094 6315 4090 6315 4099 6316 4098 6316 4093 6316 4100 6317 4091 6317 4085 6317 4100 6318 4085 6318 4092 6318 4101 6319 4097 6319 4094 6319 4101 6320 4094 6320 4098 6320 4102 6321 4103 6321 4095 6321 4102 6322 4097 6322 4101 6322 4102 6323 4095 6323 4097 6323 4104 6324 4093 6324 4091 6324 4104 6325 4091 6325 4100 6325 4105 6326 4092 6326 4096 6326 4105 6327 4100 6327 4092 6327 4106 6328 4098 6328 4099 6328 4106 6329 4101 6329 4098 6329 4107 6330 4066 6330 4065 6330 4107 6331 4096 6331 4066 6331 4108 6332 4104 6332 4100 6332 4108 6333 4100 6333 4105 6333 4109 6334 4107 6334 4065 6334 4110 6335 4102 6335 4101 6335 4110 6336 4101 6336 4106 6336 4111 6337 4103 6337 4102 6337 4112 6338 4110 6338 4106 6338 4113 6339 4093 6339 4104 6339 4113 6340 4099 6340 4093 6340 4113 6341 4104 6341 4108 6341 4114 6342 4103 6342 4111 6342 4114 6343 4115 6343 4103 6343 4116 6344 4111 6344 4102 6344 4116 6345 4102 6345 4110 6345 4117 6346 4113 6346 4108 6346 4118 6347 4105 6347 4096 6347 4118 6348 4096 6348 4107 6348 4118 6349 4108 6349 4105 6349 4119 6350 4106 6350 4099 6350 4119 6351 4099 6351 4113 6351 4119 6352 4112 6352 4106 6352 4120 6353 4110 6353 4112 6353 4120 6354 4116 6354 4110 6354 4121 6355 4107 6355 4109 6355 4121 6356 4118 6356 4107 6356 4122 6357 4108 6357 4118 6357 4122 6358 4117 6358 4108 6358 4123 6359 4113 6359 4117 6359 4123 6360 4119 6360 4113 6360 4124 6361 4114 6361 4111 6361 4124 6362 4111 6362 4116 6362 4125 6363 4065 6363 4061 6363 4125 6364 4109 6364 4065 6364 4125 6365 4121 6365 4109 6365 4126 6366 4118 6366 4121 6366 4126 6367 4122 6367 4118 6367 4127 6368 4125 6368 4061 6368 4128 6369 4115 6369 4114 6369 4129 6370 4116 6370 4120 6370 4129 6371 4124 6371 4116 6371 4130 6372 4112 6372 4119 6372 4130 6373 4119 6373 4123 6373 4131 6374 2532 6374 2523 6374 4131 6375 2523 6375 4115 6375 4131 6376 4115 6376 4128 6376 4132 6377 4130 6377 4123 6377 4133 6378 4117 6378 4122 6378 4133 6379 4123 6379 4117 6379 4133 6380 4122 6380 4126 6380 4134 6381 4128 6381 4114 6381 4134 6382 4114 6382 4124 6382 4135 6383 4133 6383 4126 6383 4136 6384 4061 6384 4063 6384 4136 6385 4127 6385 4061 6385 4137 6386 4112 6386 4130 6386 4137 6387 4120 6387 4112 6387 4138 6388 2532 6388 4131 6388 4138 6389 4131 6389 4128 6389 4138 6390 4128 6390 4134 6390 4139 6391 4124 6391 4129 6391 4139 6392 4134 6392 4124 6392 4140 6393 4121 6393 4125 6393 4140 6394 4125 6394 4127 6394 4141 6395 4132 6395 4123 6395 4141 6396 4123 6396 4133 6396 4141 6397 4133 6397 4135 6397 4142 6398 4137 6398 4130 6398 4142 6399 4130 6399 4132 6399 4143 6400 4140 6400 4127 6400 4144 6401 4138 6401 4134 6401 4144 6402 4134 6402 4139 6402 4144 6403 2532 6403 4138 6403 4145 6404 4141 6404 4135 6404 4146 6405 4126 6405 4121 6405 4146 6406 4121 6406 4140 6406 4147 6407 4129 6407 4120 6407 4147 6408 4120 6408 4137 6408 4148 6409 4140 6409 4143 6409 4148 6410 4146 6410 4140 6410 4149 6411 4063 6411 4150 6411 4149 6412 4136 6412 4063 6412 4151 6413 4150 6413 4152 6413 4151 6414 4149 6414 4150 6414 4153 6415 4137 6415 4142 6415 4153 6416 4147 6416 4137 6416 4154 6417 4152 6417 4155 6417 4154 6418 4155 6418 4156 6418 4154 6419 4151 6419 4152 6419 4157 6420 4141 6420 4145 6420 4157 6421 4132 6421 4141 6421 4158 6422 4157 6422 4145 6422 4159 6423 4143 6423 4127 6423 4159 6424 4127 6424 4136 6424 4160 6425 4126 6425 4146 6425 4160 6426 4146 6426 4148 6426 4160 6427 4145 6427 4135 6427 4160 6428 4135 6428 4126 6428 4161 6429 4139 6429 4129 6429 4161 6430 4129 6430 4147 6430 4162 6431 4143 6431 4159 6431 4162 6432 4148 6432 4143 6432 4163 6433 4160 6433 4148 6433 4163 6434 4148 6434 4162 6434 4164 6435 4142 6435 4132 6435 4164 6436 4132 6436 4157 6436 4165 6437 4161 6437 4147 6437 4165 6438 4147 6438 4153 6438 4166 6439 4144 6439 4139 6439 4166 6440 2531 6440 4144 6440 4166 6441 4139 6441 4161 6441 4167 6442 4164 6442 4157 6442 4167 6443 4157 6443 4158 6443 4168 6444 4136 6444 4149 6444 4168 6445 4149 6445 4151 6445 4168 6446 4159 6446 4136 6446 4169 6447 4160 6447 4163 6447 4169 6448 4158 6448 4145 6448 4169 6449 4145 6449 4160 6449 4170 6450 4161 6450 4165 6450 4170 6451 2531 6451 4166 6451 4170 6452 4166 6452 4161 6452 4171 6453 4169 6453 4163 6453 4172 6454 4168 6454 4151 6454 4173 6455 4162 6455 4159 6455 4173 6456 4159 6456 4168 6456 4173 6457 4168 6457 4172 6457 4174 6458 4142 6458 4164 6458 4174 6459 4153 6459 4142 6459 4175 6460 4154 6460 4156 6460 4175 6461 4151 6461 4154 6461 4175 6462 4172 6462 4151 6462 4176 6463 4173 6463 4172 6463 4177 6464 4164 6464 4167 6464 4177 6465 4174 6465 4164 6465 4178 6466 4172 6466 4175 6466 4178 6467 4156 6467 4179 6467 4178 6468 4176 6468 4172 6468 4178 6469 4175 6469 4156 6469 4180 6470 4163 6470 4162 6470 4181 6471 4158 6471 4169 6471 4181 6472 4169 6472 4171 6472 4182 6473 4181 6473 4171 6473 4183 6474 4163 6474 4180 6474 4183 6475 4171 6475 4163 6475 2531 6476 2532 6476 4144 6476 4184 6477 4173 6477 4176 6477 4184 6478 4180 6478 4162 6478 4184 6479 4162 6479 4173 6479 4185 6480 4174 6480 4177 6480 4185 6481 4165 6481 4153 6481 4185 6482 4170 6482 4165 6482 4185 6483 4153 6483 4174 6483 4186 6484 4176 6484 4178 6484 4186 6485 4184 6485 4176 6485 4187 6486 4185 6486 4177 6486 4188 6487 4158 6487 4181 6487 4188 6488 4167 6488 4158 6488 4189 6489 4170 6489 4185 6489 4190 6490 4178 6490 4179 6490 4190 6491 4186 6491 4178 6491 4191 6492 4181 6492 4182 6492 4191 6493 4188 6493 4181 6493 4192 6494 4185 6494 4187 6494 4192 6495 4189 6495 4185 6495 4193 6496 4183 6496 4180 6496 4193 6497 4184 6497 4186 6497 4193 6498 4180 6498 4184 6498 4194 6499 4171 6499 4183 6499 4194 6500 4182 6500 4171 6500 4194 6501 4191 6501 4182 6501 4195 6502 4186 6502 4190 6502 4195 6503 4193 6503 4186 6503 4196 6504 4177 6504 4167 6504 4196 6505 4167 6505 4188 6505 4196 6506 4187 6506 4177 6506 4197 6507 4179 6507 4198 6507 4197 6508 4190 6508 4179 6508 4197 6509 4195 6509 4190 6509 4199 6510 4188 6510 4191 6510 4199 6511 4196 6511 4188 6511 4200 6512 4183 6512 4193 6512 4200 6513 4194 6513 4183 6513 4200 6514 4193 6514 4195 6514 4201 6515 4191 6515 4194 6515 4202 6516 4195 6516 4197 6516 4202 6517 4200 6517 4195 6517 4203 6518 4197 6518 4198 6518 4203 6519 4202 6519 4197 6519 2541 6520 4170 6520 4189 6520 2541 6521 4189 6521 4192 6521 2541 6522 2531 6522 4170 6522 2541 6523 4192 6523 2545 6523 4204 6524 4187 6524 4196 6524 4204 6525 4196 6525 4199 6525 4205 6526 4199 6526 4191 6526 4205 6527 4191 6527 4201 6527 4206 6528 4204 6528 4199 6528 4207 6529 4194 6529 4200 6529 4207 6530 4201 6530 4194 6530 4207 6531 4200 6531 4202 6531 4208 6532 4192 6532 4187 6532 4208 6533 4187 6533 4204 6533 4081 6534 4204 6534 4206 6534 4081 6535 4208 6535 4204 6535 4209 6536 4207 6536 4202 6536 4210 6537 4198 6537 4211 6537 4210 6538 4203 6538 4198 6538 4210 6539 4202 6539 4203 6539 4210 6540 4209 6540 4202 6540 4212 6541 4205 6541 4201 6541 4212 6542 4201 6542 4207 6542 4212 6543 4207 6543 4209 6543 4213 6544 4209 6544 4210 6544 4213 6545 4212 6545 4209 6545 4214 6546 4213 6546 4210 6546 4214 6547 4210 6547 4211 6547 4215 6548 4199 6548 4205 6548 4215 6549 4206 6549 4199 6549 4082 6550 4206 6550 4215 6550 4082 6551 4081 6551 4206 6551 2545 6552 4208 6552 4081 6552 2545 6553 4192 6553 4208 6553 4216 6554 4212 6554 4213 6554 4216 6555 4205 6555 4212 6555 4216 6556 4215 6556 4205 6556 4077 6557 4216 6557 4213 6557 4076 6558 4215 6558 4216 6558 4076 6559 2554 6559 2548 6559 4076 6560 4216 6560 4077 6560 4076 6561 4082 6561 4215 6561 4080 6562 4213 6562 4214 6562 4080 6563 4214 6563 4211 6563 4080 6564 4211 6564 4079 6564 4080 6565 4077 6565 4213 6565 4217 6566 3937 6566 4218 6566 3937 6567 3938 6567 4218 6567 4219 6568 3630 6568 2997 6568 4220 6569 4071 6569 4072 6569 4220 6570 4072 6570 4073 6570 4221 6571 4220 6571 4074 6571 4220 6572 4073 6572 4074 6572 4222 6573 4223 6573 4224 6573 4219 6574 4222 6574 4225 6574 4222 6575 4224 6575 4225 6575 4225 6576 4224 6576 4226 6576 4219 6577 4225 6577 4226 6577 4224 6578 3611 6578 4226 6578 3611 6579 3638 6579 4227 6579 3638 6580 3630 6580 4227 6580 3630 6581 4219 6581 4227 6581 4219 6582 4226 6582 4227 6582 4226 6583 3611 6583 4227 6583 4221 6584 4228 6584 4229 6584 4228 6585 3611 6585 4229 6585 4224 6586 4230 6586 4229 6586 3611 6587 4224 6587 4229 6587 4230 6588 4220 6588 4231 6588 4221 6589 4229 6589 4231 6589 4229 6590 4230 6590 4231 6590 4220 6591 4221 6591 4231 6591 4232 6592 4223 6592 4222 6592 4233 6593 4234 6593 3542 6593 4233 6594 3542 6594 3267 6594 4233 6595 3267 6595 3266 6595 4233 6596 3266 6596 3300 6596 4235 6597 4222 6597 4219 6597 4236 6598 4233 6598 3300 6598 4236 6599 3300 6599 3302 6599 4236 6600 3302 6600 3315 6600 4235 6601 4232 6601 4222 6601 4236 6602 3315 6602 3346 6602 4236 6603 3346 6603 3368 6603 4237 6604 4236 6604 3368 6604 4237 6605 3368 6605 3412 6605 4237 6606 3412 6606 3425 6606 4237 6607 3425 6607 3470 6607 4237 6608 3470 6608 3490 6608 4237 6609 3490 6609 3493 6609 4238 6610 4237 6610 3493 6610 4238 6611 3493 6611 3504 6611 4238 6612 3504 6612 3752 6612 4239 6613 4219 6613 2997 6613 4239 6614 2997 6614 3127 6614 4239 6615 4235 6615 4219 6615 4240 6616 4238 6616 3752 6616 4240 6617 3752 6617 3760 6617 4241 6618 3760 6618 3762 6618 4241 6619 3762 6619 4242 6619 4241 6620 4240 6620 3760 6620 4243 6621 3127 6621 3128 6621 4244 6622 4245 6622 4246 6622 4243 6623 3128 6623 3124 6623 4244 6624 4246 6624 4247 6624 4243 6625 3124 6625 3123 6625 4244 6626 4247 6626 4248 6626 4243 6627 3123 6627 3213 6627 4243 6628 4239 6628 3127 6628 4244 6629 4249 6629 4245 6629 4250 6630 4241 6630 4242 6630 4250 6631 4242 6631 4251 6631 4252 6632 4248 6632 4253 6632 4252 6633 4253 6633 4254 6633 4252 6634 4254 6634 4255 6634 4252 6635 4255 6635 4256 6635 4257 6636 3213 6636 2926 6636 4252 6637 4244 6637 4248 6637 4257 6638 2926 6638 2928 6638 4257 6639 2928 6639 2937 6639 4257 6640 2937 6640 2962 6640 4257 6641 2962 6641 2963 6641 4258 6642 4252 6642 4256 6642 4258 6643 4256 6643 4259 6643 4258 6644 4259 6644 4260 6644 4258 6645 4260 6645 4261 6645 4258 6646 4261 6646 4262 6646 4257 6647 4243 6647 3213 6647 4258 6648 4262 6648 4263 6648 4264 6649 4263 6649 4265 6649 4264 6650 4265 6650 4266 6650 4267 6651 4251 6651 4268 6651 4267 6652 4268 6652 4269 6652 4264 6653 4258 6653 4263 6653 4270 6654 2963 6654 3114 6654 4271 6655 4264 6655 4266 6655 4270 6656 3114 6656 3192 6656 4270 6657 3192 6657 2975 6657 4271 6658 4266 6658 4272 6658 4270 6659 2975 6659 2974 6659 4267 6660 4250 6660 4251 6660 4232 6661 4271 6661 4272 6661 4232 6662 4272 6662 4223 6662 4270 6663 4257 6663 2963 6663 4273 6664 4267 6664 4269 6664 4273 6665 4269 6665 4274 6665 4273 6666 4274 6666 4275 6666 4273 6667 4275 6667 4276 6667 4273 6668 4276 6668 4277 6668 4278 6669 2974 6669 3021 6669 4278 6670 3021 6670 3010 6670 4278 6671 3010 6671 3119 6671 4278 6672 4270 6672 2974 6672 4279 6673 3119 6673 3212 6673 4279 6674 3212 6674 3242 6674 4279 6675 3242 6675 2876 6675 4279 6676 2876 6676 2882 6676 4279 6677 2882 6677 2892 6677 4279 6678 4278 6678 3119 6678 4280 6679 4277 6679 4281 6679 4280 6680 4281 6680 4282 6680 4280 6681 4282 6681 4283 6681 4284 6682 4279 6682 2892 6682 4280 6683 4283 6683 4285 6683 4284 6684 2892 6684 2032 6684 4280 6685 4285 6685 4286 6685 4280 6686 4273 6686 4277 6686 4287 6687 4284 6687 2032 6687 4287 6688 2032 6688 2010 6688 4288 6689 4287 6689 2010 6689 4288 6690 2010 6690 1987 6690 4289 6691 4286 6691 4290 6691 4289 6692 4290 6692 4291 6692 4289 6693 4280 6693 4286 6693 4289 6694 4291 6694 4292 6694 4293 6695 4288 6695 1987 6695 4289 6696 4292 6696 4294 6696 4293 6697 1987 6697 1981 6697 4295 6698 1981 6698 1947 6698 4295 6699 4293 6699 1981 6699 4296 6700 1947 6700 1946 6700 4296 6701 4295 6701 1947 6701 4297 6702 4294 6702 4298 6702 4297 6703 4298 6703 4299 6703 4297 6704 4289 6704 4294 6704 4297 6705 4299 6705 4300 6705 4301 6706 1946 6706 1926 6706 4301 6707 4296 6707 1946 6707 4302 6708 4303 6708 4304 6708 4302 6709 4304 6709 4305 6709 4306 6710 1926 6710 1903 6710 4302 6711 4297 6711 4300 6711 4302 6712 4300 6712 4307 6712 4302 6713 4307 6713 4308 6713 4302 6714 4308 6714 4303 6714 4306 6715 4301 6715 1926 6715 4309 6716 4305 6716 1337 6716 4310 6717 1903 6717 1876 6717 4309 6718 4302 6718 4305 6718 4310 6719 4306 6719 1903 6719 4311 6720 1337 6720 1315 6720 4312 6721 1876 6721 1850 6721 4311 6722 4309 6722 1337 6722 4312 6723 4310 6723 1876 6723 4313 6724 1315 6724 1291 6724 4314 6725 1850 6725 1837 6725 4313 6726 4311 6726 1315 6726 4314 6727 4312 6727 1850 6727 4315 6728 1291 6728 1285 6728 4316 6729 1837 6729 1827 6729 4315 6730 4313 6730 1291 6730 4316 6731 4314 6731 1837 6731 4317 6732 1285 6732 1252 6732 4318 6733 1827 6733 1824 6733 4317 6734 4315 6734 1285 6734 4318 6735 4316 6735 1827 6735 4319 6736 1252 6736 1251 6736 4320 6737 1824 6737 1815 6737 4319 6738 4317 6738 1252 6738 4320 6739 4318 6739 1824 6739 4321 6740 1815 6740 1805 6740 4321 6741 1805 6741 1793 6741 4322 6742 1251 6742 1231 6742 4321 6743 4320 6743 1815 6743 4322 6744 4319 6744 1251 6744 4323 6745 1793 6745 1772 6745 4323 6746 4321 6746 1793 6746 4324 6747 1231 6747 1208 6747 4324 6748 4322 6748 1231 6748 4325 6749 1772 6749 2035 6749 4325 6750 4323 6750 1772 6750 4326 6751 1208 6751 1181 6751 4326 6752 4324 6752 1208 6752 4327 6753 2035 6753 2008 6753 4327 6754 4325 6754 2035 6754 4328 6755 1181 6755 1155 6755 4328 6756 4326 6756 1181 6756 4329 6757 2008 6757 1989 6757 4329 6758 4327 6758 2008 6758 4330 6759 1155 6759 1142 6759 4331 6760 1989 6760 1970 6760 4330 6761 4328 6761 1155 6761 4331 6762 4329 6762 1989 6762 4332 6763 1142 6763 1132 6763 4333 6764 1970 6764 1969 6764 4333 6765 4331 6765 1970 6765 4332 6766 4330 6766 1142 6766 4334 6767 4333 6767 1969 6767 4334 6768 1969 6768 1952 6768 4335 6769 4332 6769 1132 6769 4335 6770 1132 6770 1121 6770 4336 6771 1952 6771 1932 6771 4337 6772 4335 6772 1121 6772 4336 6773 4334 6773 1952 6773 4337 6774 1121 6774 1120 6774 4338 6775 4336 6775 1932 6775 4338 6776 1932 6776 1910 6776 4339 6777 4337 6777 1120 6777 4339 6778 1120 6778 1110 6778 4339 6779 1110 6779 1098 6779 4340 6780 4338 6780 1910 6780 4340 6781 1910 6781 1892 6781 4341 6782 4339 6782 1098 6782 4341 6783 1098 6783 1077 6783 4342 6784 4340 6784 1892 6784 4342 6785 1892 6785 1871 6785 4343 6786 4341 6786 1077 6786 4343 6787 1077 6787 1340 6787 4344 6788 4342 6788 1871 6788 4344 6789 1871 6789 1860 6789 4345 6790 4343 6790 1340 6790 4345 6791 1340 6791 1313 6791 4346 6792 4344 6792 1860 6792 4346 6793 1860 6793 1859 6793 4347 6794 1313 6794 1294 6794 4347 6795 4345 6795 1313 6795 4348 6796 1294 6796 1274 6796 4348 6797 4347 6797 1294 6797 4349 6798 1274 6798 1258 6798 4349 6799 4348 6799 1274 6799 4350 6800 1258 6800 1257 6800 4350 6801 4349 6801 1258 6801 4351 6802 1257 6802 1237 6802 4351 6803 4350 6803 1257 6803 4352 6804 4346 6804 1859 6804 4353 6805 1237 6805 1216 6805 4352 6806 1859 6806 3280 6806 4353 6807 4351 6807 1237 6807 4354 6808 1216 6808 1197 6808 4354 6809 4353 6809 1216 6809 4355 6810 1197 6810 1176 6810 4355 6811 4354 6811 1197 6811 4356 6812 1176 6812 1165 6812 4356 6813 4355 6813 1176 6813 4357 6814 1165 6814 1164 6814 4357 6815 4356 6815 1165 6815 4358 6816 4352 6816 3280 6816 4358 6817 3280 6817 3309 6817 4358 6818 3309 6818 3410 6818 4359 6819 1164 6819 4360 6819 4359 6820 4357 6820 1164 6820 4361 6821 4360 6821 4362 6821 4361 6822 4362 6822 4363 6822 4361 6823 4359 6823 4360 6823 4234 6824 4358 6824 3410 6824 4234 6825 3410 6825 3482 6825 4234 6826 3482 6826 3517 6826 4234 6827 3517 6827 3528 6827 4234 6828 3528 6828 3542 6828 4249 6829 4363 6829 4364 6829 4249 6830 4364 6830 4365 6830 4249 6831 4365 6831 4366 6831 4249 6832 4366 6832 4245 6832 4249 6833 4361 6833 4363 6833 4367 6834 4368 6834 4369 6834 4367 6835 4370 6835 4368 6835 4371 6836 4369 6836 4372 6836 4371 6837 4367 6837 4369 6837 4373 6838 4372 6838 4374 6838 4373 6839 4371 6839 4372 6839 4375 6840 4374 6840 4376 6840 4375 6841 4373 6841 4374 6841 4377 6842 4376 6842 4378 6842 4377 6843 4375 6843 4376 6843 4379 6844 4377 6844 4378 6844 4379 6845 4378 6845 4380 6845 4381 6846 4380 6846 4382 6846 4381 6847 4379 6847 4380 6847 4383 6848 4382 6848 4384 6848 4383 6849 4381 6849 4382 6849 4385 6850 4383 6850 4384 6850 4385 6851 4384 6851 4386 6851 4387 6852 4386 6852 4388 6852 4387 6853 4385 6853 4386 6853 4389 6854 4388 6854 4390 6854 4389 6855 4387 6855 4388 6855 4391 6856 4390 6856 4392 6856 4391 6857 4389 6857 4390 6857 4393 6858 4392 6858 4394 6858 4393 6859 4391 6859 4392 6859 4395 6860 4394 6860 4396 6860 4395 6861 4396 6861 4397 6861 4395 6862 4393 6862 4394 6862 4398 6863 4397 6863 4399 6863 4398 6864 4395 6864 4397 6864 4400 6865 4399 6865 4401 6865 4400 6866 4398 6866 4399 6866 4402 6867 4401 6867 4403 6867 4402 6868 4400 6868 4401 6868 4404 6869 4403 6869 4405 6869 4404 6870 4402 6870 4403 6870 4406 6871 4405 6871 4407 6871 4406 6872 4404 6872 4405 6872 4408 6873 4407 6873 4409 6873 4408 6874 4406 6874 4407 6874 4410 6875 4409 6875 4411 6875 4410 6876 4408 6876 4409 6876 4412 6877 4411 6877 4413 6877 4412 6878 4410 6878 4411 6878 4414 6879 4413 6879 4415 6879 4414 6880 4412 6880 4413 6880 4416 6881 4415 6881 4417 6881 4416 6882 4414 6882 4415 6882 4418 6883 4417 6883 4419 6883 4418 6884 4416 6884 4417 6884 4420 6885 4419 6885 4421 6885 4420 6886 4418 6886 4419 6886 4422 6887 4421 6887 4423 6887 4422 6888 4420 6888 4421 6888 4424 6889 4423 6889 4425 6889 4424 6890 4422 6890 4423 6890 4426 6891 4425 6891 4427 6891 4426 6892 4424 6892 4425 6892 4428 6893 4426 6893 4427 6893 4428 6894 4427 6894 4429 6894 4430 6895 4428 6895 4429 6895 4430 6896 4429 6896 4431 6896 4432 6897 4430 6897 4431 6897 4432 6898 4431 6898 4433 6898 4434 6899 4432 6899 4433 6899 4434 6900 4433 6900 4435 6900 4436 6901 4434 6901 4435 6901 4436 6902 4435 6902 4437 6902 4438 6903 4436 6903 4437 6903 4438 6904 4437 6904 4439 6904 4440 6905 4438 6905 4439 6905 4440 6906 4439 6906 4441 6906 4442 6907 4440 6907 4441 6907 4442 6908 4441 6908 4443 6908 4444 6909 4442 6909 4443 6909 4444 6910 4443 6910 4445 6910 4446 6911 4444 6911 4445 6911 4446 6912 4445 6912 4447 6912 4448 6913 4447 6913 4449 6913 4448 6914 4446 6914 4447 6914 4450 6915 4449 6915 4451 6915 4450 6916 4448 6916 4449 6916 4452 6917 4451 6917 4453 6917 4452 6918 4450 6918 4451 6918 4454 6919 4453 6919 4455 6919 4454 6920 4452 6920 4453 6920 4456 6921 4455 6921 4457 6921 4456 6922 4454 6922 4455 6922 4458 6923 4457 6923 4459 6923 4458 6924 4456 6924 4457 6924 4460 6925 4459 6925 4461 6925 4460 6926 4458 6926 4459 6926 4462 6927 4461 6927 4463 6927 4462 6928 4460 6928 4461 6928 4464 6929 4463 6929 4465 6929 4464 6930 4462 6930 4463 6930 4466 6931 4465 6931 4467 6931 4466 6932 4464 6932 4465 6932 4468 6933 4467 6933 4469 6933 4468 6934 4466 6934 4467 6934 4470 6935 4469 6935 4471 6935 4470 6936 4468 6936 4469 6936 4472 6937 4471 6937 4473 6937 4472 6938 4470 6938 4471 6938 4474 6939 4473 6939 4475 6939 4474 6940 4472 6940 4473 6940 4476 6941 4475 6941 4477 6941 4476 6942 4474 6942 4475 6942 4478 6943 4477 6943 4479 6943 4478 6944 4476 6944 4477 6944 4480 6945 4478 6945 4479 6945 4480 6946 4479 6946 4481 6946 4482 6947 4480 6947 4481 6947 4482 6948 4481 6948 4483 6948 4484 6949 4482 6949 4483 6949 4484 6950 4483 6950 4485 6950 4486 6951 4484 6951 4485 6951 4486 6952 4485 6952 4487 6952 4488 6953 4486 6953 4487 6953 4488 6954 4487 6954 4489 6954 4490 6955 4488 6955 4489 6955 4490 6956 4489 6956 4491 6956 4492 6957 4490 6957 4491 6957 4492 6958 4491 6958 4493 6958 4494 6959 4492 6959 4493 6959 4494 6960 4493 6960 4495 6960 4496 6961 4494 6961 4495 6961 4496 6962 4495 6962 4497 6962 4498 6963 4496 6963 4497 6963 4498 6964 4497 6964 4499 6964 4500 6965 4498 6965 4499 6965 4500 6966 4499 6966 4501 6966 4502 6967 4500 6967 4501 6967 4502 6968 4501 6968 4503 6968 4504 6969 4502 6969 4503 6969 4504 6970 4503 6970 4505 6970 4506 6971 4504 6971 4505 6971 4506 6972 4505 6972 4507 6972 4508 6973 4506 6973 4507 6973 4508 6974 4507 6974 4509 6974 4510 6975 4508 6975 4509 6975 4510 6976 4509 6976 4511 6976 4512 6977 4510 6977 4511 6977 4512 6978 4511 6978 4513 6978 4514 6979 4513 6979 4515 6979 4514 6980 4512 6980 4513 6980 4516 6981 4514 6981 4515 6981 4516 6982 4515 6982 4517 6982 4518 6983 4517 6983 4519 6983 4518 6984 4516 6984 4517 6984 4520 6985 4519 6985 4521 6985 4520 6986 4518 6986 4519 6986 4522 6987 4521 6987 4523 6987 4522 6988 4520 6988 4521 6988 4524 6989 4523 6989 4525 6989 4524 6990 4522 6990 4523 6990 4526 6991 4525 6991 4527 6991 4526 6992 4524 6992 4525 6992 4528 6993 4527 6993 4529 6993 4528 6994 4526 6994 4527 6994 4530 6995 4528 6995 4529 6995 4530 6996 4529 6996 4531 6996 4532 6997 4530 6997 4531 6997 4532 6998 4531 6998 4533 6998 4534 6999 4532 6999 4533 6999 4534 7000 4533 7000 4535 7000 4536 7001 4534 7001 4535 7001 4536 7002 4535 7002 4537 7002 4538 7003 4536 7003 4537 7003 4538 7004 4537 7004 4539 7004 4540 7005 4538 7005 4539 7005 4540 7006 4539 7006 4541 7006 4542 7007 4540 7007 4541 7007 4542 7008 4541 7008 4368 7008 4370 7009 4542 7009 4368 7009 4415 7010 4327 7010 4417 7010 4325 7011 4327 7011 4415 7011 4240 7012 4241 7012 4455 7012 4453 7013 4240 7013 4455 7013 4323 7014 4415 7014 4413 7014 4323 7015 4325 7015 4415 7015 4238 7016 4240 7016 4453 7016 4451 7017 4238 7017 4453 7017 4306 7018 4310 7018 4399 7018 4237 7019 4238 7019 4451 7019 4321 7020 4413 7020 4411 7020 4449 7021 4237 7021 4451 7021 4321 7022 4323 7022 4413 7022 4306 7023 4399 7023 4397 7023 4236 7024 4237 7024 4449 7024 4279 7025 4382 7025 4278 7025 4447 7026 4236 7026 4449 7026 4409 7027 4321 7027 4411 7027 4284 7028 4382 7028 4279 7028 4233 7029 4236 7029 4447 7029 4284 7030 4384 7030 4382 7030 4284 7031 4386 7031 4384 7031 4445 7032 4233 7032 4447 7032 4320 7033 4321 7033 4409 7033 4301 7034 4306 7034 4397 7034 4234 7035 4233 7035 4445 7035 4235 7036 4369 7036 4368 7036 4301 7037 4396 7037 4394 7037 4301 7038 4397 7038 4396 7038 4235 7039 4368 7039 4232 7039 4443 7040 4234 7040 4445 7040 4296 7041 4394 7041 4392 7041 4296 7042 4301 7042 4394 7042 4407 7043 4320 7043 4409 7043 4441 7044 4234 7044 4443 7044 4287 7045 4386 7045 4284 7045 4441 7046 4358 7046 4234 7046 4372 7047 4369 7047 4235 7047 4288 7048 4388 7048 4386 7048 4352 7049 4358 7049 4441 7049 4288 7050 4386 7050 4287 7050 4439 7051 4352 7051 4441 7051 4295 7052 4296 7052 4392 7052 4293 7053 4388 7053 4288 7053 4318 7054 4407 7054 4405 7054 4318 7055 4320 7055 4407 7055 4293 7056 4390 7056 4388 7056 4293 7057 4392 7057 4390 7057 4239 7058 4372 7058 4235 7058 4437 7059 4352 7059 4439 7059 4293 7060 4295 7060 4392 7060 4239 7061 4374 7061 4372 7061 4437 7062 4346 7062 4352 7062 4344 7063 4346 7063 4437 7063 4435 7064 4344 7064 4437 7064 4316 7065 4318 7065 4405 7065 4342 7066 4344 7066 4435 7066 4243 7067 4374 7067 4239 7067 4433 7068 4342 7068 4435 7068 4340 7069 4342 7069 4433 7069 4314 7070 4316 7070 4405 7070 4340 7071 4433 7071 4431 7071 4314 7072 4405 7072 4403 7072 4257 7073 4374 7073 4243 7073 4338 7074 4340 7074 4431 7074 4338 7075 4431 7075 4429 7075 4257 7076 4376 7076 4374 7076 4257 7077 4378 7077 4376 7077 4336 7078 4338 7078 4429 7078 4336 7079 4429 7079 4427 7079 4334 7080 4336 7080 4427 7080 4334 7081 4427 7081 4425 7081 4312 7082 4314 7082 4403 7082 4333 7083 4334 7083 4425 7083 4312 7084 4401 7084 4399 7084 4312 7085 4403 7085 4401 7085 4333 7086 4425 7086 4423 7086 4270 7087 4378 7087 4257 7087 4331 7088 4333 7088 4423 7088 4331 7089 4423 7089 4421 7089 4329 7090 4331 7090 4421 7090 4329 7091 4421 7091 4419 7091 4310 7092 4312 7092 4399 7092 4278 7093 4378 7093 4270 7093 4327 7094 4329 7094 4419 7094 4278 7095 4380 7095 4378 7095 4278 7096 4382 7096 4380 7096 4327 7097 4419 7097 4417 7097 1937 7098 1629 7098 1625 7098 1937 7099 1632 7099 1629 7099 1955 7100 1635 7100 1632 7100 1955 7101 1632 7101 1937 7101 1967 7102 1635 7102 1955 7102 2002 7103 1635 7103 1967 7103 2021 7104 1635 7104 2002 7104 1775 7105 1635 7105 2021 7105 1774 7106 1635 7106 1775 7106 1796 7107 1635 7107 1774 7107 1807 7108 1635 7108 1796 7108 1817 7109 1635 7109 1807 7109 1834 7110 1635 7110 1817 7110 1578 7111 1834 7111 1844 7111 1578 7112 1844 7112 1857 7112 1578 7113 1857 7113 1886 7113 1578 7114 1886 7114 1909 7114 1578 7115 1635 7115 1834 7115 1928 7116 1578 7116 1909 7116 1950 7117 1578 7117 1928 7117 1963 7118 1578 7118 1950 7118 2003 7119 1578 7119 1963 7119 2023 7120 1580 7120 1578 7120 2023 7121 1578 7121 2003 7121 2050 7122 1586 7122 1580 7122 2050 7123 1589 7123 1586 7123 2050 7124 1580 7124 2023 7124 4543 7125 3676 7125 4544 7125 4543 7126 4544 7126 4545 7126 4546 7127 4547 7127 4548 7127 4549 7128 4550 7128 4551 7128 4546 7129 4548 7129 4552 7129 4546 7130 4552 7130 4553 7130 4554 7131 4555 7131 4556 7131 4554 7132 4556 7132 4557 7132 4549 7133 4558 7133 4550 7133 4554 7134 4559 7134 4555 7134 4560 7135 3769 7135 3766 7135 4561 7136 4562 7136 4563 7136 4564 7137 3673 7137 4565 7137 4560 7138 4566 7138 4567 7138 4560 7139 4567 7139 4568 7139 4564 7140 4565 7140 4569 7140 4561 7141 4563 7141 4570 7141 4560 7142 3766 7142 4566 7142 4571 7143 4569 7143 4572 7143 4573 7144 4553 7144 4574 7144 4573 7145 4546 7145 4553 7145 4571 7146 4564 7146 4569 7146 4575 7147 4576 7147 4547 7147 4577 7148 4562 7148 4561 7148 4577 7149 4578 7149 4562 7149 2351 7150 1742 7150 1740 7150 4579 7151 4580 7151 4581 7151 4581 7152 4571 7152 4572 7152 4563 7153 2351 7153 2390 7153 4575 7154 4546 7154 4573 7154 4579 7155 4559 7155 4554 7155 4579 7156 4572 7156 4559 7156 4563 7157 4582 7157 2351 7157 4575 7158 4547 7158 4546 7158 4583 7159 4584 7159 4558 7159 4579 7160 4581 7160 4572 7160 4585 7161 4568 7161 4576 7161 4586 7162 3907 7162 3896 7162 4583 7163 4558 7163 4549 7163 4586 7164 4574 7164 3907 7164 4586 7165 4573 7165 4574 7165 4548 7166 4554 7166 4557 7166 4587 7167 3675 7167 3673 7167 4588 7168 3769 7168 4560 7168 4589 7169 4570 7169 4590 7169 4587 7170 3673 7170 4564 7170 4588 7171 4560 7171 4568 7171 4587 7172 4564 7172 4571 7172 4588 7173 4568 7173 4585 7173 4589 7174 4561 7174 4570 7174 4591 7175 4571 7175 4581 7175 4592 7176 4575 7176 4573 7176 4593 7177 4577 7177 4561 7177 4591 7178 4587 7178 4571 7178 4592 7179 4573 7179 4586 7179 4593 7180 4561 7180 4589 7180 4594 7181 4586 7181 3896 7181 4595 7182 4596 7182 4578 7182 4597 7183 4551 7183 4598 7183 4597 7184 4598 7184 4582 7184 4595 7185 4578 7185 4577 7185 4594 7186 4592 7186 4586 7186 4599 7187 4600 7187 3913 7187 4601 7188 4585 7188 4576 7188 4599 7189 4590 7189 4600 7189 4580 7190 4591 7190 4581 7190 4599 7191 4589 7191 4590 7191 4601 7192 4575 7192 4592 7192 4599 7193 4593 7193 4589 7193 4601 7194 4576 7194 4575 7194 4602 7195 4549 7195 4551 7195 3766 7196 3676 7196 4566 7196 4603 7197 4599 7197 3913 7197 4602 7198 4551 7198 4597 7198 4604 7199 3769 7199 4588 7199 4603 7200 4593 7200 4599 7200 4604 7201 4585 7201 4601 7201 4605 7202 4580 7202 4579 7202 4604 7203 4588 7203 4585 7203 4555 7204 4606 7204 4584 7204 4607 7205 4592 7205 4594 7205 4607 7206 4601 7206 4592 7206 4555 7207 4584 7207 4583 7207 4608 7208 4577 7208 4593 7208 4562 7209 4597 7209 4582 7209 4609 7210 4604 7210 4601 7210 4608 7211 4595 7211 4577 7211 4562 7212 4602 7212 4597 7212 4609 7213 4601 7213 4607 7213 4610 7214 3896 7214 3881 7214 4610 7215 4607 7215 4594 7215 4550 7216 1745 7216 1742 7216 4562 7217 4582 7217 4563 7217 4610 7218 4594 7218 3896 7218 4578 7219 4602 7219 4562 7219 4611 7220 3881 7220 3756 7220 4612 7221 4554 7221 4548 7221 4558 7222 1747 7222 1745 7222 4611 7223 3755 7223 3754 7223 4612 7224 4579 7224 4554 7224 4611 7225 3756 7225 3755 7225 4558 7226 1745 7226 4550 7226 4611 7227 4610 7227 3881 7227 4613 7228 4557 7228 4596 7228 4611 7229 3754 7229 4609 7229 4613 7230 4596 7230 4595 7230 4611 7231 4609 7231 4607 7231 4611 7232 4607 7232 4610 7232 3754 7233 3769 7233 4604 7233 4614 7234 1747 7234 4558 7234 3754 7235 4604 7235 4609 7235 4615 7236 4555 7236 4583 7236 4615 7237 4583 7237 4549 7237 4584 7238 4614 7238 4558 7238 4616 7239 4603 7239 3913 7239 4615 7240 4549 7240 4602 7240 4616 7241 4593 7241 4603 7241 4616 7242 4608 7242 4593 7242 4559 7243 4606 7243 4555 7243 4617 7244 1748 7244 1747 7244 4559 7245 4572 7245 4606 7245 4618 7246 4605 7246 4579 7246 4618 7247 4579 7247 4612 7247 4596 7248 4602 7248 4578 7248 4619 7249 4617 7249 1747 7249 4619 7250 1747 7250 4614 7250 4620 7251 4613 7251 4595 7251 4596 7252 4615 7252 4602 7252 4620 7253 4595 7253 4608 7253 4606 7254 4614 7254 4584 7254 4606 7255 4619 7255 4614 7255 4570 7256 4563 7256 2390 7256 4547 7257 4612 7257 4548 7257 4565 7258 3673 7258 1748 7258 4565 7259 1748 7259 4617 7259 4556 7260 4555 7260 4615 7260 4621 7261 4620 7261 4608 7261 4621 7262 4608 7262 4616 7262 4621 7263 3913 7263 3907 7263 4621 7264 4616 7264 3913 7264 4552 7265 4613 7265 4620 7265 4622 7266 3675 7266 4587 7266 4622 7267 4587 7267 4591 7267 4569 7268 4565 7268 4617 7268 4545 7269 4591 7269 4580 7269 4552 7270 4548 7270 4557 7270 4552 7271 4557 7271 4613 7271 4569 7272 4617 7272 4619 7272 4545 7273 4622 7273 4591 7273 4576 7274 4612 7274 4547 7274 4576 7275 4618 7275 4612 7275 4590 7276 4570 7276 2390 7276 4572 7277 4619 7277 4606 7277 4572 7278 4569 7278 4619 7278 4623 7279 4545 7279 4580 7279 4553 7280 4552 7280 4620 7280 4567 7281 4605 7281 4618 7281 4557 7282 4615 7282 4596 7282 4598 7283 1742 7283 2351 7283 4557 7284 4556 7284 4615 7284 4567 7285 4623 7285 4580 7285 4567 7286 4580 7286 4605 7286 4624 7287 3676 7287 3675 7287 4624 7288 3675 7288 4622 7288 4582 7289 4598 7289 2351 7289 4574 7290 4621 7290 3907 7290 4574 7291 4553 7291 4620 7291 4574 7292 4620 7292 4621 7292 4544 7293 4622 7293 4545 7293 4544 7294 3676 7294 4624 7294 4566 7295 4623 7295 4567 7295 4551 7296 4550 7296 1742 7296 4544 7297 4624 7297 4622 7297 4551 7298 1742 7298 4598 7298 4566 7299 3676 7299 4543 7299 4600 7300 2390 7300 2365 7300 4566 7301 4543 7301 4623 7301 4600 7302 2365 7302 3913 7302 4600 7303 4590 7303 2390 7303 4568 7304 4618 7304 4576 7304 4568 7305 4567 7305 4618 7305 4543 7306 4545 7306 4623 7306 4625 7307 4218 7307 3938 7307 4057 7308 4625 7308 3938 7308 4156 7309 4057 7309 4059 7309 4156 7310 4155 7310 4625 7310 4156 7311 4625 7311 4057 7311 4179 7312 4059 7312 4028 7312 4179 7313 4156 7313 4059 7313 4198 7314 4028 7314 4027 7314 4198 7315 4179 7315 4028 7315 4211 7316 4027 7316 4046 7316 4211 7317 4198 7317 4027 7317 4079 7318 4046 7318 2580 7318 4079 7319 4211 7319 4046 7319 2554 7320 4079 7320 2580 7320 4626 7321 4627 7321 4628 7321 4629 7322 4630 7322 4631 7322 4629 7323 4631 7323 4632 7323 4633 7324 4634 7324 4629 7324 4635 7325 4636 7325 4637 7325 4633 7326 4221 7326 4638 7326 4633 7327 4638 7327 4634 7327 4635 7328 4639 7328 4636 7328 4640 7329 4629 7329 4632 7329 4641 7330 2495 7330 1692 7330 4640 7331 4633 7331 4629 7331 4641 7332 4628 7332 2495 7332 4641 7333 4626 7333 4628 7333 4642 7334 4643 7334 4644 7334 4642 7335 4644 7335 4645 7335 4646 7336 4626 7336 4641 7336 4642 7337 4645 7337 4647 7337 4648 7338 4647 7338 3602 7338 4648 7339 4642 7339 4647 7339 4649 7340 4639 7340 4635 7340 4650 7341 4633 7341 4640 7341 4651 7342 4637 7342 4652 7342 4653 7343 4643 7343 4642 7343 4651 7344 4652 7344 4626 7344 4653 7345 4632 7345 4643 7345 4651 7346 4626 7346 4646 7346 4654 7347 3602 7347 3601 7347 4654 7348 4653 7348 4642 7348 4654 7349 4648 7349 3602 7349 4655 7350 4637 7350 4651 7350 4654 7351 4642 7351 4648 7351 4656 7352 4640 7352 4632 7352 4656 7353 4650 7353 4640 7353 4656 7354 4632 7354 4653 7354 4657 7355 4095 7355 4103 7355 4657 7356 4103 7356 4639 7356 4228 7357 4221 7357 4633 7357 4228 7358 4633 7358 4650 7358 4657 7359 4639 7359 4649 7359 4658 7360 4654 7360 3601 7360 4658 7361 4653 7361 4654 7361 4659 7362 4651 7362 4646 7362 4658 7363 4656 7363 4653 7363 4659 7364 4655 7364 4651 7364 4659 7365 4646 7365 1688 7365 4660 7366 3611 7366 4228 7366 4660 7367 4228 7367 4650 7367 4660 7368 4650 7368 4656 7368 4661 7369 3601 7369 3611 7369 4662 7370 4095 7370 4657 7370 4661 7371 3611 7371 4660 7371 4661 7372 4658 7372 3601 7372 4661 7373 4656 7373 4658 7373 4661 7374 4660 7374 4656 7374 4663 7375 4655 7375 4659 7375 4664 7376 4635 7376 4637 7376 4664 7377 4637 7377 4655 7377 4664 7378 4655 7378 4663 7378 4665 7379 4657 7379 4649 7379 4665 7380 4662 7380 4657 7380 4666 7381 1690 7381 1688 7381 4666 7382 1692 7382 1690 7382 4666 7383 4641 7383 1692 7383 4666 7384 1688 7384 4646 7384 4666 7385 4646 7385 4641 7385 4630 7386 4662 7386 4665 7386 4667 7387 2523 7387 2512 7387 4668 7388 4664 7388 4663 7388 4669 7389 4664 7389 4668 7389 4669 7390 4649 7390 4635 7390 4670 7391 4115 7391 2523 7391 4669 7392 4635 7392 4664 7392 4670 7393 2523 7393 4667 7393 4671 7394 4087 7394 4095 7394 4671 7395 4095 7395 4662 7395 4627 7396 2512 7396 2495 7396 4671 7397 4662 7397 4630 7397 4627 7398 4670 7398 4667 7398 4627 7399 4667 7399 2512 7399 4644 7400 4669 7400 4668 7400 4672 7401 4221 7401 4074 7401 4673 7402 4115 7402 4670 7402 4672 7403 4074 7403 4087 7403 4672 7404 4087 7404 4671 7404 4674 7405 1688 7405 1687 7405 4674 7406 4668 7406 4663 7406 4674 7407 4659 7407 1688 7407 4674 7408 4663 7408 4659 7408 4675 7409 4115 7409 4673 7409 4676 7410 4669 7410 4644 7410 4676 7411 4649 7411 4669 7411 4676 7412 4665 7412 4649 7412 4677 7413 4670 7413 4627 7413 4677 7414 4673 7414 4670 7414 4634 7415 4672 7415 4671 7415 4634 7416 4671 7416 4630 7416 4652 7417 4675 7417 4673 7417 4638 7418 4221 7418 4672 7418 4652 7419 4673 7419 4677 7419 4638 7420 4672 7420 4634 7420 4631 7421 4665 7421 4676 7421 4636 7422 4103 7422 4115 7422 4631 7423 4630 7423 4665 7423 4636 7424 4115 7424 4675 7424 4643 7425 4676 7425 4644 7425 4643 7426 4631 7426 4676 7426 4637 7427 4636 7427 4675 7427 4637 7428 4675 7428 4652 7428 4678 7429 4644 7429 4668 7429 4678 7430 4668 7430 4674 7430 4678 7431 4674 7431 1687 7431 4679 7432 1687 7432 1685 7432 4679 7433 4678 7433 1687 7433 4628 7434 4627 7434 2495 7434 4632 7435 4631 7435 4643 7435 4639 7436 4103 7436 4636 7436 4645 7437 4644 7437 4678 7437 4645 7438 4678 7438 4679 7438 4647 7439 1685 7439 3602 7439 4647 7440 4679 7440 1685 7440 4647 7441 4645 7441 4679 7441 4626 7442 4677 7442 4627 7442 4626 7443 4652 7443 4677 7443 4629 7444 4634 7444 4630 7444 4542 7445 4370 7445 3731 7445 4542 7446 3731 7446 4680 7446 4681 7447 4542 7447 4680 7447 4540 7448 4542 7448 4681 7448 4682 7449 4540 7449 4681 7449 4538 7450 4540 7450 4682 7450 4683 7451 4538 7451 4682 7451 4536 7452 4538 7452 4683 7452 4684 7453 4536 7453 4683 7453 4534 7454 4536 7454 4684 7454 4685 7455 4534 7455 4684 7455 4532 7456 4534 7456 4685 7456 4686 7457 4532 7457 4685 7457 4530 7458 4532 7458 4686 7458 4687 7459 4530 7459 4686 7459 4528 7460 4530 7460 4687 7460 4688 7461 4528 7461 4687 7461 4526 7462 4528 7462 4688 7462 4689 7463 4526 7463 4688 7463 4524 7464 4526 7464 4689 7464 4690 7465 4524 7465 4689 7465 4522 7466 4524 7466 4690 7466 4691 7467 4522 7467 4690 7467 4520 7468 4522 7468 4691 7468 4692 7469 4520 7469 4691 7469 4518 7470 4520 7470 4692 7470 4693 7471 4518 7471 4692 7471 4516 7472 4518 7472 4693 7472 4694 7473 4516 7473 4693 7473 4514 7474 4516 7474 4694 7474 4695 7475 4514 7475 4694 7475 4512 7476 4514 7476 4695 7476 4696 7477 4512 7477 4695 7477 4510 7478 4512 7478 4696 7478 4697 7479 4510 7479 4696 7479 4508 7480 4510 7480 4697 7480 4698 7481 4508 7481 4697 7481 4506 7482 4508 7482 4698 7482 4699 7483 4506 7483 4698 7483 4504 7484 4506 7484 4699 7484 4700 7485 4504 7485 4699 7485 4502 7486 4504 7486 4700 7486 4701 7487 4502 7487 4700 7487 4500 7488 4502 7488 4701 7488 4702 7489 4500 7489 4701 7489 4498 7490 4500 7490 4702 7490 4703 7491 4498 7491 4702 7491 4496 7492 4498 7492 4703 7492 4704 7493 4496 7493 4703 7493 4494 7494 4496 7494 4704 7494 4705 7495 4494 7495 4704 7495 4492 7496 4494 7496 4705 7496 4706 7497 4492 7497 4705 7497 4490 7498 4492 7498 4706 7498 4707 7499 4490 7499 4706 7499 4488 7500 4490 7500 4707 7500 4708 7501 4488 7501 4707 7501 4486 7502 4488 7502 4708 7502 4709 7503 4486 7503 4708 7503 4484 7504 4486 7504 4709 7504 4710 7505 4484 7505 4709 7505 4482 7506 4484 7506 4710 7506 4711 7507 4482 7507 4710 7507 4480 7508 4482 7508 4711 7508 4712 7509 4480 7509 4711 7509 4478 7510 4480 7510 4712 7510 4713 7511 4478 7511 4712 7511 4476 7512 4478 7512 4713 7512 4714 7513 4476 7513 4713 7513 4474 7514 4476 7514 4714 7514 4715 7515 4474 7515 4714 7515 4472 7516 4474 7516 4715 7516 4716 7517 4472 7517 4715 7517 4470 7518 4472 7518 4716 7518 4717 7519 4470 7519 4716 7519 4468 7520 4470 7520 4717 7520 4718 7521 4468 7521 4717 7521 4466 7522 4468 7522 4718 7522 4719 7523 4466 7523 4718 7523 4464 7524 4466 7524 4719 7524 4720 7525 4464 7525 4719 7525 4462 7526 4464 7526 4720 7526 4721 7527 4462 7527 4720 7527 4460 7528 4462 7528 4721 7528 4722 7529 4460 7529 4721 7529 4458 7530 4460 7530 4722 7530 3707 7531 4458 7531 4722 7531 4456 7532 4458 7532 3707 7532 4454 7533 3707 7533 3708 7533 4454 7534 4456 7534 3707 7534 4452 7535 3708 7535 3709 7535 4452 7536 4454 7536 3708 7536 4450 7537 3709 7537 3710 7537 4450 7538 4452 7538 3709 7538 4448 7539 3710 7539 3711 7539 4448 7540 4450 7540 3710 7540 4446 7541 3711 7541 3712 7541 4446 7542 4448 7542 3711 7542 4444 7543 3712 7543 3713 7543 4444 7544 4446 7544 3712 7544 4442 7545 3713 7545 3714 7545 4442 7546 4444 7546 3713 7546 4440 7547 3714 7547 3715 7547 4440 7548 4442 7548 3714 7548 4438 7549 3715 7549 3716 7549 4438 7550 4440 7550 3715 7550 4436 7551 3716 7551 3717 7551 4436 7552 4438 7552 3716 7552 4434 7553 3717 7553 3718 7553 4434 7554 4436 7554 3717 7554 4432 7555 4434 7555 3718 7555 4432 7556 3718 7556 3719 7556 4430 7557 4432 7557 3719 7557 4430 7558 3719 7558 3720 7558 4428 7559 4430 7559 3720 7559 4428 7560 3720 7560 3721 7560 4426 7561 4428 7561 3721 7561 4426 7562 3721 7562 3722 7562 4424 7563 4426 7563 3722 7563 4424 7564 3722 7564 3723 7564 4422 7565 4424 7565 3723 7565 4422 7566 3723 7566 3724 7566 4420 7567 4422 7567 3724 7567 4420 7568 3724 7568 3725 7568 4418 7569 3725 7569 3726 7569 4418 7570 4420 7570 3725 7570 4416 7571 3726 7571 3727 7571 4416 7572 4418 7572 3726 7572 4414 7573 3727 7573 3728 7573 4414 7574 4416 7574 3727 7574 4412 7575 3728 7575 3729 7575 4412 7576 4414 7576 3728 7576 4410 7577 3729 7577 3732 7577 4410 7578 4412 7578 3729 7578 4408 7579 3732 7579 3734 7579 4408 7580 4410 7580 3732 7580 4406 7581 3734 7581 3736 7581 4406 7582 4408 7582 3734 7582 4404 7583 3736 7583 3738 7583 4404 7584 4406 7584 3736 7584 4402 7585 3738 7585 3739 7585 4402 7586 4404 7586 3738 7586 4400 7587 3739 7587 3742 7587 4400 7588 4402 7588 3739 7588 4398 7589 3742 7589 3744 7589 4398 7590 4400 7590 3742 7590 4395 7591 3744 7591 3746 7591 4395 7592 4398 7592 3744 7592 4393 7593 3746 7593 3704 7593 4393 7594 4395 7594 3746 7594 4391 7595 3704 7595 3703 7595 4391 7596 4393 7596 3704 7596 3705 7597 4391 7597 3703 7597 4389 7598 4391 7598 3705 7598 3706 7599 4389 7599 3705 7599 4387 7600 4389 7600 3706 7600 3747 7601 4387 7601 3706 7601 4385 7602 4387 7602 3747 7602 3745 7603 4385 7603 3747 7603 4383 7604 4385 7604 3745 7604 3743 7605 4383 7605 3745 7605 4381 7606 4383 7606 3743 7606 3741 7607 4381 7607 3743 7607 4379 7608 4381 7608 3741 7608 3740 7609 4379 7609 3741 7609 4377 7610 4379 7610 3740 7610 3737 7611 4377 7611 3740 7611 4375 7612 4377 7612 3737 7612 3735 7613 4375 7613 3737 7613 4373 7614 4375 7614 3735 7614 3733 7615 4373 7615 3735 7615 4371 7616 4373 7616 3733 7616 3730 7617 4371 7617 3733 7617 4367 7618 4371 7618 3730 7618 3731 7619 4367 7619 3730 7619 4370 7620 4367 7620 3731 7620 4723 7621 4230 7621 4224 7621 4724 7622 4220 7622 4230 7622 4724 7623 4230 7623 4723 7623 4725 7624 4071 7624 4220 7624 4725 7625 4220 7625 4724 7625 96 7626 4725 7626 2202 7626 96 7627 2202 7627 104 7627 96 7628 4071 7628 4725 7628 88 7629 4069 7629 4071 7629 88 7630 4071 7630 96 7630 74 7631 4067 7631 4069 7631 74 7632 4069 7632 88 7632 75 7633 4064 7633 4067 7633 75 7634 4062 7634 4064 7634 75 7635 4067 7635 74 7635 137 7636 4062 7636 75 7636 4063 7637 4062 7637 137 7637 128 7638 4150 7638 4063 7638 128 7639 4152 7639 4150 7639 128 7640 4155 7640 4152 7640 128 7641 4063 7641 137 7641 119 7642 4155 7642 128 7642 111 7643 4155 7643 119 7643 2203 7644 105 7644 97 7644 2203 7645 111 7645 105 7645 2203 7646 4155 7646 111 7646 4726 7647 4155 7647 2203 7647 4727 7648 4155 7648 4726 7648 4625 7649 4155 7649 4727 7649 2198 7650 2202 7650 4725 7650 4728 7651 4725 7651 4724 7651 4728 7652 2197 7652 2198 7652 4728 7653 2198 7653 4725 7653 4729 7654 4724 7654 4723 7654 4730 7655 4724 7655 4729 7655 4730 7656 4728 7656 4724 7656 4731 7657 4730 7657 4729 7657 4223 7658 4729 7658 4224 7658 4729 7659 4723 7659 4224 7659 3926 7660 3925 7660 4732 7660 4060 7661 3926 7661 4732 7661 4009 7662 4060 7662 4732 7662 4038 7663 4732 7663 4040 7663 4031 7664 4732 7664 4038 7664 4030 7665 4009 7665 4732 7665 4030 7666 4732 7666 4031 7666 4733 7667 3960 7667 3978 7667 4733 7668 4004 7668 3960 7668 4733 7669 3999 7669 4004 7669 4733 7670 4000 7670 3999 7670 4733 7671 3952 7671 4000 7671 3951 7672 3952 7672 4733 7672 4732 7673 4734 7673 4735 7673 4732 7674 4736 7674 4734 7674 4048 7675 4040 7675 4732 7675 3920 7676 4048 7676 4732 7676 4733 7677 4735 7677 4737 7677 4733 7678 4738 7678 4739 7678 4733 7679 4737 7679 4738 7679 4733 7680 4732 7680 4735 7680 4733 7681 3920 7681 4732 7681 3921 7682 3920 7682 4733 7682 3970 7683 3921 7683 4733 7683 3978 7684 3970 7684 4733 7684 3782 7685 4740 7685 4741 7685 2194 7686 3782 7686 4741 7686 5 7687 3778 7687 3780 7687 5 7688 3794 7688 3782 7688 5 7689 3796 7689 3794 7689 5 7690 3780 7690 3796 7690 5 7691 3782 7691 7 7691 9 7692 7 7692 3782 7692 9 7693 3782 7693 2194 7693 4 7694 3776 7694 3778 7694 4 7695 3778 7695 5 7695 11 7696 9 7696 2194 7696 18 7697 3775 7697 3776 7697 18 7698 3776 7698 4 7698 13 7699 11 7699 2194 7699 56 7700 3773 7700 3775 7700 56 7701 3771 7701 3773 7701 56 7702 3775 7702 18 7702 49 7703 3759 7703 3771 7703 49 7704 3771 7704 56 7704 2195 7705 49 7705 45 7705 2195 7706 3759 7706 49 7706 4742 7707 3753 7707 3759 7707 4742 7708 3759 7708 2195 7708 4743 7709 3753 7709 4742 7709 4744 7710 3753 7710 4743 7710 3768 7711 3753 7711 4744 7711 3761 7712 3768 7712 4744 7712 3782 7713 3781 7713 4740 7713 3761 7714 4744 7714 4745 7714 3761 7715 4745 7715 3762 7715 4745 7716 4744 7716 4743 7716 4746 7717 4743 7717 4742 7717 4746 7718 4747 7718 4745 7718 4746 7719 4745 7719 4743 7719 2196 7720 4742 7720 2195 7720 4748 7721 4746 7721 4742 7721 4748 7722 4742 7722 2196 7722 4749 7723 4748 7723 2196 7723 3749 7724 4750 7724 4751 7724 4752 7725 3749 7725 4751 7725 3781 7726 3751 7726 3749 7726 4740 7727 3749 7727 4752 7727 4740 7728 3781 7728 3749 7728 4741 7729 4752 7729 4753 7729 4741 7730 4740 7730 4752 7730 2193 7731 4753 7731 2201 7731 2193 7732 4741 7732 4753 7732 2194 7733 4741 7733 2193 7733 4217 7734 4218 7734 4625 7734 4727 7735 4217 7735 4625 7735 4754 7736 4755 7736 4217 7736 4756 7737 4727 7737 4726 7737 4756 7738 4217 7738 4727 7738 4756 7739 4754 7739 4217 7739 4757 7740 4756 7740 4726 7740 2200 7741 4726 7741 2203 7741 2200 7742 4757 7742 4726 7742 2199 7743 4757 7743 2200 7743 1764 7744 2190 7744 2191 7744 2129 7745 1737 7745 1739 7745 2130 7746 2129 7746 1739 7746 1764 7747 2191 7747 1757 7747 2191 7748 2125 7748 1757 7748 1750 7749 1755 7749 2162 7749 1746 7750 1750 7750 2163 7750 1750 7751 2162 7751 2163 7751 1755 7752 1758 7752 2142 7752 2162 7753 1755 7753 2142 7753 1743 7754 1746 7754 2164 7754 2130 7755 1739 7755 1741 7755 2131 7756 2130 7756 1741 7756 1746 7757 2163 7757 2164 7757 1757 7758 2125 7758 1754 7758 2125 7759 2160 7759 1754 7759 1758 7760 1723 7760 2140 7760 2135 7761 2131 7761 1744 7761 2142 7762 1758 7762 2140 7762 2131 7763 1741 7763 1744 7763 1735 7764 1743 7764 2167 7764 2160 7765 2136 7765 1751 7765 1754 7766 2160 7766 1751 7766 1743 7767 2164 7767 2167 7767 2136 7768 2135 7768 1749 7768 2135 7769 1744 7769 1749 7769 1751 7770 2136 7770 1749 7770 2140 7771 1723 7771 2141 7771 2141 7772 1723 7772 1724 7772 1730 7773 1735 7773 2144 7773 1735 7774 2167 7774 2144 7774 2141 7775 1724 7775 2176 7775 1726 7776 1730 7776 2172 7776 1730 7777 2144 7777 2172 7777 2176 7778 1724 7778 1728 7778 2176 7779 1728 7779 2177 7779 1726 7780 2172 7780 2155 7780 1726 7781 2155 7781 1719 7781 2177 7782 1728 7782 1732 7782 2177 7783 1732 7783 2184 7783 1719 7784 2155 7784 2181 7784 1719 7785 2181 7785 1720 7785 2184 7786 1732 7786 1734 7786 2184 7787 1734 7787 2185 7787 1720 7788 2181 7788 2182 7788 1720 7789 2182 7789 1768 7789 2185 7790 1734 7790 1737 7790 2129 7791 2185 7791 1737 7791 1768 7792 2182 7792 2190 7792 1768 7793 2190 7793 1764 7793 1714 7794 476 7794 477 7794 415 7795 1686 7795 1689 7795 416 7796 415 7796 1689 7796 1714 7797 477 7797 1712 7797 477 7798 412 7798 1712 7798 1697 7799 1702 7799 448 7799 1694 7800 1697 7800 449 7800 1697 7801 448 7801 449 7801 1702 7802 1707 7802 426 7802 448 7803 1702 7803 426 7803 1676 7804 1694 7804 450 7804 416 7805 1689 7805 1693 7805 417 7806 416 7806 1693 7806 1694 7807 449 7807 450 7807 1712 7808 412 7808 1709 7808 412 7809 446 7809 1709 7809 1707 7810 1671 7810 424 7810 421 7811 417 7811 1699 7811 426 7812 1707 7812 424 7812 417 7813 1693 7813 1699 7813 1669 7814 1676 7814 453 7814 446 7815 422 7815 1705 7815 1709 7816 446 7816 1705 7816 1676 7817 450 7817 453 7817 422 7818 421 7818 1700 7818 421 7819 1699 7819 1700 7819 1705 7820 422 7820 1700 7820 424 7821 1671 7821 425 7821 425 7822 1671 7822 1675 7822 1670 7823 1669 7823 430 7823 1669 7824 453 7824 430 7824 425 7825 1675 7825 462 7825 1718 7826 1670 7826 458 7826 1670 7827 430 7827 458 7827 462 7828 1675 7828 1679 7828 462 7829 1679 7829 463 7829 1718 7830 458 7830 442 7830 1718 7831 442 7831 1717 7831 463 7832 1679 7832 1682 7832 463 7833 1682 7833 470 7833 1717 7834 442 7834 467 7834 1717 7835 467 7835 1716 7835 470 7836 1682 7836 1684 7836 470 7837 1684 7837 471 7837 1716 7838 467 7838 468 7838 1716 7839 468 7839 1715 7839 471 7840 1684 7840 1686 7840 415 7841 471 7841 1686 7841 1715 7842 468 7842 476 7842 1715 7843 476 7843 1714 7843 319 7844 1628 7844 1631 7844 321 7845 319 7845 1631 7845 1664 7846 337 7846 1658 7846 334 7847 333 7847 1658 7847 337 7848 334 7848 1658 7848 321 7849 1631 7849 1637 7849 323 7850 321 7850 1637 7850 1658 7851 333 7851 1655 7851 1626 7852 1633 7852 301 7852 323 7853 1637 7853 1642 7853 1633 7854 307 7854 301 7854 1633 7855 1640 7855 311 7855 1640 7856 1644 7856 311 7856 307 7857 1633 7857 311 7857 331 7858 329 7858 1654 7858 333 7859 331 7859 1654 7859 1655 7860 333 7860 1654 7860 325 7861 323 7861 1647 7861 327 7862 325 7862 1647 7862 1622 7863 1626 7863 298 7863 323 7864 1642 7864 1647 7864 1626 7865 301 7865 298 7865 1654 7866 329 7866 1653 7866 329 7867 327 7867 1650 7867 311 7868 1644 7868 315 7868 1653 7869 329 7869 1650 7869 327 7870 1647 7870 1650 7870 1614 7871 1619 7871 299 7871 1619 7872 1622 7872 299 7872 1622 7873 298 7873 299 7873 1612 7874 1611 7874 305 7874 1644 7875 1612 7875 305 7875 315 7876 1644 7876 305 7876 1614 7877 299 7877 345 7877 305 7878 1611 7878 304 7878 304 7879 1611 7879 1617 7879 1606 7880 1614 7880 343 7880 1614 7881 345 7881 343 7881 304 7882 1617 7882 309 7882 1607 7883 1606 7883 341 7883 1606 7884 343 7884 341 7884 1617 7885 1624 7885 313 7885 309 7886 1617 7886 313 7886 341 7887 339 7887 1667 7887 1607 7888 341 7888 1667 7888 313 7889 1624 7889 1628 7889 317 7890 313 7890 1628 7890 317 7891 1628 7891 319 7891 1667 7892 339 7892 1664 7892 339 7893 337 7893 1664 7893 267 7894 1562 7894 1567 7894 268 7895 267 7895 1567 7895 1547 7896 284 7896 1548 7896 281 7897 280 7897 1548 7897 284 7898 281 7898 1548 7898 268 7899 1567 7899 1576 7899 270 7900 268 7900 1576 7900 1548 7901 280 7901 1601 7901 1579 7902 1585 7902 248 7902 270 7903 1576 7903 1581 7903 1585 7904 254 7904 248 7904 1585 7905 1588 7905 256 7905 1588 7906 1593 7906 256 7906 254 7907 1585 7907 256 7907 278 7908 276 7908 1598 7908 280 7909 278 7909 1598 7909 1601 7910 280 7910 1598 7910 273 7911 270 7911 1583 7911 274 7912 273 7912 1583 7912 1574 7913 1579 7913 249 7913 270 7914 1581 7914 1583 7914 1579 7915 248 7915 249 7915 1598 7916 276 7916 1595 7916 276 7917 274 7917 1590 7917 256 7918 1593 7918 259 7918 1595 7919 276 7919 1590 7919 274 7920 1583 7920 1590 7920 1565 7921 1570 7921 295 7921 1570 7922 1574 7922 295 7922 1574 7923 249 7923 295 7923 1544 7924 1543 7924 252 7924 1593 7925 1544 7925 252 7925 259 7926 1593 7926 252 7926 1565 7927 295 7927 293 7927 252 7928 1543 7928 258 7928 258 7929 1543 7929 1550 7929 1560 7930 1565 7930 291 7930 1565 7931 293 7931 291 7931 258 7932 1550 7932 261 7932 1554 7933 1560 7933 289 7933 1560 7934 291 7934 289 7934 1550 7935 1556 7935 263 7935 261 7936 1550 7936 263 7936 289 7937 286 7937 1552 7937 1554 7938 289 7938 1552 7938 263 7939 1556 7939 1562 7939 265 7940 263 7940 1562 7940 265 7941 1562 7941 267 7941 1552 7942 286 7942 1547 7942 286 7943 284 7943 1547 7943 4758 7944 4759 7944 4760 7944 4760 7945 4759 7945 4761 7945 4759 7946 2443 7946 4762 7946 4761 7947 4759 7947 4762 7947 2443 7948 2449 7948 4763 7948 4762 7949 2443 7949 4763 7949 4764 7950 4758 7950 4765 7950 4758 7951 4760 7951 4765 7951 4760 7952 4761 7952 4766 7952 4765 7953 4760 7953 4766 7953 4766 7954 4761 7954 4767 7954 4761 7955 4762 7955 4767 7955 2449 7956 2448 7956 4768 7956 4762 7957 4763 7957 4768 7957 4763 7958 2449 7958 4768 7958 4767 7959 4762 7959 4768 7959 4769 7960 4764 7960 4770 7960 4764 7961 4765 7961 4770 7961 4765 7962 4766 7962 4771 7962 4770 7963 4765 7963 4771 7963 4766 7964 4767 7964 4772 7964 4771 7965 4766 7965 4772 7965 2448 7966 2446 7966 4773 7966 4768 7967 2448 7967 4773 7967 4767 7968 4768 7968 4773 7968 4772 7969 4767 7969 4773 7969 4774 7970 4769 7970 4775 7970 4776 7971 4774 7971 4775 7971 4769 7972 4770 7972 4775 7972 4776 7973 4775 7973 4777 7973 4770 7974 4771 7974 4777 7974 4775 7975 4770 7975 4777 7975 2373 7976 4776 7976 4778 7976 4771 7977 4772 7977 4778 7977 4776 7978 4777 7978 4778 7978 4777 7979 4771 7979 4778 7979 2446 7980 2428 7980 4779 7980 2428 7981 2373 7981 4779 7981 4773 7982 2446 7982 4779 7982 4772 7983 4773 7983 4779 7983 2373 7984 4778 7984 4779 7984 4778 7985 4772 7985 4779 7985 2443 7986 4759 7986 2451 7986 4759 7987 4780 7987 2451 7987 4781 7988 2521 7988 4780 7988 4780 7989 2521 7989 2451 7989 4782 7990 2522 7990 4781 7990 4781 7991 2522 7991 2521 7991 4783 7992 2559 7992 2525 7992 4784 7993 4783 7993 2525 7993 4782 7994 4784 7994 2522 7994 4784 7995 2525 7995 2522 7995 4785 7996 2506 7996 2528 7996 4786 7997 4785 7997 2528 7997 4787 7998 4786 7998 2540 7998 4786 7999 2528 7999 2540 7999 4787 8000 2540 8000 4788 8000 4788 8001 2540 8001 2550 8001 4788 8002 2550 8002 4789 8002 4789 8003 2550 8003 2552 8003 4790 8004 4789 8004 2560 8004 4789 8005 2552 8005 2560 8005 4783 8006 4790 8006 2559 8006 4790 8007 2560 8007 2559 8007 4791 8008 2473 8008 2472 8008 4792 8009 4791 8009 2472 8009 4793 8010 4792 8010 2493 8010 4792 8011 2472 8011 2493 8011 4793 8012 2493 8012 4794 8012 4794 8013 2493 8013 2505 8013 4785 8014 4794 8014 2506 8014 4794 8015 2505 8015 2506 8015 4795 8016 2422 8016 4796 8016 4796 8017 2422 8017 2421 8017 4791 8018 4796 8018 2473 8018 4796 8019 2421 8019 2473 8019 2423 8020 2422 8020 4795 8020 4797 8021 2423 8021 4795 8021 4798 8022 2424 8022 4797 8022 4797 8023 2424 8023 2423 8023 4799 8024 2457 8024 2456 8024 4800 8025 4799 8025 2456 8025 4798 8026 4800 8026 2424 8026 4800 8027 2456 8027 2424 8027 2400 8028 2457 8028 4799 8028 4801 8029 2400 8029 4799 8029 4802 8030 2337 8030 2400 8030 4802 8031 2400 8031 4801 8031 4803 8032 2617 8032 2334 8032 4804 8033 4803 8033 2334 8033 4802 8034 4804 8034 2337 8034 4804 8035 2334 8035 2337 8035 4805 8036 2378 8036 2617 8036 4803 8037 4805 8037 2617 8037 2379 8038 2378 8038 4805 8038 4806 8039 2379 8039 4805 8039 2380 8040 2379 8040 4806 8040 4807 8041 2380 8041 4806 8041 4808 8042 2691 8042 2693 8042 4809 8043 4808 8043 2693 8043 4809 8044 2693 8044 4810 8044 4810 8045 2693 8045 2692 8045 4811 8046 4810 8046 2695 8046 4810 8047 2692 8047 2695 8047 4811 8048 2695 8048 4812 8048 4812 8049 2695 8049 2618 8049 4807 8050 4812 8050 2380 8050 4812 8051 2618 8051 2380 8051 2335 8052 2691 8052 4808 8052 4813 8053 2335 8053 4808 8053 4814 8054 2648 8054 2335 8054 4814 8055 2335 8055 4813 8055 2648 8056 4814 8056 2662 8056 4814 8057 4815 8057 2662 8057 4816 8058 2375 8058 4817 8058 4817 8059 2375 8059 2669 8059 4818 8060 4817 8060 2668 8060 4817 8061 2669 8061 2668 8061 4819 8062 4818 8062 2666 8062 4818 8063 2668 8063 2666 8063 4819 8064 2666 8064 4820 8064 4820 8065 2666 8065 2667 8065 4815 8066 4820 8066 2662 8066 4820 8067 2667 8067 2662 8067 2375 8068 4816 8068 4776 8068 2375 8069 4776 8069 2373 8069 4774 8070 4821 8070 4781 8070 4795 8071 4822 8071 4823 8071 4774 8072 4781 8072 4769 8072 4792 8073 4793 8073 4824 8073 4825 8074 4792 8074 4824 8074 4801 8075 4799 8075 4800 8075 4795 8076 4823 8076 4826 8076 4801 8077 4800 8077 4802 8077 4805 8078 4795 8078 4826 8078 4802 8079 4800 8079 4798 8079 4793 8080 4794 8080 4827 8080 4759 8081 4758 8081 4780 8081 4824 8082 4793 8082 4827 8082 4802 8083 4798 8083 4804 8083 4758 8084 4764 8084 4780 8084 4764 8085 4769 8085 4780 8085 4804 8086 4798 8086 4803 8086 4769 8087 4781 8087 4780 8087 4797 8088 4805 8088 4803 8088 4805 8089 4826 8089 4828 8089 4827 8090 4794 8090 4829 8090 4794 8091 4785 8091 4829 8091 4813 8092 4808 8092 4809 8092 4829 8093 4785 8093 4830 8093 4806 8094 4805 8094 4831 8094 4813 8095 4809 8095 4810 8095 4805 8096 4828 8096 4831 8096 4806 8097 4831 8097 4832 8097 4813 8098 4810 8098 4811 8098 4785 8099 4786 8099 4833 8099 4786 8100 4787 8100 4833 8100 4830 8101 4785 8101 4833 8101 4787 8102 4788 8102 4834 8102 4833 8103 4787 8103 4834 8103 4834 8104 4788 8104 4835 8104 4817 8105 4807 8105 4816 8105 4806 8106 4832 8106 4816 8106 4807 8107 4806 8107 4816 8107 4814 8108 4819 8108 4820 8108 4835 8109 4788 8109 4789 8109 4814 8110 4820 8110 4815 8110 4814 8111 4813 8111 4818 8111 4819 8112 4814 8112 4818 8112 4835 8113 4789 8113 4836 8113 4813 8114 4811 8114 4818 8114 4818 8115 4811 8115 4817 8115 4811 8116 4812 8116 4817 8116 4836 8117 4789 8117 4790 8117 4803 8118 4798 8118 4797 8118 4816 8119 4832 8119 4776 8119 4837 8120 4836 8120 4783 8120 4817 8121 4812 8121 4807 8121 4836 8122 4790 8122 4783 8122 4797 8123 4795 8123 4805 8123 4776 8124 4832 8124 4821 8124 4838 8125 4837 8125 4784 8125 4839 8126 4838 8126 4784 8126 4840 8127 4839 8127 4784 8127 4795 8128 4796 8128 4822 8128 4837 8129 4783 8129 4784 8129 4796 8130 4791 8130 4822 8130 4821 8131 4840 8131 4782 8131 4840 8132 4784 8132 4782 8132 4822 8133 4791 8133 4825 8133 4776 8134 4821 8134 4774 8134 4791 8135 4792 8135 4825 8135 4821 8136 4782 8136 4781 8136 4841 8137 4842 8137 4830 8137 4841 8138 4830 8138 4833 8138 4834 8139 4841 8139 4833 8139 4843 8140 4841 8140 4834 8140 4844 8141 4834 8141 4835 8141 4844 8142 4843 8142 4834 8142 4845 8143 4835 8143 4836 8143 4845 8144 4844 8144 4835 8144 4837 8145 4845 8145 4836 8145 4846 8146 4845 8146 4837 8146 4847 8147 4837 8147 4838 8147 4847 8148 4846 8148 4837 8148 4848 8149 4838 8149 4839 8149 4848 8150 4847 8150 4838 8150 4849 8151 4839 8151 4840 8151 4849 8152 4848 8152 4839 8152 4830 8153 4842 8153 4850 8153 4830 8154 4850 8154 4829 8154 4851 8155 4852 8155 4823 8155 4851 8156 4823 8156 4822 8156 4825 8157 4851 8157 4822 8157 4853 8158 4851 8158 4825 8158 4824 8159 4853 8159 4825 8159 4854 8160 4853 8160 4824 8160 4827 8161 4854 8161 4824 8161 4855 8162 4854 8162 4827 8162 4850 8163 4827 8163 4829 8163 4850 8164 4855 8164 4827 8164 4856 8165 4857 8165 4831 8165 4856 8166 4831 8166 4828 8166 4826 8167 4856 8167 4828 8167 4858 8168 4856 8168 4826 8168 4823 8169 4858 8169 4826 8169 4852 8170 4858 8170 4823 8170 4857 8171 4859 8171 4832 8171 4857 8172 4832 8172 4831 8172 4860 8173 4821 8173 4832 8173 4860 8174 4832 8174 4859 8174 4821 8175 4849 8175 4840 8175 4860 8176 4849 8176 4821 8176 4853 8177 4852 8177 4851 8177 4854 8178 4852 8178 4853 8178 4860 8179 4859 8179 4857 8179 4855 8180 4858 8180 4852 8180 4855 8181 4852 8181 4854 8181 4849 8182 4857 8182 4856 8182 4849 8183 4856 8183 4858 8183 4849 8184 4860 8184 4857 8184 4849 8185 4858 8185 4855 8185 4850 8186 4849 8186 4855 8186 4848 8187 4850 8187 4842 8187 4848 8188 4849 8188 4850 8188 4847 8189 4848 8189 4842 8189 4841 8190 4847 8190 4842 8190 4846 8191 4847 8191 4841 8191 4843 8192 4846 8192 4841 8192 4845 8193 4846 8193 4843 8193 4844 8194 4845 8194 4843 8194 4861 8195 2496 8195 4862 8195 4862 8196 2496 8196 2566 8196 4862 8197 2566 8197 4863 8197 4863 8198 2566 8198 2568 8198 4864 8199 4863 8199 2569 8199 4863 8200 2568 8200 2569 8200 4864 8201 2569 8201 4865 8201 4865 8202 2569 8202 2575 8202 4866 8203 4865 8203 2621 8203 4865 8204 2575 8204 2621 8204 4867 8205 4866 8205 2638 8205 4866 8206 2621 8206 2638 8206 4868 8207 4867 8207 2636 8207 4867 8208 2638 8208 2636 8208 4869 8209 2492 8209 2471 8209 4870 8210 4869 8210 2471 8210 4871 8211 4870 8211 2461 8211 4870 8212 2471 8212 2461 8212 4871 8213 2461 8213 4872 8213 4872 8214 2461 8214 2455 8214 4873 8215 4872 8215 2458 8215 4872 8216 2455 8216 2458 8216 4873 8217 2458 8217 4874 8217 4874 8218 2458 8218 2462 8218 4875 8219 4874 8219 2476 8219 4874 8220 2462 8220 2476 8220 4861 8221 4875 8221 2496 8221 4875 8222 2476 8222 2496 8222 4876 8223 2640 8223 2639 8223 4877 8224 4876 8224 2639 8224 4877 8225 2639 8225 4878 8225 4878 8226 2639 8226 2597 8226 4878 8227 2597 8227 4879 8227 4879 8228 2597 8228 2549 8228 4879 8229 2549 8229 4880 8229 4880 8230 2549 8230 2539 8230 4881 8231 4880 8231 2527 8231 4880 8232 2539 8232 2527 8232 4882 8233 4881 8233 2504 8233 4881 8234 2527 8234 2504 8234 4882 8235 2504 8235 4869 8235 4869 8236 2504 8236 2492 8236 4883 8237 2635 8237 2653 8237 4884 8238 4883 8238 2653 8238 4885 8239 4884 8239 2677 8239 4884 8240 2653 8240 2677 8240 4886 8241 4885 8241 2678 8241 4885 8242 2677 8242 2678 8242 4887 8243 4886 8243 2688 8243 4886 8244 2678 8244 2688 8244 4887 8245 2688 8245 4888 8245 4888 8246 2688 8246 2696 8246 4889 8247 4888 8247 2683 8247 4888 8248 2696 8248 2683 8248 4889 8249 2683 8249 4890 8249 4890 8250 2683 8250 2682 8250 4876 8251 4890 8251 2640 8251 4890 8252 2682 8252 2640 8252 2636 8253 2635 8253 4883 8253 4868 8254 2636 8254 4883 8254 4865 8255 4891 8255 4864 8255 4865 8256 4892 8256 4891 8256 4878 8257 4879 8257 4893 8257 4878 8258 4893 8258 4894 8258 4866 8259 4892 8259 4865 8259 4866 8260 4895 8260 4892 8260 4896 8261 4872 8261 4873 8261 4866 8262 4897 8262 4895 8262 4896 8263 4898 8263 4872 8263 4899 8264 4871 8264 4872 8264 4899 8265 4872 8265 4898 8265 4900 8266 4873 8266 4874 8266 4900 8267 4896 8267 4873 8267 4901 8268 4874 8268 4875 8268 4877 8269 4878 8269 4894 8269 4877 8270 4894 8270 4902 8270 4901 8271 4900 8271 4874 8271 4903 8272 4870 8272 4871 8272 4903 8273 4871 8273 4899 8273 4867 8274 4904 8274 4897 8274 4867 8275 4897 8275 4866 8275 4905 8276 4875 8276 4861 8276 4905 8277 4901 8277 4875 8277 4906 8278 4905 8278 4861 8278 4907 8279 4882 8279 4869 8279 4907 8280 4869 8280 4870 8280 4907 8281 4870 8281 4903 8281 4876 8282 4902 8282 4908 8282 4876 8283 4877 8283 4902 8283 4909 8284 4881 8284 4882 8284 4909 8285 4882 8285 4907 8285 4910 8286 4861 8286 4862 8286 4868 8287 4904 8287 4867 8287 4868 8288 4911 8288 4904 8288 4910 8289 4906 8289 4861 8289 4883 8290 4911 8290 4868 8290 4883 8291 4912 8291 4911 8291 4913 8292 4881 8292 4909 8292 4890 8293 4876 8293 4908 8293 4914 8294 4862 8294 4863 8294 4914 8295 4910 8295 4862 8295 4890 8296 4908 8296 4915 8296 4880 8297 4881 8297 4913 8297 4884 8298 4912 8298 4883 8298 4916 8299 4914 8299 4863 8299 4889 8300 4915 8300 4917 8300 4889 8301 4890 8301 4915 8301 4888 8302 4889 8302 4917 8302 4888 8303 4917 8303 4918 8303 4919 8304 4880 8304 4913 8304 4885 8305 4920 8305 4912 8305 4864 8306 4916 8306 4863 8306 4885 8307 4912 8307 4884 8307 4887 8308 4918 8308 4921 8308 4891 8309 4916 8309 4864 8309 4887 8310 4888 8310 4918 8310 4886 8311 4921 8311 4920 8311 4886 8312 4887 8312 4921 8312 4886 8313 4920 8313 4885 8313 4879 8314 4880 8314 4919 8314 4893 8315 4879 8315 4919 8315 4922 8316 4923 8316 4911 8316 4922 8317 4911 8317 4912 8317 4924 8318 4912 8318 4920 8318 4924 8319 4922 8319 4912 8319 4921 8320 4924 8320 4920 8320 4925 8321 4924 8321 4921 8321 4926 8322 4921 8322 4918 8322 4926 8323 4925 8323 4921 8323 4927 8324 4918 8324 4917 8324 4927 8325 4926 8325 4918 8325 4915 8326 4927 8326 4917 8326 4928 8327 4927 8327 4915 8327 4908 8328 4928 8328 4915 8328 4929 8329 4928 8329 4908 8329 4911 8330 4923 8330 4930 8330 4911 8331 4930 8331 4904 8331 4931 8332 4932 8332 4906 8332 4931 8333 4906 8333 4910 8333 4933 8334 4910 8334 4914 8334 4933 8335 4931 8335 4910 8335 4934 8336 4914 8336 4916 8336 4934 8337 4933 8337 4914 8337 4935 8338 4916 8338 4891 8338 4935 8339 4934 8339 4916 8339 4936 8340 4891 8340 4892 8340 4936 8341 4935 8341 4891 8341 4895 8342 4936 8342 4892 8342 4937 8343 4936 8343 4895 8343 4897 8344 4937 8344 4895 8344 4938 8345 4937 8345 4897 8345 4904 8346 4938 8346 4897 8346 4930 8347 4938 8347 4904 8347 4903 8348 4939 8348 4907 8348 4940 8349 4939 8349 4903 8349 4941 8350 4903 8350 4899 8350 4941 8351 4940 8351 4903 8351 4898 8352 4941 8352 4899 8352 4942 8353 4941 8353 4898 8353 4943 8354 4898 8354 4896 8354 4943 8355 4942 8355 4898 8355 4900 8356 4943 8356 4896 8356 4944 8357 4943 8357 4900 8357 4945 8358 4900 8358 4901 8358 4945 8359 4944 8359 4900 8359 4946 8360 4901 8360 4905 8360 4946 8361 4945 8361 4901 8361 4906 8362 4946 8362 4905 8362 4932 8363 4946 8363 4906 8363 4947 8364 4929 8364 4908 8364 4947 8365 4908 8365 4902 8365 4948 8366 4902 8366 4894 8366 4948 8367 4947 8367 4902 8367 4893 8368 4948 8368 4894 8368 4949 8369 4948 8369 4893 8369 4919 8370 4949 8370 4893 8370 4950 8371 4949 8371 4919 8371 4913 8372 4950 8372 4919 8372 4951 8373 4950 8373 4913 8373 4952 8374 4913 8374 4909 8374 4952 8375 4951 8375 4913 8375 4907 8376 4952 8376 4909 8376 4939 8377 4952 8377 4907 8377 4945 8378 4942 8378 4943 8378 4945 8379 4943 8379 4944 8379 4946 8380 4941 8380 4942 8380 4946 8381 4942 8381 4945 8381 4934 8382 4931 8382 4933 8382 4935 8383 4931 8383 4934 8383 4936 8384 4932 8384 4931 8384 4936 8385 4931 8385 4935 8385 4937 8386 4940 8386 4941 8386 4937 8387 4946 8387 4932 8387 4937 8388 4941 8388 4946 8388 4937 8389 4932 8389 4936 8389 4947 8390 4948 8390 4949 8390 4947 8391 4949 8391 4950 8391 4947 8392 4950 8392 4951 8392 4938 8393 4939 8393 4940 8393 4938 8394 4940 8394 4937 8394 4930 8395 4939 8395 4938 8395 4923 8396 4952 8396 4939 8396 4923 8397 4939 8397 4930 8397 4929 8398 4947 8398 4951 8398 4922 8399 4951 8399 4952 8399 4922 8400 4952 8400 4923 8400 4924 8401 4929 8401 4951 8401 4924 8402 4951 8402 4922 8402 4926 8403 4927 8403 4928 8403 4925 8404 4928 8404 4929 8404 4925 8405 4929 8405 4924 8405 4925 8406 4926 8406 4928 8406 4953 8407 2716 8407 4954 8407 4954 8408 2716 8408 2713 8408 4954 8409 2713 8409 4955 8409 4955 8410 2713 8410 2712 8410 4955 8411 2712 8411 4956 8411 4956 8412 2712 8412 2714 8412 4956 8413 2714 8413 4957 8413 4957 8414 2714 8414 2720 8414 4958 8415 4957 8415 2721 8415 4957 8416 2720 8416 2721 8416 4959 8417 2346 8417 2730 8417 4960 8418 4959 8418 2730 8418 4960 8419 2730 8419 4961 8419 4961 8420 2730 8420 2729 8420 4953 8421 4961 8421 2716 8421 4961 8422 2729 8422 2716 8422 4962 8423 2604 8423 2346 8423 4959 8424 4962 8424 2346 8424 4963 8425 2565 8425 2604 8425 4962 8426 4963 8426 2604 8426 2565 8427 4963 8427 2574 8427 4963 8428 4964 8428 2574 8428 4965 8429 2634 8429 2586 8429 4966 8430 4965 8430 2586 8430 4967 8431 4966 8431 2585 8431 4966 8432 2586 8432 2585 8432 4968 8433 4967 8433 2582 8433 4967 8434 2585 8434 2582 8434 4968 8435 2582 8435 4969 8435 4969 8436 2582 8436 2578 8436 4970 8437 4969 8437 2579 8437 4969 8438 2578 8438 2579 8438 4970 8439 2579 8439 4964 8439 4964 8440 2579 8440 2574 8440 2634 8441 4965 8441 4971 8441 2634 8442 4971 8442 2652 8442 4972 8443 2687 8443 2694 8443 4973 8444 4972 8444 2694 8444 4974 8445 4973 8445 2690 8445 4973 8446 2694 8446 2690 8446 4975 8447 4974 8447 2689 8447 4974 8448 2690 8448 2689 8448 4976 8449 4975 8449 2676 8449 4975 8450 2689 8450 2676 8450 4971 8451 4976 8451 2652 8451 4976 8452 2676 8452 2652 8452 2687 8453 4972 8453 2391 8453 4972 8454 4977 8454 2391 8454 4978 8455 2392 8455 4977 8455 4977 8456 2392 8456 2391 8456 4979 8457 2393 8457 2392 8457 4978 8458 4979 8458 2392 8458 4980 8459 2675 8459 4981 8459 4981 8460 2675 8460 2674 8460 4981 8461 2674 8461 4979 8461 4979 8462 2674 8462 2393 8462 4982 8463 2385 8463 2384 8463 4983 8464 4982 8464 2384 8464 4984 8465 4983 8465 2409 8465 4983 8466 2384 8466 2409 8466 4985 8467 4984 8467 2412 8467 4984 8468 2409 8468 2412 8468 4985 8469 2412 8469 4986 8469 4986 8470 2412 8470 2413 8470 4986 8471 2413 8471 4987 8471 4987 8472 2413 8472 2426 8472 4988 8473 4987 8473 2427 8473 4987 8474 2426 8474 2427 8474 4980 8475 4988 8475 2675 8475 4988 8476 2427 8476 2675 8476 4989 8477 2706 8477 2705 8477 4990 8478 4989 8478 2705 8478 4990 8479 2705 8479 4991 8479 4991 8480 2705 8480 2725 8480 4992 8481 4991 8481 2343 8481 4991 8482 2725 8482 2343 8482 4993 8483 4992 8483 2355 8483 4992 8484 2343 8484 2355 8484 4993 8485 2355 8485 4994 8485 4994 8486 2355 8486 2356 8486 4982 8487 4994 8487 2385 8487 4994 8488 2356 8488 2385 8488 2707 8489 2706 8489 4989 8489 4995 8490 2707 8490 4989 8490 4996 8491 2724 8491 4997 8491 4997 8492 2724 8492 2731 8492 4998 8493 4997 8493 2341 8493 4997 8494 2731 8494 2341 8494 4998 8495 2341 8495 4999 8495 4999 8496 2341 8496 2340 8496 4999 8497 2340 8497 5000 8497 5000 8498 2340 8498 2727 8498 5001 8499 5000 8499 2708 8499 5000 8500 2727 8500 2708 8500 5001 8501 2708 8501 4995 8501 4995 8502 2708 8502 2707 8502 2721 8503 2724 8503 4996 8503 4958 8504 2721 8504 4996 8504 4980 8505 4981 8505 5002 8505 5000 8506 5003 8506 5004 8506 4988 8507 4980 8507 5005 8507 4999 8508 5006 8508 4998 8508 4999 8509 5000 8509 5004 8509 4999 8510 5004 8510 5006 8510 4977 8511 4972 8511 4973 8511 4977 8512 4973 8512 4974 8512 4984 8513 5007 8513 4983 8513 4970 8514 4964 8514 4963 8514 4987 8515 5005 8515 5008 8515 4987 8516 4988 8516 5005 8516 4969 8517 4970 8517 4963 8517 4985 8518 5008 8518 5007 8518 4990 8519 5009 8519 4989 8519 4985 8520 5007 8520 4984 8520 4968 8521 4969 8521 4963 8521 5010 8522 5009 8522 4990 8522 4986 8523 4987 8523 5008 8523 4986 8524 5008 8524 4985 8524 4962 8525 4968 8525 4963 8525 5011 8526 4976 8526 4971 8526 4962 8527 4966 8527 4967 8527 4962 8528 4967 8528 4968 8528 5011 8529 4971 8529 5012 8529 5012 8530 4971 8530 5013 8530 4991 8531 5010 8531 4990 8531 4956 8532 5014 8532 4955 8532 4991 8533 5015 8533 5010 8533 5016 8534 5017 8534 4962 8534 4956 8535 5018 8535 5014 8535 5016 8536 4962 8536 4959 8536 5019 8537 4966 8537 4962 8537 5019 8538 4962 8538 5017 8538 5020 8539 5012 8539 5013 8539 4978 8540 4977 8540 4974 8540 5021 8541 5016 8541 4959 8541 4978 8542 4976 8542 5011 8542 5020 8543 5013 8543 5022 8543 4978 8544 4974 8544 4975 8544 4978 8545 4975 8545 4976 8545 5023 8546 4966 8546 5019 8546 4957 8547 5018 8547 4956 8547 4957 8548 5024 8548 5018 8548 5025 8549 5021 8549 4959 8549 5026 8550 4966 8550 5023 8550 5027 8551 5020 8551 5022 8551 5028 8552 5025 8552 4959 8552 5027 8553 5022 8553 5029 8553 5028 8554 4959 8554 4960 8554 4958 8555 5024 8555 4957 8555 5030 8556 5028 8556 4960 8556 4992 8557 5015 8557 4991 8557 4965 8558 4966 8558 5026 8558 4996 8559 5031 8559 5032 8559 4996 8560 5024 8560 4958 8560 4996 8561 5032 8561 5024 8561 5033 8562 5030 8562 4960 8562 5034 8563 5033 8563 4960 8563 5034 8564 4960 8564 4961 8564 5035 8565 5027 8565 5029 8565 5036 8566 5034 8566 4961 8566 5036 8567 4961 8567 4953 8567 4995 8568 5035 8568 5029 8568 4995 8569 5037 8569 5038 8569 4995 8570 5029 8570 5037 8570 4993 8571 5039 8571 5015 8571 5040 8572 5036 8572 4953 8572 4989 8573 5035 8573 4995 8573 5041 8574 5035 8574 4989 8574 4993 8575 5015 8575 4992 8575 4979 8576 4978 8576 5011 8576 4954 8577 5040 8577 4953 8577 4979 8578 5011 8578 5042 8578 4997 8579 5031 8579 4996 8579 5013 8580 4965 8580 5026 8580 4997 8581 5006 8581 5031 8581 5013 8582 4971 8582 4965 8582 5001 8583 4995 8583 5038 8583 4994 8584 5043 8584 5044 8584 4994 8585 5039 8585 4993 8585 4994 8586 5044 8586 5039 8586 5001 8587 5038 8587 5003 8587 4998 8588 5006 8588 4997 8588 4982 8589 5043 8589 4994 8589 4982 8590 5045 8590 5043 8590 5009 8591 5041 8591 4989 8591 4981 8592 4979 8592 5042 8592 4981 8593 5046 8593 5002 8593 4981 8594 5042 8594 5046 8594 4983 8595 5045 8595 4982 8595 4983 8596 5007 8596 5045 8596 4955 8597 5040 8597 4954 8597 4955 8598 5014 8598 5040 8598 4980 8599 5047 8599 5005 8599 4980 8600 5002 8600 5047 8600 5000 8601 5001 8601 5003 8601 5048 8602 5049 8602 5031 8602 5048 8603 5031 8603 5006 8603 5050 8604 5006 8604 5004 8604 5050 8605 5048 8605 5006 8605 5051 8606 5004 8606 5003 8606 5051 8607 5050 8607 5004 8607 5052 8608 5003 8608 5038 8608 5052 8609 5051 8609 5003 8609 5053 8610 5038 8610 5037 8610 5053 8611 5052 8611 5038 8611 5029 8612 5053 8612 5037 8612 5054 8613 5053 8613 5029 8613 5031 8614 5049 8614 5055 8614 5031 8615 5055 8615 5032 8615 5056 8616 5057 8616 5034 8616 5056 8617 5034 8617 5036 8617 5040 8618 5056 8618 5036 8618 5058 8619 5056 8619 5040 8619 5059 8620 5040 8620 5014 8620 5059 8621 5058 8621 5040 8621 5060 8622 5014 8622 5018 8622 5060 8623 5059 8623 5014 8623 5024 8624 5060 8624 5018 8624 5061 8625 5060 8625 5024 8625 5055 8626 5024 8626 5032 8626 5055 8627 5061 8627 5024 8627 5062 8628 5063 8628 5028 8628 5062 8629 5028 8629 5030 8629 5033 8630 5062 8630 5030 8630 5064 8631 5062 8631 5033 8631 5057 8632 5033 8632 5034 8632 5057 8633 5064 8633 5033 8633 5028 8634 5065 8634 5025 8634 5063 8635 5065 8635 5028 8635 5066 8636 5067 8636 5026 8636 5066 8637 5026 8637 5023 8637 5068 8638 5023 8638 5019 8638 5068 8639 5066 8639 5023 8639 5069 8640 5019 8640 5017 8640 5069 8641 5068 8641 5019 8641 5070 8642 5017 8642 5016 8642 5070 8643 5069 8643 5017 8643 5071 8644 5016 8644 5021 8644 5071 8645 5070 8645 5016 8645 5065 8646 5021 8646 5025 8646 5065 8647 5071 8647 5021 8647 5072 8648 5013 8648 5026 8648 5072 8649 5026 8649 5067 8649 5072 8650 5073 8650 5022 8650 5072 8651 5022 8651 5013 8651 5073 8652 5054 8652 5029 8652 5073 8653 5029 8653 5022 8653 5074 8654 5075 8654 5043 8654 5074 8655 5043 8655 5045 8655 5076 8656 5045 8656 5007 8656 5076 8657 5074 8657 5045 8657 5077 8658 5007 8658 5008 8658 5077 8659 5076 8659 5007 8659 5005 8660 5077 8660 5008 8660 5078 8661 5077 8661 5005 8661 5079 8662 5005 8662 5047 8662 5079 8663 5078 8663 5005 8663 5002 8664 5079 8664 5047 8664 5080 8665 5079 8665 5002 8665 5081 8666 5002 8666 5046 8666 5081 8667 5080 8667 5002 8667 5082 8668 5046 8668 5042 8668 5082 8669 5081 8669 5046 8669 5043 8670 5075 8670 5083 8670 5043 8671 5083 8671 5044 8671 5084 8672 5085 8672 5035 8672 5084 8673 5035 8673 5041 8673 5009 8674 5084 8674 5041 8674 5086 8675 5084 8675 5009 8675 5010 8676 5086 8676 5009 8676 5087 8677 5086 8677 5010 8677 5088 8678 5010 8678 5015 8678 5088 8679 5087 8679 5010 8679 5089 8680 5015 8680 5039 8680 5089 8681 5088 8681 5015 8681 5083 8682 5039 8682 5044 8682 5083 8683 5089 8683 5039 8683 5090 8684 5091 8684 5020 8684 5090 8685 5020 8685 5027 8685 5085 8686 5027 8686 5035 8686 5085 8687 5090 8687 5027 8687 5091 8688 5092 8688 5012 8688 5091 8689 5012 8689 5020 8689 5011 8690 5012 8690 5092 8690 5093 8691 5011 8691 5092 8691 5093 8692 5082 8692 5042 8692 5093 8693 5042 8693 5011 8693 5068 8694 5069 8694 5070 8694 5066 8695 5070 8695 5071 8695 5066 8696 5068 8696 5070 8696 5065 8697 5066 8697 5071 8697 5067 8698 5066 8698 5065 8698 5063 8699 5067 8699 5065 8699 5073 8700 5072 8700 5067 8700 5073 8701 5063 8701 5062 8701 5073 8702 5067 8702 5063 8702 5060 8703 5058 8703 5059 8703 5061 8704 5056 8704 5058 8704 5061 8705 5058 8705 5060 8705 5055 8706 5056 8706 5061 8706 5054 8707 5062 8707 5064 8707 5054 8708 5064 8708 5057 8708 5054 8709 5073 8709 5062 8709 5053 8710 5057 8710 5056 8710 5053 8711 5054 8711 5057 8711 5052 8712 5055 8712 5049 8712 5052 8713 5056 8713 5055 8713 5052 8714 5053 8714 5056 8714 5051 8715 5049 8715 5048 8715 5051 8716 5048 8716 5050 8716 5051 8717 5052 8717 5049 8717 5093 8718 5092 8718 5091 8718 5088 8719 5086 8719 5087 8719 5089 8720 5084 8720 5086 8720 5089 8721 5086 8721 5088 8721 5082 8722 5091 8722 5090 8722 5082 8723 5093 8723 5091 8723 5083 8724 5085 8724 5084 8724 5083 8725 5084 8725 5089 8725 5081 8726 5083 8726 5075 8726 5081 8727 5090 8727 5085 8727 5081 8728 5082 8728 5090 8728 5081 8729 5085 8729 5083 8729 5080 8730 5075 8730 5074 8730 5080 8731 5081 8731 5075 8731 5079 8732 5080 8732 5074 8732 5076 8733 5079 8733 5074 8733 5078 8734 5079 8734 5076 8734 5077 8735 5078 8735 5076 8735 5094 8736 2344 8736 2431 8736 5095 8737 5094 8737 2431 8737 5095 8738 2431 8738 5096 8738 5096 8739 2431 8739 2434 8739 5097 8740 5096 8740 2436 8740 5096 8741 2434 8741 2436 8741 5097 8742 2436 8742 5098 8742 5098 8743 2436 8743 2438 8743 5099 8744 5098 8744 2453 8744 5098 8745 2438 8745 2453 8745 5099 8746 2453 8746 5100 8746 5100 8747 2453 8747 2508 8747 5100 8748 2508 8748 5101 8748 5101 8749 2508 8749 2509 8749 5102 8750 2339 8750 5103 8750 5103 8751 2339 8751 2342 8751 5103 8752 2342 8752 5104 8752 5104 8753 2342 8753 2719 8753 5104 8754 2719 8754 5105 8754 5105 8755 2719 8755 2711 8755 5106 8756 5105 8756 2715 8756 5105 8757 2711 8757 2715 8757 5106 8758 2715 8758 5107 8758 5107 8759 2715 8759 2728 8759 5108 8760 5107 8760 2345 8760 5107 8761 2728 8761 2345 8761 5108 8762 2345 8762 5094 8762 5094 8763 2345 8763 2344 8763 5109 8764 2659 8764 2658 8764 5110 8765 5109 8765 2658 8765 5110 8766 2658 8766 5111 8766 5111 8767 2658 8767 2420 8767 5112 8768 5111 8768 2410 8768 5111 8769 2420 8769 2410 8769 5113 8770 5112 8770 2408 8770 5112 8771 2410 8771 2408 8771 5114 8772 5113 8772 2381 8772 5113 8773 2408 8773 2381 8773 5114 8774 2381 8774 5115 8774 5115 8775 2381 8775 2354 8775 5102 8776 5115 8776 2339 8776 5115 8777 2354 8777 2339 8777 5116 8778 2511 8778 2510 8778 5117 8779 5116 8779 2510 8779 5117 8780 2510 8780 5118 8780 5118 8781 2510 8781 2515 8781 5118 8782 2515 8782 5119 8782 5119 8783 2515 8783 2516 8783 5119 8784 2516 8784 5120 8784 5120 8785 2516 8785 2571 8785 5120 8786 2571 8786 5121 8786 5121 8787 2571 8787 2572 8787 5121 8788 2572 8788 5122 8788 5122 8789 2572 8789 2661 8789 5123 8790 5122 8790 2660 8790 5122 8791 2661 8791 2660 8791 5123 8792 2660 8792 5109 8792 5109 8793 2660 8793 2659 8793 2509 8794 2511 8794 5116 8794 5101 8795 2509 8795 5116 8795 5098 8796 5124 8796 5097 8796 5098 8797 5125 8797 5124 8797 5111 8798 5112 8798 5126 8798 5111 8799 5126 8799 5127 8799 5099 8800 5125 8800 5098 8800 5099 8801 5128 8801 5125 8801 5129 8802 5105 8802 5106 8802 5099 8803 5130 8803 5128 8803 5129 8804 5131 8804 5105 8804 5132 8805 5104 8805 5105 8805 5132 8806 5105 8806 5131 8806 5133 8807 5106 8807 5107 8807 5133 8808 5129 8808 5106 8808 5134 8809 5107 8809 5108 8809 5110 8810 5111 8810 5127 8810 5110 8811 5127 8811 5135 8811 5134 8812 5133 8812 5107 8812 5136 8813 5103 8813 5104 8813 5136 8814 5104 8814 5132 8814 5100 8815 5137 8815 5130 8815 5100 8816 5130 8816 5099 8816 5138 8817 5108 8817 5094 8817 5138 8818 5134 8818 5108 8818 5139 8819 5138 8819 5094 8819 5140 8820 5115 8820 5102 8820 5140 8821 5102 8821 5103 8821 5140 8822 5103 8822 5136 8822 5109 8823 5135 8823 5141 8823 5109 8824 5110 8824 5135 8824 5142 8825 5114 8825 5115 8825 5142 8826 5115 8826 5140 8826 5143 8827 5094 8827 5095 8827 5101 8828 5137 8828 5100 8828 5101 8829 5144 8829 5137 8829 5143 8830 5139 8830 5094 8830 5116 8831 5144 8831 5101 8831 5116 8832 5145 8832 5144 8832 5146 8833 5114 8833 5142 8833 5123 8834 5109 8834 5141 8834 5147 8835 5095 8835 5096 8835 5147 8836 5143 8836 5095 8836 5123 8837 5141 8837 5148 8837 5113 8838 5114 8838 5146 8838 5117 8839 5145 8839 5116 8839 5149 8840 5147 8840 5096 8840 5122 8841 5148 8841 5150 8841 5122 8842 5123 8842 5148 8842 5121 8843 5122 8843 5150 8843 5121 8844 5150 8844 5151 8844 5152 8845 5113 8845 5146 8845 5118 8846 5153 8846 5145 8846 5097 8847 5149 8847 5096 8847 5118 8848 5145 8848 5117 8848 5120 8849 5151 8849 5154 8849 5124 8850 5149 8850 5097 8850 5120 8851 5121 8851 5151 8851 5119 8852 5154 8852 5153 8852 5119 8853 5120 8853 5154 8853 5119 8854 5153 8854 5118 8854 5112 8855 5113 8855 5152 8855 5126 8856 5112 8856 5152 8856 5155 8857 5156 8857 5144 8857 5155 8858 5144 8858 5145 8858 5153 8859 5155 8859 5145 8859 5157 8860 5155 8860 5153 8860 5154 8861 5157 8861 5153 8861 5158 8862 5157 8862 5154 8862 5159 8863 5154 8863 5151 8863 5159 8864 5158 8864 5154 8864 5160 8865 5151 8865 5150 8865 5160 8866 5159 8866 5151 8866 5148 8867 5160 8867 5150 8867 5161 8868 5160 8868 5148 8868 5162 8869 5148 8869 5141 8869 5162 8870 5161 8870 5148 8870 5144 8871 5156 8871 5163 8871 5144 8872 5163 8872 5137 8872 5164 8873 5165 8873 5139 8873 5164 8874 5139 8874 5143 8874 5166 8875 5143 8875 5147 8875 5166 8876 5164 8876 5143 8876 5167 8877 5147 8877 5149 8877 5167 8878 5166 8878 5147 8878 5168 8879 5149 8879 5124 8879 5168 8880 5167 8880 5149 8880 5125 8881 5168 8881 5124 8881 5169 8882 5168 8882 5125 8882 5170 8883 5125 8883 5128 8883 5170 8884 5169 8884 5125 8884 5171 8885 5128 8885 5130 8885 5171 8886 5170 8886 5128 8886 5137 8887 5171 8887 5130 8887 5163 8888 5171 8888 5137 8888 5172 8889 5173 8889 5140 8889 5172 8890 5140 8890 5136 8890 5174 8891 5136 8891 5132 8891 5174 8892 5172 8892 5136 8892 5131 8893 5174 8893 5132 8893 5175 8894 5174 8894 5131 8894 5129 8895 5175 8895 5131 8895 5176 8896 5175 8896 5129 8896 5177 8897 5129 8897 5133 8897 5177 8898 5176 8898 5129 8898 5134 8899 5177 8899 5133 8899 5178 8900 5177 8900 5134 8900 5138 8901 5178 8901 5134 8901 5179 8902 5178 8902 5138 8902 5139 8903 5179 8903 5138 8903 5165 8904 5179 8904 5139 8904 5180 8905 5162 8905 5141 8905 5180 8906 5141 8906 5135 8906 5181 8907 5135 8907 5127 8907 5181 8908 5180 8908 5135 8908 5182 8909 5127 8909 5126 8909 5182 8910 5181 8910 5127 8910 5183 8911 5126 8911 5152 8911 5183 8912 5182 8912 5126 8912 5184 8913 5152 8913 5146 8913 5184 8914 5183 8914 5152 8914 5185 8915 5146 8915 5142 8915 5185 8916 5184 8916 5146 8916 5140 8917 5185 8917 5142 8917 5173 8918 5185 8918 5140 8918 5178 8919 5175 8919 5176 8919 5178 8920 5176 8920 5177 8920 5179 8921 5174 8921 5175 8921 5179 8922 5175 8922 5178 8922 5167 8923 5164 8923 5166 8923 5168 8924 5164 8924 5167 8924 5169 8925 5165 8925 5164 8925 5169 8926 5164 8926 5168 8926 5170 8927 5172 8927 5174 8927 5170 8928 5179 8928 5165 8928 5170 8929 5174 8929 5179 8929 5170 8930 5165 8930 5169 8930 5180 8931 5181 8931 5182 8931 5180 8932 5182 8932 5183 8932 5180 8933 5183 8933 5184 8933 5171 8934 5173 8934 5172 8934 5171 8935 5172 8935 5170 8935 5163 8936 5173 8936 5171 8936 5156 8937 5185 8937 5173 8937 5156 8938 5173 8938 5163 8938 5162 8939 5180 8939 5184 8939 5155 8940 5184 8940 5185 8940 5155 8941 5185 8941 5156 8941 5157 8942 5162 8942 5184 8942 5157 8943 5184 8943 5155 8943 5159 8944 5160 8944 5161 8944 5158 8945 5161 8945 5162 8945 5158 8946 5162 8946 5157 8946 5158 8947 5159 8947 5161 8947 5186 8948 2517 8948 2534 8948 5187 8949 5186 8949 2534 8949 5188 8950 5187 8950 2533 8950 5187 8951 2534 8951 2533 8951 5189 8952 5188 8952 2555 8952 5188 8953 2533 8953 2555 8953 5190 8954 5189 8954 2562 8954 5189 8955 2555 8955 2562 8955 2514 8956 2517 8956 5186 8956 5191 8957 2514 8957 5186 8957 2514 8958 5191 8958 5192 8958 2514 8959 5192 8959 2563 8959 2563 8960 5192 8960 2352 8960 5192 8961 5193 8961 2352 8961 2646 8962 2352 8962 5193 8962 5194 8963 2646 8963 5193 8963 2642 8964 2646 8964 5194 8964 5195 8965 2642 8965 5194 8965 5196 8966 2630 8966 2643 8966 5197 8967 5196 8967 2643 8967 5198 8968 5197 8968 2644 8968 5197 8969 2643 8969 2644 8969 5198 8970 2644 8970 5199 8970 5199 8971 2644 8971 2645 8971 5195 8972 5199 8972 2642 8972 5199 8973 2645 8973 2642 8973 5200 8974 2631 8974 2630 8974 5200 8975 2630 8975 5196 8975 2626 8976 2631 8976 5200 8976 5201 8977 2626 8977 5200 8977 5202 8978 2481 8978 2483 8978 5203 8979 5202 8979 2483 8979 5204 8980 5203 8980 2482 8980 5203 8981 2483 8981 2482 8981 5205 8982 5204 8982 2484 8982 5204 8983 2482 8983 2484 8983 5206 8984 5205 8984 2485 8984 5205 8985 2484 8985 2485 8985 5207 8986 5206 8986 2486 8986 5206 8987 2485 8987 2486 8987 5208 8988 5207 8988 2487 8988 5207 8989 2486 8989 2487 8989 5209 8990 5208 8990 2498 8990 5208 8991 2487 8991 2498 8991 5201 8992 5209 8992 2626 8992 5209 8993 2498 8993 2626 8993 2538 8994 2481 8994 5202 8994 5210 8995 2538 8995 5202 8995 2430 8996 2538 8996 5210 8996 5211 8997 2430 8997 5210 8997 2430 8998 5211 8998 2439 8998 5211 8999 5212 8999 2439 8999 5213 9000 2507 9000 5214 9000 5214 9001 2507 9001 2452 9001 5214 9002 2452 9002 5215 9002 5215 9003 2452 9003 2447 9003 5216 9004 5215 9004 2444 9004 5215 9005 2447 9005 2444 9005 5216 9006 2444 9006 5217 9006 5217 9007 2444 9007 2445 9007 5212 9008 5217 9008 2439 9008 5217 9009 2445 9009 2439 9009 2507 9010 5213 9010 2602 9010 5213 9011 5218 9011 2602 9011 2562 9012 2602 9012 5218 9012 5190 9013 2562 9013 5218 9013 5210 9014 5202 9014 5203 9014 5210 9015 5203 9015 5204 9015 5210 9016 5204 9016 5205 9016 5210 9017 5205 9017 5206 9017 5210 9018 5206 9018 5207 9018 5210 9019 5207 9019 5211 9019 5217 9020 5211 9020 5216 9020 5211 9021 5217 9021 5212 9021 5207 9022 5208 9022 5215 9022 5211 9023 5207 9023 5215 9023 5216 9024 5211 9024 5215 9024 5208 9025 5209 9025 5214 9025 5215 9026 5208 9026 5214 9026 5195 9027 5194 9027 5199 9027 5209 9028 5201 9028 5213 9028 5214 9029 5209 9029 5213 9029 5196 9030 5197 9030 5193 9030 5197 9031 5198 9031 5193 9031 5198 9032 5199 9032 5193 9032 5199 9033 5194 9033 5193 9033 5196 9034 5193 9034 5200 9034 5201 9035 5200 9035 5218 9035 5213 9036 5201 9036 5218 9036 5200 9037 5193 9037 5218 9037 5186 9038 5187 9038 5191 9038 5187 9039 5188 9039 5192 9039 5188 9040 5189 9040 5192 9040 5189 9041 5190 9041 5192 9041 5190 9042 5218 9042 5192 9042 5218 9043 5193 9043 5192 9043 5191 9044 5187 9044 5192 9044 5219 9045 2595 9045 2594 9045 5220 9046 5219 9046 2594 9046 5221 9047 5220 9047 2593 9047 5220 9048 2594 9048 2593 9048 5221 9049 2593 9049 5222 9049 5222 9050 2593 9050 2619 9050 5222 9051 2619 9051 5223 9051 5223 9052 2619 9052 2655 9052 2603 9053 2595 9053 5219 9053 5224 9054 2603 9054 5219 9054 2537 9055 2603 9055 5224 9055 5225 9056 2537 9056 5224 9056 2537 9057 5225 9057 2542 9057 5225 9058 5226 9058 2542 9058 5227 9059 2625 9059 2551 9059 5228 9060 5227 9060 2551 9060 5229 9061 5228 9061 2546 9061 5228 9062 2551 9062 2546 9062 5230 9063 5229 9063 2547 9063 5229 9064 2546 9064 2547 9064 5226 9065 5230 9065 2542 9065 5230 9066 2547 9066 2542 9066 2625 9067 5227 9067 2627 9067 5227 9068 5231 9068 2627 9068 5232 9069 2685 9069 2686 9069 5233 9070 5232 9070 2686 9070 5234 9071 5233 9071 2684 9071 5233 9072 2686 9072 2684 9072 5234 9073 2684 9073 5235 9073 5235 9074 2684 9074 2679 9074 5231 9075 5235 9075 2627 9075 5235 9076 2679 9076 2627 9076 2685 9077 5232 9077 2353 9077 5232 9078 5236 9078 2353 9078 2353 9079 5236 9079 2383 9079 5236 9080 5237 9080 2383 9080 2348 9081 2383 9081 5237 9081 5238 9082 2348 9082 5237 9082 5239 9083 2673 9083 5240 9083 5240 9084 2673 9084 2349 9084 5241 9085 5240 9085 2732 9085 5240 9086 2349 9086 2732 9086 5241 9087 2732 9087 5242 9087 5242 9088 2732 9088 2733 9088 5238 9089 5242 9089 2348 9089 5242 9090 2733 9090 2348 9090 5223 9091 2655 9091 2673 9091 5223 9092 2673 9092 5239 9092 5224 9093 5219 9093 5220 9093 5224 9094 5220 9094 5221 9094 5224 9095 5221 9095 5225 9095 5225 9096 5230 9096 5226 9096 5225 9097 5221 9097 5229 9097 5230 9098 5225 9098 5229 9098 5221 9099 5222 9099 5228 9099 5229 9100 5221 9100 5228 9100 5222 9101 5223 9101 5227 9101 5228 9102 5222 9102 5227 9102 5223 9103 5239 9103 5231 9103 5227 9104 5223 9104 5231 9104 5241 9105 5242 9105 5237 9105 5242 9106 5238 9106 5237 9106 5239 9107 5240 9107 5235 9107 5231 9108 5239 9108 5235 9108 5240 9109 5241 9109 5234 9109 5235 9110 5240 9110 5234 9110 5241 9111 5237 9111 5234 9111 5232 9112 5233 9112 5236 9112 5233 9113 5234 9113 5236 9113 5234 9114 5237 9114 5236 9114 5243 9115 2402 9115 2406 9115 5244 9116 5243 9116 2406 9116 5245 9117 5244 9117 2425 9117 5244 9118 2406 9118 2425 9118 5245 9119 2425 9119 5246 9119 5246 9120 2425 9120 2440 9120 5247 9121 2360 9121 2359 9121 5248 9122 5247 9122 2359 9122 5249 9123 5248 9123 2397 9123 5248 9124 2359 9124 2397 9124 5243 9125 5249 9125 2402 9125 5249 9126 2397 9126 2402 9126 2361 9127 2360 9127 5247 9127 5250 9128 2361 9128 5247 9128 5251 9129 2362 9129 2361 9129 5250 9130 5251 9130 2361 9130 5252 9131 2398 9131 2362 9131 5251 9132 5252 9132 2362 9132 5253 9133 2403 9133 5252 9133 5252 9134 2403 9134 2398 9134 5253 9135 5254 9135 2403 9135 5254 9136 2407 9136 2403 9136 5255 9137 2441 9137 2407 9137 5254 9138 5255 9138 2407 9138 5256 9139 2601 9139 2600 9139 5257 9140 5256 9140 2600 9140 5258 9141 5257 9141 2599 9141 5257 9142 2600 9142 2599 9142 5259 9143 5258 9143 2606 9143 5258 9144 2599 9144 2606 9144 5260 9145 5259 9145 2442 9145 5259 9146 2606 9146 2442 9146 5255 9147 5260 9147 2441 9147 5260 9148 2442 9148 2441 9148 5261 9149 2697 9149 2601 9149 5256 9150 5261 9150 2601 9150 5262 9151 2698 9151 5261 9151 5261 9152 2698 9152 2697 9152 5263 9153 2699 9153 2698 9153 5262 9154 5263 9154 2698 9154 5264 9155 2702 9155 2699 9155 5263 9156 5264 9156 2699 9156 5265 9157 2671 9157 2654 9157 5266 9158 5265 9158 2654 9158 5267 9159 5266 9159 2641 9159 5266 9160 2654 9160 2641 9160 5268 9161 5267 9161 2633 9161 5267 9162 2641 9162 2633 9162 5269 9163 5268 9163 2632 9163 5268 9164 2633 9164 2632 9164 5269 9165 2632 9165 5270 9165 5270 9166 2632 9166 2637 9166 5271 9167 5270 9167 2647 9167 5270 9168 2637 9168 2647 9168 5272 9169 5271 9169 2665 9169 5271 9170 2647 9170 2665 9170 5264 9171 5272 9171 2702 9171 5272 9172 2665 9172 2702 9172 5273 9173 2460 9173 2459 9173 5274 9174 5273 9174 2459 9174 5275 9175 5274 9175 2405 9175 5274 9176 2459 9176 2405 9176 5276 9177 5275 9177 2382 9177 5275 9178 2405 9178 2382 9178 5276 9179 2382 9179 5277 9179 5277 9180 2382 9180 2347 9180 5278 9181 5277 9181 2350 9181 5277 9182 2347 9182 2350 9182 5278 9183 2350 9183 5279 9183 5279 9184 2350 9184 2681 9184 5280 9185 5279 9185 2680 9185 5279 9186 2681 9186 2680 9186 5280 9187 2680 9187 5265 9187 5265 9188 2680 9188 2671 9188 5281 9189 2500 9189 5282 9189 5282 9190 2500 9190 2513 9190 5283 9191 5282 9191 2502 9191 5282 9192 2513 9192 2502 9192 5283 9193 2502 9193 5284 9193 5284 9194 2502 9194 2491 9194 5285 9195 5284 9195 2490 9195 5284 9196 2491 9196 2490 9196 5286 9197 5285 9197 2478 9197 5285 9198 2490 9198 2478 9198 5286 9199 2478 9199 5287 9199 5287 9200 2478 9200 2477 9200 5287 9201 2477 9201 5288 9201 5288 9202 2477 9202 2479 9202 5273 9203 5288 9203 2460 9203 5288 9204 2479 9204 2460 9204 2440 9205 2500 9205 5281 9205 5246 9206 2440 9206 5281 9206 5289 9207 5290 9207 5262 9207 5250 9208 5262 9208 5261 9208 5247 9209 5289 9209 5262 9209 5247 9210 5262 9210 5250 9210 5277 9211 5278 9211 5291 9211 5251 9212 5261 9212 5256 9212 5273 9213 5292 9213 5293 9213 5273 9214 5274 9214 5292 9214 5251 9215 5250 9215 5261 9215 5246 9216 5294 9216 5295 9216 5246 9217 5295 9217 5296 9217 5297 9218 5289 9218 5247 9218 5246 9219 5296 9219 5245 9219 5281 9220 5298 9220 5294 9220 5299 9221 5277 9221 5291 9221 5281 9222 5294 9222 5246 9222 5248 9223 5297 9223 5247 9223 5288 9224 5273 9224 5293 9224 5300 9225 5268 9225 5269 9225 5252 9226 5256 9226 5255 9226 5282 9227 5298 9227 5281 9227 5252 9228 5251 9228 5256 9228 5301 9229 5297 9229 5248 9229 5287 9230 5288 9230 5293 9230 5302 9231 5269 9231 5270 9231 5287 9232 5293 9232 5303 9232 5302 9233 5300 9233 5269 9233 5283 9234 5298 9234 5282 9234 5283 9235 5304 9235 5298 9235 5276 9236 5277 9236 5299 9236 5305 9237 5267 9237 5268 9237 5305 9238 5268 9238 5300 9238 5286 9239 5287 9239 5303 9239 5254 9240 5253 9240 5252 9240 5286 9241 5303 9241 5306 9241 5284 9242 5304 9242 5283 9242 5254 9243 5252 9243 5255 9243 5307 9244 5270 9244 5271 9244 5284 9245 5308 9245 5304 9245 5309 9246 5276 9246 5299 9246 5307 9247 5302 9247 5270 9247 5285 9248 5286 9248 5306 9248 5285 9249 5308 9249 5284 9249 5249 9250 5301 9250 5248 9250 5285 9251 5306 9251 5308 9251 5310 9252 5266 9252 5267 9252 5310 9253 5267 9253 5305 9253 5311 9254 5301 9254 5249 9254 5312 9255 5307 9255 5271 9255 5312 9256 5271 9256 5272 9256 5243 9257 5311 9257 5249 9257 5313 9258 5312 9258 5272 9258 5313 9259 5272 9259 5264 9259 5313 9260 5264 9260 5263 9260 5314 9261 5311 9261 5243 9261 5315 9262 5280 9262 5265 9262 5315 9263 5265 9263 5266 9263 5315 9264 5266 9264 5310 9264 5275 9265 5309 9265 5316 9265 5275 9266 5276 9266 5309 9266 5290 9267 5313 9267 5263 9267 5290 9268 5263 9268 5262 9268 5244 9269 5314 9269 5243 9269 5317 9270 5278 9270 5279 9270 5317 9271 5279 9271 5280 9271 5317 9272 5280 9272 5315 9272 5274 9273 5318 9273 5292 9273 5259 9274 5257 9274 5258 9274 5274 9275 5316 9275 5318 9275 5274 9276 5275 9276 5316 9276 5245 9277 5296 9277 5314 9277 5260 9278 5257 9278 5259 9278 5245 9279 5314 9279 5244 9279 5255 9280 5256 9280 5257 9280 5255 9281 5257 9281 5260 9281 5291 9282 5278 9282 5317 9282 5298 9283 5319 9283 5294 9283 5320 9284 5319 9284 5298 9284 5304 9285 5320 9285 5298 9285 5321 9286 5320 9286 5304 9286 5322 9287 5304 9287 5308 9287 5322 9288 5321 9288 5304 9288 5306 9289 5322 9289 5308 9289 5323 9290 5322 9290 5306 9290 5324 9291 5306 9291 5303 9291 5324 9292 5323 9292 5306 9292 5325 9293 5303 9293 5293 9293 5325 9294 5324 9294 5303 9294 5292 9295 5325 9295 5293 9295 5326 9296 5325 9296 5292 9296 5294 9297 5319 9297 5327 9297 5294 9298 5327 9298 5295 9298 5328 9299 5329 9299 5313 9299 5328 9300 5313 9300 5290 9300 5330 9301 5290 9301 5289 9301 5330 9302 5328 9302 5290 9302 5331 9303 5289 9303 5297 9303 5331 9304 5330 9304 5289 9304 5332 9305 5297 9305 5301 9305 5332 9306 5331 9306 5297 9306 5333 9307 5301 9307 5311 9307 5333 9308 5332 9308 5301 9308 5314 9309 5333 9309 5311 9309 5334 9310 5333 9310 5314 9310 5296 9311 5334 9311 5314 9311 5335 9312 5334 9312 5296 9312 5327 9313 5296 9313 5295 9313 5327 9314 5335 9314 5296 9314 5336 9315 5337 9315 5315 9315 5336 9316 5315 9316 5310 9316 5305 9317 5336 9317 5310 9317 5338 9318 5336 9318 5305 9318 5339 9319 5305 9319 5300 9319 5339 9320 5338 9320 5305 9320 5302 9321 5339 9321 5300 9321 5340 9322 5339 9322 5302 9322 5307 9323 5340 9323 5302 9323 5341 9324 5340 9324 5307 9324 5312 9325 5341 9325 5307 9325 5342 9326 5341 9326 5312 9326 5313 9327 5342 9327 5312 9327 5329 9328 5342 9328 5313 9328 5318 9329 5326 9329 5292 9329 5343 9330 5326 9330 5318 9330 5316 9331 5343 9331 5318 9331 5344 9332 5343 9332 5316 9332 5345 9333 5316 9333 5309 9333 5345 9334 5344 9334 5316 9334 5346 9335 5309 9335 5299 9335 5346 9336 5345 9336 5309 9336 5291 9337 5346 9337 5299 9337 5347 9338 5346 9338 5291 9338 5348 9339 5291 9339 5317 9339 5348 9340 5347 9340 5291 9340 5337 9341 5317 9341 5315 9341 5337 9342 5348 9342 5317 9342 5342 9343 5339 9343 5340 9343 5342 9344 5340 9344 5341 9344 5329 9345 5339 9345 5342 9345 5331 9346 5328 9346 5330 9346 5332 9347 5328 9347 5331 9347 5333 9348 5329 9348 5328 9348 5333 9349 5328 9349 5332 9349 5334 9350 5336 9350 5338 9350 5334 9351 5338 9351 5339 9351 5334 9352 5339 9352 5329 9352 5334 9353 5329 9353 5333 9353 5343 9354 5344 9354 5345 9354 5343 9355 5345 9355 5346 9355 5335 9356 5337 9356 5336 9356 5335 9357 5336 9357 5334 9357 5327 9358 5337 9358 5335 9358 5319 9359 5348 9359 5337 9359 5319 9360 5337 9360 5327 9360 5326 9361 5343 9361 5346 9361 5320 9362 5347 9362 5348 9362 5320 9363 5348 9363 5319 9363 5321 9364 5346 9364 5347 9364 5321 9365 5326 9365 5346 9365 5321 9366 5347 9366 5320 9366 5323 9367 5324 9367 5325 9367 5322 9368 5325 9368 5326 9368 5322 9369 5326 9369 5321 9369 5322 9370 5323 9370 5325 9370 5349 9371 2386 9371 2367 9371 5350 9372 5349 9372 2367 9372 5351 9373 5350 9373 2366 9373 5350 9374 2367 9374 2366 9374 5352 9375 5351 9375 2368 9375 5351 9376 2366 9376 2368 9376 5352 9377 2368 9377 5353 9377 5353 9378 2368 9378 2369 9378 5353 9379 2369 9379 5354 9379 5354 9380 2369 9380 2371 9380 5355 9381 5354 9381 2394 9381 5354 9382 2371 9382 2394 9382 5356 9383 5355 9383 2395 9383 5355 9384 2394 9384 2395 9384 5357 9385 5356 9385 2396 9385 5356 9386 2395 9386 2396 9386 5358 9387 2387 9387 5349 9387 5349 9388 2387 9388 2386 9388 5359 9389 2454 9389 2467 9389 5360 9390 5359 9390 2467 9390 5361 9391 5360 9391 2468 9391 5360 9392 2467 9392 2468 9392 5362 9393 5361 9393 2469 9393 5361 9394 2468 9394 2469 9394 5363 9395 5362 9395 2416 9395 5362 9396 2469 9396 2416 9396 5363 9397 2416 9397 5364 9397 5364 9398 2416 9398 2415 9398 5364 9399 2415 9399 5358 9399 5358 9400 2415 9400 2387 9400 5365 9401 2437 9401 5359 9401 5359 9402 2437 9402 2454 9402 5366 9403 2616 9403 2703 9403 5367 9404 5366 9404 2703 9404 5367 9405 2703 9405 5368 9405 5368 9406 2703 9406 2709 9406 5369 9407 5368 9407 2717 9407 5368 9408 2709 9408 2717 9408 5369 9409 2717 9409 5370 9409 5370 9410 2717 9410 2722 9410 5371 9411 5370 9411 2726 9411 5370 9412 2722 9412 2726 9412 5372 9413 5371 9413 2433 9413 5371 9414 2726 9414 2433 9414 5373 9415 5372 9415 2432 9415 5372 9416 2433 9416 2432 9416 5373 9417 2432 9417 5374 9417 5374 9418 2432 9418 2435 9418 5365 9419 5374 9419 2437 9419 5374 9420 2435 9420 2437 9420 5375 9421 2564 9421 5366 9421 5366 9422 2564 9422 2616 9422 5376 9423 2561 9423 2553 9423 5377 9424 5376 9424 2553 9424 5378 9425 5377 9425 2543 9425 5377 9426 2553 9426 2543 9426 5379 9427 5378 9427 2529 9427 5378 9428 2543 9428 2529 9428 5380 9429 5379 9429 2518 9429 5379 9430 2529 9430 2518 9430 5381 9431 5380 9431 2524 9431 5380 9432 2518 9432 2524 9432 5382 9433 5381 9433 2526 9433 5381 9434 2524 9434 2526 9434 5382 9435 2526 9435 5383 9435 5383 9436 2526 9436 2535 9436 5384 9437 5383 9437 2556 9437 5383 9438 2535 9438 2556 9438 5375 9439 5384 9439 2564 9439 5384 9440 2556 9440 2564 9440 5357 9441 2396 9441 2561 9441 5376 9442 5357 9442 2561 9442 5378 9443 5379 9443 5380 9443 5378 9444 5380 9444 5381 9444 5378 9445 5381 9445 5382 9445 5377 9446 5382 9446 5383 9446 5377 9447 5378 9447 5382 9447 5376 9448 5383 9448 5384 9448 5376 9449 5377 9449 5383 9449 5375 9450 5376 9450 5384 9450 5357 9451 5376 9451 5375 9451 5351 9452 5352 9452 5353 9452 5351 9453 5353 9453 5354 9453 5350 9454 5354 9454 5355 9454 5350 9455 5355 9455 5356 9455 5350 9456 5351 9456 5354 9456 5349 9457 5356 9457 5357 9457 5349 9458 5357 9458 5375 9458 5349 9459 5350 9459 5356 9459 5370 9460 5368 9460 5369 9460 5371 9461 5368 9461 5370 9461 5372 9462 5367 9462 5368 9462 5372 9463 5368 9463 5371 9463 5373 9464 5366 9464 5367 9464 5373 9465 5367 9465 5372 9465 5374 9466 5366 9466 5373 9466 5365 9467 5366 9467 5374 9467 5358 9468 5375 9468 5366 9468 5358 9469 5349 9469 5375 9469 5359 9470 5364 9470 5358 9470 5359 9471 5358 9471 5366 9471 5359 9472 5366 9472 5365 9472 5363 9473 5364 9473 5359 9473 5362 9474 5363 9474 5359 9474 5361 9475 5362 9475 5359 9475 5361 9476 5359 9476 5360 9476 5385 9477 2374 9477 2376 9477 5386 9478 5385 9478 2376 9478 5386 9479 2376 9479 5387 9479 5387 9480 2376 9480 2429 9480 5388 9481 5387 9481 2723 9481 5387 9482 2429 9482 2723 9482 5388 9483 2723 9483 5389 9483 5389 9484 2723 9484 2718 9484 5390 9485 5389 9485 2710 9485 5389 9486 2718 9486 2710 9486 5391 9487 5390 9487 2704 9487 5390 9488 2710 9488 2704 9488 5392 9489 5391 9489 2701 9489 5391 9490 2704 9490 2701 9490 5393 9491 5392 9491 2700 9491 5392 9492 2701 9492 2700 9492 5394 9493 2672 9493 5385 9493 5385 9494 2672 9494 2374 9494 5395 9495 2608 9495 2622 9495 5396 9496 5395 9496 2622 9496 5397 9497 5396 9497 2628 9497 5396 9498 2622 9498 2628 9498 5397 9499 2628 9499 5398 9499 5398 9500 2628 9500 2651 9500 5399 9501 5398 9501 2656 9501 5398 9502 2651 9502 2656 9502 5399 9503 2656 9503 5400 9503 5400 9504 2656 9504 2657 9504 5401 9505 5400 9505 2663 9505 5400 9506 2657 9506 2663 9506 5402 9507 5401 9507 2664 9507 5401 9508 2663 9508 2664 9508 5403 9509 5402 9509 2670 9509 5402 9510 2664 9510 2670 9510 5403 9511 2670 9511 5394 9511 5394 9512 2670 9512 2672 9512 5404 9513 2489 9513 2608 9513 5395 9514 5404 9514 2608 9514 5405 9515 2499 9515 2494 9515 5406 9516 5405 9516 2494 9516 5407 9517 5406 9517 2480 9517 5406 9518 2494 9518 2480 9518 5407 9519 2480 9519 5408 9519 5408 9520 2480 9520 2474 9520 5409 9521 5408 9521 2463 9521 5408 9522 2474 9522 2463 9522 5410 9523 5409 9523 2465 9523 5409 9524 2463 9524 2465 9524 5411 9525 5410 9525 2470 9525 5410 9526 2465 9526 2470 9526 5411 9527 2470 9527 5412 9527 5412 9528 2470 9528 2475 9528 5412 9529 2475 9529 5413 9529 5413 9530 2475 9530 2488 9530 5404 9531 5413 9531 2489 9531 5413 9532 2488 9532 2489 9532 5414 9533 2536 9533 2499 9533 5405 9534 5414 9534 2499 9534 5415 9535 2605 9535 2590 9535 5416 9536 5415 9536 2590 9536 5416 9537 2590 9537 5417 9537 5417 9538 2590 9538 2581 9538 5418 9539 5417 9539 2576 9539 5417 9540 2581 9540 2576 9540 5418 9541 2576 9541 5419 9541 5419 9542 2576 9542 2570 9542 5420 9543 5419 9543 2557 9543 5419 9544 2570 9544 2557 9544 5420 9545 2557 9545 5414 9545 5414 9546 2557 9546 2536 9546 5393 9547 2700 9547 2605 9547 5415 9548 5393 9548 2605 9548 5398 9549 5399 9549 5401 9549 5399 9550 5400 9550 5401 9550 5398 9551 5401 9551 5402 9551 5397 9552 5398 9552 5403 9552 5398 9553 5402 9553 5403 9553 5395 9554 5396 9554 5394 9554 5396 9555 5397 9555 5394 9555 5397 9556 5403 9556 5394 9556 5395 9557 5394 9557 5385 9557 5386 9558 5387 9558 5389 9558 5387 9559 5388 9559 5389 9559 5385 9560 5386 9560 5390 9560 5386 9561 5389 9561 5390 9561 5385 9562 5390 9562 5391 9562 5385 9563 5391 9563 5392 9563 5395 9564 5385 9564 5393 9564 5385 9565 5392 9565 5393 9565 5409 9566 5410 9566 5408 9566 5410 9567 5411 9567 5407 9567 5408 9568 5410 9568 5407 9568 5411 9569 5412 9569 5406 9569 5412 9570 5413 9570 5406 9570 5407 9571 5411 9571 5406 9571 5413 9572 5404 9572 5405 9572 5406 9573 5413 9573 5405 9573 5404 9574 5395 9574 5415 9574 5395 9575 5393 9575 5415 9575 5405 9576 5404 9576 5414 9576 5404 9577 5415 9577 5414 9577 5414 9578 5415 9578 5416 9578 5414 9579 5416 9579 5420 9579 5416 9580 5417 9580 5419 9580 5420 9581 5416 9581 5419 9581 5419 9582 5417 9582 5418 9582 5421 9583 2464 9583 2501 9583 5422 9584 5421 9584 2501 9584 5423 9585 5422 9585 2520 9585 5422 9586 2501 9586 2520 9586 5423 9587 2520 9587 5424 9587 5424 9588 2520 9588 2519 9588 5425 9589 5424 9589 2530 9589 5424 9590 2519 9590 2530 9590 5425 9591 2530 9591 5426 9591 5426 9592 2530 9592 2544 9592 5427 9593 5426 9593 2419 9593 5426 9594 2544 9594 2419 9594 5428 9595 5427 9595 2417 9595 5427 9596 2419 9596 2417 9596 5429 9597 5428 9597 2414 9597 5428 9598 2417 9598 2414 9598 5430 9599 2503 9599 2464 9599 5421 9600 5430 9600 2464 9600 5431 9601 2610 9601 2609 9601 5432 9602 5431 9602 2609 9602 5432 9603 2609 9603 5433 9603 5433 9604 2609 9604 2611 9604 5434 9605 5433 9605 2612 9605 5433 9606 2611 9606 2612 9606 5434 9607 2612 9607 5435 9607 5435 9608 2612 9608 2613 9608 5436 9609 5435 9609 2614 9609 5435 9610 2613 9610 2614 9610 5430 9611 5436 9611 2503 9611 5436 9612 2614 9612 2503 9612 5437 9613 2615 9613 2610 9613 5431 9614 5437 9614 2610 9614 5438 9615 2598 9615 2497 9615 5439 9616 5438 9616 2497 9616 5439 9617 2497 9617 5440 9617 5440 9618 2497 9618 2338 9618 5440 9619 2338 9619 5441 9619 5441 9620 2338 9620 2336 9620 5442 9621 5441 9621 2650 9621 5441 9622 2336 9622 2650 9622 5443 9623 5442 9623 2649 9623 5442 9624 2650 9624 2649 9624 5444 9625 5443 9625 2624 9625 5443 9626 2649 9626 2624 9626 5445 9627 5444 9627 2623 9627 5444 9628 2624 9628 2623 9628 5446 9629 5445 9629 2620 9629 5445 9630 2623 9630 2620 9630 5446 9631 2620 9631 5437 9631 5437 9632 2620 9632 2615 9632 5447 9633 2596 9633 2598 9633 5438 9634 5447 9634 2598 9634 5448 9635 2411 9635 2404 9635 5449 9636 5448 9636 2404 9636 5449 9637 2404 9637 5450 9637 5450 9638 2404 9638 2401 9638 5451 9639 5450 9639 2388 9639 5450 9640 2401 9640 2388 9640 5452 9641 5451 9641 2389 9641 5451 9642 2388 9642 2389 9642 5453 9643 5452 9643 2592 9643 5452 9644 2389 9644 2592 9644 5454 9645 5453 9645 2591 9645 5453 9646 2592 9646 2591 9646 5454 9647 2591 9647 5455 9647 5455 9648 2591 9648 2589 9648 5456 9649 5455 9649 2588 9649 5455 9650 2589 9650 2588 9650 5456 9651 2588 9651 5457 9651 5457 9652 2588 9652 2587 9652 5447 9653 5457 9653 2596 9653 5457 9654 2587 9654 2596 9654 5429 9655 2414 9655 2411 9655 5448 9656 5429 9656 2411 9656 5433 9657 5434 9657 5431 9657 5433 9658 5431 9658 5432 9658 5451 9659 5452 9659 5453 9659 5450 9660 5453 9660 5454 9660 5450 9661 5451 9661 5453 9661 5449 9662 5454 9662 5455 9662 5449 9663 5450 9663 5454 9663 5448 9664 5455 9664 5456 9664 5448 9665 5456 9665 5457 9665 5448 9666 5449 9666 5455 9666 5447 9667 5448 9667 5457 9667 5429 9668 5448 9668 5447 9668 5423 9669 5424 9669 5425 9669 5423 9670 5425 9670 5426 9670 5422 9671 5426 9671 5427 9671 5422 9672 5427 9672 5428 9672 5422 9673 5423 9673 5426 9673 5421 9674 5428 9674 5429 9674 5421 9675 5429 9675 5447 9675 5421 9676 5422 9676 5428 9676 5442 9677 5440 9677 5441 9677 5443 9678 5439 9678 5440 9678 5443 9679 5440 9679 5442 9679 5444 9680 5438 9680 5439 9680 5444 9681 5439 9681 5443 9681 5445 9682 5438 9682 5444 9682 5446 9683 5438 9683 5445 9683 5437 9684 5438 9684 5446 9684 5430 9685 5447 9685 5438 9685 5430 9686 5421 9686 5447 9686 5431 9687 5438 9687 5437 9687 5431 9688 5436 9688 5430 9688 5431 9689 5430 9689 5438 9689 5435 9690 5436 9690 5431 9690 5434 9691 5435 9691 5431 9691 1497 9692 1492 9692 1491 9692 1497 9693 1495 9693 1492 9693 1497 9694 1499 9694 1495 9694 1497 9695 1504 9695 1499 9695 1497 9696 1505 9696 1504 9696 1539 9697 1497 9697 1491 9697 1501 9698 1498 9698 1497 9698 1509 9699 1501 9699 1497 9699 1533 9700 1536 9700 1535 9700 1533 9701 1539 9701 1536 9701 1533 9702 1497 9702 1539 9702 1531 9703 1497 9703 1533 9703 1513 9704 1510 9704 1509 9704 1513 9705 1509 9705 1497 9705 1527 9706 1531 9706 1528 9706 1527 9707 1497 9707 1531 9707 1517 9708 1514 9708 1513 9708 1517 9709 1513 9709 1497 9709 1522 9710 1527 9710 1525 9710 1522 9711 1517 9711 1497 9711 1522 9712 1497 9712 1527 9712 1521 9713 1519 9713 1517 9713 1521 9714 1517 9714 1522 9714 1442 9715 1450 9715 1443 9715 1456 9716 1455 9716 1450 9716 1488 9717 1442 9717 1441 9717 1448 9718 1447 9718 1456 9718 1448 9719 1456 9719 1450 9719 1487 9720 1442 9720 1488 9720 1458 9721 1453 9721 1448 9721 1461 9722 1450 9722 1442 9722 1461 9723 1448 9723 1450 9723 1461 9724 1458 9724 1448 9724 1465 9725 1462 9725 1461 9725 1465 9726 1461 9726 1442 9726 1475 9727 1478 9727 1477 9727 1475 9728 1480 9728 1478 9728 1475 9729 1482 9729 1480 9729 1475 9730 1485 9730 1482 9730 1469 9731 1467 9731 1465 9731 1469 9732 1442 9732 1487 9732 1469 9733 1465 9733 1442 9733 1471 9734 1475 9734 1473 9734 1471 9735 1487 9735 1485 9735 1471 9736 1485 9736 1475 9736 1471 9737 1469 9737 1487 9737 1404 9738 1402 9738 1406 9738 1408 9739 1406 9739 1410 9739 1398 9740 1396 9740 1394 9740 1388 9741 1386 9741 1370 9741 1390 9742 1388 9742 1370 9742 1392 9743 1390 9743 1370 9743 1394 9744 1392 9744 1370 9744 1400 9745 1398 9745 1370 9745 1402 9746 1400 9746 1370 9746 1412 9747 1410 9747 1370 9747 1414 9748 1412 9748 1370 9748 1366 9749 1414 9749 1370 9749 1367 9750 1366 9750 1370 9750 1373 9751 1367 9751 1370 9751 1406 9752 1402 9752 1370 9752 1410 9753 1406 9753 1370 9753 1398 9754 1394 9754 1370 9754 1370 9755 1386 9755 1384 9755 1371 9756 1370 9756 1375 9756 1384 9757 1382 9757 1380 9757 1370 9758 1384 9758 1380 9758 1370 9759 1380 9759 1378 9759 1375 9760 1370 9760 1378 9760 5458 9761 5459 9761 5460 9761 5461 9762 5458 9762 5460 9762 5462 9763 5461 9763 5463 9763 5461 9764 5460 9764 5463 9764 5464 9765 5462 9765 5465 9765 5462 9766 5463 9766 5465 9766 5466 9767 5467 9767 5468 9767 5469 9768 5466 9768 5468 9768 5470 9769 5469 9769 5471 9769 5469 9770 5468 9770 5471 9770 5472 9771 5470 9771 5473 9771 5470 9772 5471 9772 5473 9772 5474 9773 5475 9773 5476 9773 5476 9774 5475 9774 5477 9774 5478 9775 5479 9775 5480 9775 5481 9776 5482 9776 5483 9776 5484 9777 5481 9777 5483 9777 5485 9778 5484 9778 5486 9778 5484 9779 5483 9779 5486 9779 5487 9780 5485 9780 5488 9780 5485 9781 5486 9781 5488 9781 5489 9782 5487 9782 5490 9782 5487 9783 5488 9783 5490 9783 5491 9784 5489 9784 5492 9784 5489 9785 5490 9785 5492 9785 5493 9786 5491 9786 5494 9786 5491 9787 5492 9787 5494 9787 5495 9788 5493 9788 5496 9788 5493 9789 5494 9789 5496 9789 5497 9790 5495 9790 5498 9790 5495 9791 5496 9791 5498 9791 5499 9792 5497 9792 5500 9792 5497 9793 5498 9793 5500 9793 5501 9794 5499 9794 5502 9794 5499 9795 5500 9795 5502 9795 5503 9796 5501 9796 5504 9796 5501 9797 5502 9797 5504 9797 5505 9798 5503 9798 5506 9798 5503 9799 5504 9799 5506 9799 5507 9800 5505 9800 5508 9800 5505 9801 5506 9801 5508 9801 5509 9802 5507 9802 5510 9802 5507 9803 5508 9803 5510 9803 5509 9804 5510 9804 5511 9804 5512 9805 5509 9805 5511 9805 5512 9806 5511 9806 5513 9806 5514 9807 5512 9807 5513 9807 5514 9808 5513 9808 5515 9808 5479 9809 5514 9809 5515 9809 5479 9810 5515 9810 5480 9810 5516 9811 5517 9811 5518 9811 5519 9812 5516 9812 5518 9812 5520 9813 5521 9813 5522 9813 5523 9814 5520 9814 5522 9814 2837 9815 2839 9815 5524 9815 5525 9816 2837 9816 5524 9816 5526 9817 5525 9817 5527 9817 5525 9818 5524 9818 5527 9818 5528 9819 5526 9819 5529 9819 5526 9820 5527 9820 5529 9820 5530 9821 5528 9821 5531 9821 5528 9822 5529 9822 5531 9822 5522 9823 5530 9823 5523 9823 5530 9824 5531 9824 5523 9824 5532 9825 5533 9825 5534 9825 5535 9826 5533 9826 5532 9826 5535 9827 5532 9827 5536 9827 5537 9828 5535 9828 5536 9828 5538 9829 5537 9829 5539 9829 5537 9830 5536 9830 5539 9830 5540 9831 5538 9831 5541 9831 5538 9832 5539 9832 5541 9832 5542 9833 5540 9833 5543 9833 5540 9834 5541 9834 5543 9834 2811 9835 5542 9835 2812 9835 5542 9836 5543 9836 2812 9836 5534 9837 5533 9837 5544 9837 5545 9838 5544 9838 5546 9838 5545 9839 5534 9839 5544 9839 5547 9840 5546 9840 5548 9840 5547 9841 5545 9841 5546 9841 5549 9842 5548 9842 5464 9842 5549 9843 5547 9843 5548 9843 5465 9844 5549 9844 5464 9844 5467 9845 5466 9845 5550 9845 5551 9846 5550 9846 5552 9846 5551 9847 5467 9847 5550 9847 5553 9848 5552 9848 5554 9848 5553 9849 5551 9849 5552 9849 5555 9850 5554 9850 5521 9850 5555 9851 5553 9851 5554 9851 5520 9852 5555 9852 5521 9852 5459 9853 5458 9853 5556 9853 5557 9854 5556 9854 5558 9854 5557 9855 5459 9855 5556 9855 5559 9856 5558 9856 5475 9856 5559 9857 5557 9857 5558 9857 5474 9858 5559 9858 5475 9858 5519 9859 5518 9859 5560 9859 5561 9860 5560 9860 5562 9860 5561 9861 5519 9861 5560 9861 5563 9862 5562 9862 5472 9862 5563 9863 5561 9863 5562 9863 5473 9864 5563 9864 5472 9864 5478 9865 5480 9865 5564 9865 5565 9866 5478 9866 5564 9866 5566 9867 5565 9867 5567 9867 5565 9868 5564 9868 5567 9868 5477 9869 5566 9869 5476 9869 5566 9870 5567 9870 5476 9870 5517 9871 5516 9871 5568 9871 5569 9872 5517 9872 5568 9872 5570 9873 5569 9873 5571 9873 5569 9874 5568 9874 5571 9874 5481 9875 5570 9875 5482 9875 5570 9876 5571 9876 5482 9876 847 9877 846 9877 968 9877 858 9878 854 9878 961 9878 854 9879 847 9879 961 9879 847 9880 968 9880 961 9880 860 9881 858 9881 957 9881 858 9882 961 9882 957 9882 866 9883 864 9883 956 9883 864 9884 860 9884 956 9884 860 9885 957 9885 956 9885 871 9886 866 9886 954 9886 866 9887 956 9887 954 9887 876 9888 874 9888 951 9888 874 9889 871 9889 951 9889 871 9890 954 9890 951 9890 880 9891 876 9891 948 9891 876 9892 951 9892 948 9892 883 9893 880 9893 943 9893 880 9894 948 9894 943 9894 883 9895 943 9895 940 9895 5572 9896 5573 9896 5574 9896 5575 9897 5576 9897 5577 9897 5572 9898 4304 9898 5578 9898 5579 9899 5580 9899 5581 9899 5575 9900 5582 9900 5583 9900 5575 9901 5583 9901 5576 9901 5575 9902 5584 9902 5582 9902 5585 9903 5574 9903 5586 9903 5587 9904 5588 9904 5589 9904 5587 9905 5589 9905 5590 9905 5585 9906 5572 9906 5574 9906 5591 9907 1351 9907 1338 9907 5592 9908 5577 9908 5593 9908 5591 9909 5594 9909 1351 9909 5595 9910 5596 9910 5597 9910 5591 9911 5598 9911 5594 9911 5599 9912 5600 9912 1003 9912 5599 9913 1003 9913 1000 9913 5595 9914 5597 9914 5601 9914 5602 9915 5586 9915 5603 9915 5604 9916 5580 9916 5579 9916 5602 9917 5585 9917 5586 9917 4303 9918 5605 9918 5606 9918 4303 9919 5578 9919 4304 9919 5604 9920 5607 9920 5580 9920 4303 9921 5606 9921 5578 9921 5608 9922 5575 9922 5577 9922 5609 9923 5603 9923 5598 9923 5609 9924 5591 9924 1338 9924 5609 9925 5602 9925 5603 9925 5609 9926 5598 9926 5591 9926 4305 9927 4304 9927 5572 9927 5610 9928 5587 9928 5590 9928 5611 9929 5577 9929 5592 9929 4305 9930 5572 9930 5585 9930 5611 9931 5608 9931 5577 9931 4305 9932 5585 9932 5602 9932 5612 9933 1338 9933 1337 9933 5612 9934 1337 9934 4305 9934 5612 9935 4305 9935 5602 9935 5612 9936 5609 9936 1338 9936 5612 9937 5602 9937 5609 9937 5613 9938 5614 9938 5615 9938 5616 9939 5599 9939 1000 9939 5613 9940 5615 9940 5596 9940 5617 9941 5596 9941 5595 9941 5618 9942 5616 9942 1000 9942 4281 9943 5619 9943 5620 9943 4281 9944 5620 9944 5584 9944 5617 9945 5613 9945 5596 9945 4281 9946 4277 9946 5619 9946 5621 9947 4298 9947 5622 9947 5621 9948 5622 9948 5623 9948 5621 9949 5623 9949 5624 9949 5625 9950 5600 9950 5599 9950 5626 9951 5627 9951 873 9951 5628 9952 5614 9952 5613 9952 5629 9953 5584 9953 5575 9953 5628 9954 5630 9954 5614 9954 5629 9955 5575 9955 5608 9955 5629 9956 4283 9956 5584 9956 5631 9957 5627 9957 5626 9957 5632 9958 5600 9958 5625 9958 5631 9959 5579 9959 5627 9959 5633 9960 5601 9960 5634 9960 5633 9961 5595 9961 5601 9961 5632 9962 5635 9962 5600 9962 5633 9963 5634 9963 5607 9963 5636 9964 5625 9964 5599 9964 5637 9965 5638 9965 5630 9965 5637 9966 5630 9966 5628 9966 5636 9967 5599 9967 5616 9967 5636 9968 5616 9968 5618 9968 5639 9969 5640 9969 5635 9969 5641 9970 5638 9970 5637 9970 5641 9971 5590 9971 5638 9971 5639 9972 5635 9972 5632 9972 5642 9973 5604 9973 5579 9973 5642 9974 5579 9974 5631 9974 5643 9975 5632 9975 5625 9975 5643 9976 5625 9976 5636 9976 5644 9977 5624 9977 5588 9977 5644 9978 5588 9978 5587 9978 5645 9979 5628 9979 5613 9979 5646 9980 5647 9980 5640 9980 5645 9981 5613 9981 5617 9981 5646 9982 5640 9982 5639 9982 5648 9983 5643 9983 5636 9983 5649 9984 5628 9984 5645 9984 5648 9985 5636 9985 5618 9985 5649 9986 5637 9986 5628 9986 4282 9987 4281 9987 5584 9987 5650 9988 5629 9988 5608 9988 5651 9989 5641 9989 5637 9989 5651 9990 5637 9990 5649 9990 5652 9991 5587 9991 5610 9991 5653 9992 5654 9992 5647 9992 5652 9993 5644 9993 5587 9993 5653 9994 5647 9994 5646 9994 5655 9995 5650 9995 5608 9995 5655 9996 4285 9996 5650 9996 5655 9997 5608 9997 5611 9997 5656 9998 5641 9998 5651 9998 5657 9999 5643 9999 5648 9999 5658 10000 5607 10000 5604 10000 5658 10001 5633 10001 5607 10001 5659 10002 5654 10002 5653 10002 5659 10003 5593 10003 5654 10003 5660 10004 873 10004 869 10004 5661 10005 5639 10005 5632 10005 5660 10006 5626 10006 873 10006 5661 10007 5643 10007 5657 10007 5662 10008 5631 10008 5626 10008 5661 10009 5632 10009 5643 10009 5662 10010 5660 10010 869 10010 5662 10011 5626 10011 5660 10011 5663 10012 5646 10012 5639 10012 5664 10013 5595 10013 5633 10013 5663 10014 5639 10014 5661 10014 5665 10015 5661 10015 5657 10015 5665 10016 5663 10016 5661 10016 5666 10017 5653 10017 5646 10017 5667 10018 5642 10018 5631 10018 5667 10019 5631 10019 5662 10019 5666 10020 5646 10020 5663 10020 5668 10021 5662 10021 869 10021 5668 10022 5667 10022 5662 10022 5669 10023 5617 10023 5595 10023 5670 10024 5618 10024 1000 10024 5669 10025 5595 10025 5664 10025 5671 10026 5658 10026 5604 10026 5672 10027 5653 10027 5666 10027 5672 10028 5659 10028 5653 10028 5671 10029 5604 10029 5642 10029 5673 10030 978 10030 977 10030 5674 10031 5663 10031 5665 10031 5673 10032 977 10032 1016 10032 5674 10033 5666 10033 5663 10033 5675 10034 5673 10034 1016 10034 5675 10035 5676 10035 978 10035 5677 10036 5667 10036 5668 10036 5675 10037 978 10037 5673 10037 4294 10038 5622 10038 4298 10038 5678 10039 5672 10039 5666 10039 4294 10040 5679 10040 5622 10040 5678 10041 5666 10041 5674 10041 5680 10042 5675 10042 1016 10042 5680 10043 5676 10043 5675 10043 5681 10044 5682 10044 5676 10044 5683 10045 5645 10045 5617 10045 5681 10046 5676 10046 5680 10046 5684 10047 5672 10047 5678 10047 5683 10048 5617 10048 5669 10048 5685 10049 5670 10049 1000 10049 5686 10050 5680 10050 1016 10050 4283 10051 4282 10051 5584 10051 5687 10052 5633 10052 5658 10052 5688 10053 5648 10053 5618 10053 5689 10054 1016 10054 1013 10054 5687 10055 5664 10055 5633 10055 5690 10056 5624 10056 5644 10056 5690 10057 5621 10057 5624 10057 5688 10058 5618 10058 5670 10058 5691 10059 4268 10059 5682 10059 5690 10060 4299 10060 4298 10060 5691 10061 5682 10061 5681 10061 5692 10062 1013 10062 1009 10062 5693 10063 5645 10063 5683 10063 5692 10064 5689 10064 1013 10064 5694 10065 5648 10065 5688 10065 5693 10066 5649 10066 5645 10066 5694 10067 5657 10067 5648 10067 5695 10068 5689 10068 5692 10068 5693 10069 5651 10069 5649 10069 5696 10070 5680 10070 5686 10070 5697 10071 5664 10071 5687 10071 5696 10072 5681 10072 5680 10072 5698 10073 5692 10073 1009 10073 5697 10074 5669 10074 5664 10074 5699 10075 5651 10075 5693 10075 5698 10076 5695 10076 5692 10076 5700 10077 5593 10077 5659 10077 5700 10078 5592 10078 5593 10078 5701 10079 5688 10079 5670 10079 5702 10080 5695 10080 5698 10080 5703 10081 5651 10081 5699 10081 5701 10082 5670 10082 5685 10082 5704 10083 5686 10083 1016 10083 5705 10084 5665 10084 5657 10084 5704 10085 1016 10085 5689 10085 5703 10086 5656 10086 5651 10086 5704 10087 5689 10087 5695 10087 5706 10088 5668 10088 869 10088 5705 10089 5657 10089 5694 10089 5707 10090 5691 10090 5681 10090 5707 10091 5681 10091 5696 10091 5707 10092 4268 10092 5691 10092 4285 10093 5629 10093 5650 10093 4285 10094 4283 10094 5629 10094 5708 10095 5698 10095 1009 10095 5709 10096 5590 10096 5641 10096 5710 10097 5674 10097 5665 10097 5709 10098 5641 10098 5656 10098 5709 10099 5610 10099 5590 10099 5711 10100 4299 10100 5690 10100 5711 10101 5690 10101 5644 10101 5710 10102 5665 10102 5705 10102 5712 10103 5708 10103 1009 10103 5711 10104 5644 10104 5652 10104 5713 10105 5694 10105 5688 10105 5713 10106 5688 10106 5701 10106 5714 10107 5708 10107 5712 10107 5713 10108 5705 10108 5694 10108 5715 10109 5642 10109 5667 10109 5716 10110 5659 10110 5672 10110 5714 10111 5698 10111 5708 10111 5715 10112 5671 10112 5642 10112 5715 10113 5667 10113 5677 10113 5717 10114 5658 10114 5671 10114 5718 10115 5698 10115 5714 10115 5718 10116 5702 10116 5698 10116 5716 10117 5672 10117 5684 10117 5716 10118 5700 10118 5659 10118 5717 10119 5687 10119 5658 10119 5719 10120 5668 10120 5706 10120 5720 10121 5678 10121 5674 10121 5721 10122 5714 10122 5712 10122 5720 10123 5674 10123 5710 10123 5719 10124 5677 10124 5668 10124 4298 10125 5621 10125 5690 10125 5722 10126 869 10126 868 10126 5723 10127 5695 10127 5702 10127 5722 10128 5719 10128 5706 10128 5724 10129 5684 10129 5678 10129 5723 10130 5704 10130 5695 10130 5722 10131 5706 10131 869 10131 5725 10132 5669 10132 5697 10132 5724 10133 5678 10133 5720 10133 5725 10134 5683 10134 5669 10134 5726 10135 5718 10135 5714 10135 5726 10136 5714 10136 5721 10136 5727 10137 5686 10137 5704 10137 5728 10138 5716 10138 5684 10138 5728 10139 5684 10139 5724 10139 5727 10140 5696 10140 5686 10140 5729 10141 5655 10141 5611 10141 5727 10142 5704 10142 5723 10142 5730 10143 5687 10143 5717 10143 5730 10144 5697 10144 5687 10144 5729 10145 5592 10145 5700 10145 5731 10146 5702 10146 5718 10146 5729 10147 5611 10147 5592 10147 5731 10148 5723 10148 5702 10148 5732 10149 5715 10149 5677 10149 5733 10150 1000 10150 996 10150 5734 10151 5727 10151 5723 10151 5735 10152 5719 10152 5722 10152 5734 10153 5723 10153 5731 10153 5736 10154 5705 10154 5713 10154 5737 10155 5734 10155 5731 10155 5738 10156 5693 10156 5683 10156 5739 10157 5696 10157 5727 10157 5738 10158 5683 10158 5725 10158 5740 10159 5705 10159 5736 10159 5740 10160 5710 10160 5705 10160 5741 10161 5656 10161 5703 10161 5739 10162 5707 10162 5696 10162 5741 10163 5709 10163 5656 10163 5742 10164 5718 10164 5726 10164 5742 10165 5731 10165 5718 10165 5743 10166 5685 10166 1000 10166 5744 10167 5699 10167 5693 10167 5742 10168 5737 10168 5731 10168 5743 10169 1000 10169 5733 10169 5744 10170 5693 10170 5738 10170 5745 10171 5742 10171 5726 10171 5746 10172 5699 10172 5744 10172 5747 10173 5720 10173 5710 10173 5748 10174 5727 10174 5734 10174 5746 10175 5703 10175 5699 10175 5747 10176 5724 10176 5720 10176 5748 10177 5739 10177 5727 10177 5747 10178 5710 10178 5740 10178 5749 10179 5724 10179 5747 10179 5750 10180 1009 10180 1008 10180 5751 10181 5610 10181 5709 10181 5750 10182 5712 10182 1009 10182 5751 10183 5652 10183 5610 10183 5751 10184 5709 10184 5741 10184 5752 10185 5725 10185 5697 10185 5753 10186 5700 10186 5716 10186 5753 10187 5716 10187 5728 10187 5754 10188 5737 10188 5742 10188 5752 10189 5697 10189 5730 10189 5753 10190 5729 10190 5700 10190 5752 10191 5738 10191 5725 10191 5755 10192 5748 10192 5734 10192 5755 10193 5734 10193 5737 10193 5756 10194 5753 10194 5728 10194 5757 10195 5744 10195 5738 10195 5757 10196 5738 10196 5752 10196 5758 10197 5743 10197 5733 10197 5759 10198 5742 10198 5745 10198 5759 10199 5754 10199 5742 10199 5760 10200 5715 10200 5732 10200 5761 10201 5701 10201 5685 10201 5760 10202 5671 10202 5715 10202 5761 10203 5685 10203 5743 10203 5760 10204 5717 10204 5671 10204 5762 10205 5712 10205 5750 10205 5763 10206 5722 10206 868 10206 5763 10207 5735 10207 5722 10207 5764 10208 5655 10208 5729 10208 5765 10209 5701 10209 5761 10209 5766 10210 5712 10210 5762 10210 5767 10211 5744 10211 5757 10211 5765 10212 5713 10212 5701 10212 5768 10213 5750 10213 1008 10213 5769 10214 5744 10214 5767 10214 5770 10215 5733 10215 996 10215 5769 10216 5746 10216 5744 10216 5771 10217 5721 10217 5712 10217 5772 10218 5677 10218 5719 10218 5772 10219 5732 10219 5677 10219 5771 10220 5712 10220 5766 10220 5772 10221 5719 10221 5735 10221 5773 10222 5733 10222 5770 10222 5774 10223 5730 10223 5717 10223 5774 10224 5717 10224 5760 10224 5775 10225 5726 10225 5721 10225 5776 10226 5756 10226 5728 10226 5775 10227 5721 10227 5771 10227 5776 10228 5728 10228 5724 10228 5776 10229 5724 10229 5749 10229 5777 10230 5768 10230 1008 10230 5778 10231 5733 10231 5773 10231 5779 10232 5751 10232 5741 10232 5780 10233 5770 10233 996 10233 5781 10234 5762 10234 5750 10234 5782 10235 5774 10235 5760 10235 5781 10236 5750 10236 5768 10236 5782 10237 5760 10237 5732 10237 5783 10238 5773 10238 5770 10238 5783 10239 5770 10239 5780 10239 5781 10240 5768 10240 5777 10240 5784 10241 5772 10241 5735 10241 5785 10242 5729 10242 5753 10242 5786 10243 5766 10243 5762 10243 5786 10244 5762 10244 5781 10244 5785 10245 4286 10245 5764 10245 5785 10246 5764 10246 5729 10246 5787 10247 5774 10247 5782 10247 5788 10248 5781 10248 5777 10248 5789 10249 5743 10249 5758 10249 5790 10250 5774 10250 5787 10250 5789 10251 5761 10251 5743 10251 5790 10252 5752 10252 5730 10252 5791 10253 5713 10253 5765 10253 5790 10254 5730 10254 5774 10254 5792 10255 5786 10255 5781 10255 5793 10256 5741 10256 5703 10256 5792 10257 5781 10257 5788 10257 5791 10258 5736 10258 5713 10258 5794 10259 5766 10259 5786 10259 5795 10260 5736 10260 5791 10260 5794 10261 5771 10261 5766 10261 5795 10262 5740 10262 5736 10262 5796 10263 5771 10263 5794 10263 5797 10264 5752 10264 5790 10264 5797 10265 5757 10265 5752 10265 5798 10266 5773 10266 5783 10266 5798 10267 5778 10267 5773 10267 5796 10268 5775 10268 5771 10268 5799 10269 5790 10269 5787 10269 5800 10270 5785 10270 5753 10270 5799 10271 5797 10271 5790 10271 5800 10272 5753 10272 5756 10272 5801 10273 5786 10273 5792 10273 5802 10274 5757 10274 5797 10274 5803 10275 5765 10275 5761 10275 5801 10276 5794 10276 5786 10276 5804 10277 5796 10277 5794 10277 5802 10278 5767 10278 5757 10278 5803 10279 5761 10279 5789 10279 5805 10280 5776 10280 5749 10280 5804 10281 5794 10281 5801 10281 5806 10282 5767 10282 5802 10282 5806 10283 5769 10283 5767 10283 5807 10284 5737 10284 5754 10284 5807 10285 5755 10285 5737 10285 5808 10286 5740 10286 5795 10286 5809 10287 5807 10287 5754 10287 5810 10288 5735 10288 5763 10288 5808 10289 5747 10289 5740 10289 5809 10290 5754 10290 5759 10290 5810 10291 5784 10291 5735 10291 4269 10292 5707 10292 5739 10292 5811 10293 5802 10293 5797 10293 5811 10294 5797 10294 5799 10294 4269 10295 5739 10295 5748 10295 4269 10296 4268 10296 5707 10296 5812 10297 5747 10297 5808 10297 5812 10298 5749 10298 5747 10298 5813 10299 5756 10299 5776 10299 5814 10300 1008 10300 1003 10300 5815 10301 5732 10301 5772 10301 5815 10302 5782 10302 5732 10302 5816 10303 5791 10303 5765 10303 5815 10304 5772 10304 5784 10304 5817 10305 5711 10305 5652 10305 5816 10306 5765 10306 5803 10306 5818 10307 1008 10307 5814 10307 5817 10308 4299 10308 5711 10308 5817 10309 5652 10309 5751 10309 5818 10310 5777 10310 1008 10310 5817 10311 5751 10311 5779 10311 4274 10312 4269 10312 5748 10312 4274 10313 5755 10313 5807 10313 5819 10314 5806 10314 5802 10314 4274 10315 5748 10315 5755 10315 5820 10316 5795 10316 5791 10316 5821 10317 5745 10317 5726 10317 5819 10318 5802 10318 5811 10318 5821 10319 5775 10319 5796 10319 5820 10320 5791 10320 5816 10320 5822 10321 5806 10321 5819 10321 5823 10322 5733 10322 5778 10322 5823 10323 5758 10323 5733 10323 5821 10324 5726 10324 5775 10324 5824 10325 5787 10325 5782 10325 5824 10326 5782 10326 5815 10326 5825 10327 5777 10327 5818 10327 5825 10328 5788 10328 5777 10328 5826 10329 5808 10329 5795 10329 5827 10330 5792 10330 5788 10330 5828 10331 5815 10331 5784 10331 5826 10332 5812 10332 5808 10332 5826 10333 5795 10333 5820 10333 5828 10334 5824 10334 5815 10334 5827 10335 5788 10335 5825 10335 5829 10336 5703 10336 5746 10336 5830 10337 5812 10337 5826 10337 5831 10338 5814 10338 1003 10338 5831 10339 5818 10339 5814 10339 5832 10340 5776 10340 5805 10340 5829 10341 5746 10341 5769 10341 5832 10342 5813 10342 5776 10342 5829 10343 5793 10343 5703 10343 5833 10344 5801 10344 5792 10344 5834 10345 5824 10345 5828 10345 5833 10346 5792 10346 5827 10346 5835 10347 863 10347 862 10347 5836 10348 5823 10348 5778 10348 5835 10349 868 10349 863 10349 5836 10350 5778 10350 5798 10350 4286 10351 4285 10351 5655 10351 5837 10352 5801 10352 5833 10352 4286 10353 5655 10353 5764 10353 5838 10354 5789 10354 5758 10354 5837 10355 5804 10355 5801 10355 5839 10356 5741 10356 5793 10356 5839 10357 5779 10357 5741 10357 5838 10358 5758 10358 5823 10358 5840 10359 868 10359 5835 10359 5838 10360 5803 10360 5789 10360 5841 10361 5796 10361 5804 10361 5840 10362 5835 10362 862 10362 5841 10363 5821 10363 5796 10363 5842 10364 5817 10364 5779 10364 5842 10365 4300 10365 5817 10365 5843 10366 5780 10366 996 10366 5844 10367 5841 10367 5804 10367 5845 10368 5811 10368 5799 10368 5843 10369 996 10369 877 10369 5846 10370 5825 10370 5818 10370 5846 10371 5818 10371 5831 10371 5847 10372 5800 10372 5756 10372 5845 10373 5787 10373 5824 10373 5845 10374 5824 10374 5834 10374 5845 10375 5799 10375 5787 10375 5847 10376 5756 10376 5813 10376 5848 10377 862 10377 1351 10377 5849 10378 5745 10378 5821 10378 5848 10379 5810 10379 5763 10379 5850 10380 5803 10380 5838 10380 5849 10381 5809 10381 5759 10381 5848 10382 5840 10382 862 10382 5848 10383 868 10383 5840 10383 5848 10384 5763 10384 868 10384 5849 10385 5759 10385 5745 10385 5851 10386 5827 10386 5825 10386 5852 10387 5811 10387 5845 10387 5851 10388 5825 10388 5846 10388 5853 10389 5780 10389 5843 10389 5854 10390 5829 10390 5769 10390 5855 10391 5827 10391 5851 10391 5855 10392 5833 10392 5827 10392 5856 10393 5828 10393 5784 10393 4275 10394 5807 10394 5809 10394 5856 10395 5834 10395 5828 10395 5857 10396 5838 10396 5823 10396 4275 10397 4274 10397 5807 10397 5857 10398 5823 10398 5836 10398 5856 10399 5784 10399 5810 10399 5858 10400 5849 10400 5821 10400 5859 10401 5780 10401 5853 10401 5860 10402 5845 10402 5834 10402 5860 10403 5852 10403 5845 10403 5859 10404 5783 10404 5780 10404 5858 10405 5821 10405 5841 10405 5861 10406 5805 10406 5749 10406 5862 10407 5819 10407 5811 10407 5861 10408 5749 10408 5812 10408 5862 10409 5811 10409 5852 10409 5863 10410 5833 10410 5855 10410 5863 10411 5837 10411 5833 10411 5864 10412 5822 10412 5819 10412 5861 10413 5812 10413 5830 10413 4290 10414 5785 10414 5800 10414 5864 10415 5819 10415 5862 10415 4290 10416 4286 10416 5785 10416 5615 10417 5850 10417 5838 10417 5865 10418 5837 10418 5863 10418 5866 10419 5852 10419 5860 10419 5866 10420 5862 10420 5852 10420 5867 10421 5841 10421 5844 10421 5615 10422 5838 10422 5857 10422 5867 10423 5858 10423 5841 10423 5868 10424 5834 10424 5856 10424 5869 10425 5831 10425 1003 10425 5870 10426 5783 10426 5859 10426 5870 10427 5798 10427 5783 10427 5871 10428 5793 10428 5829 10428 5871 10429 5839 10429 5793 10429 5872 10430 5853 10430 5843 10430 5872 10431 5843 10431 877 10431 5873 10432 5809 10432 5849 10432 5679 10433 5847 10433 5813 10433 5874 10434 5864 10434 5862 10434 5874 10435 5862 10435 5866 10435 5875 10436 5846 10436 5831 10436 5679 10437 5813 10437 5832 10437 5876 10438 5850 10438 5615 10438 5875 10439 5831 10439 5869 10439 5877 10440 5864 10440 5874 10440 5876 10441 5816 10441 5803 10441 5878 10442 5860 10442 5834 10442 5876 10443 5803 10443 5850 10443 5879 10444 5804 10444 5837 10444 4291 10445 5800 10445 5847 10445 5879 10446 5844 10446 5804 10446 5878 10447 5834 10447 5868 10447 4291 10448 4290 10448 5800 10448 4291 10449 5847 10449 4292 10449 5879 10450 5837 10450 5865 10450 5880 10451 5859 10451 5853 10451 5881 10452 5829 10452 5854 10452 5880 10453 5853 10453 5872 10453 5881 10454 5871 10454 5829 10454 5882 10455 5851 10455 5846 10455 5883 10456 5860 10456 5878 10456 5882 10457 5846 10457 5875 10457 5883 10458 5866 10458 5860 10458 5884 10459 5816 10459 5876 10459 5883 10460 5874 10460 5866 10460 5884 10461 5820 10461 5816 10461 5885 10462 5849 10462 5858 10462 5886 10463 5810 10463 5848 10463 5886 10464 5848 10464 1351 10464 5886 10465 5856 10465 5810 10465 5885 10466 5873 10466 5849 10466 5887 10467 5859 10467 5880 10467 5888 10468 5806 10468 5822 10468 5887 10469 5870 10469 5859 10469 5889 10470 5855 10470 5851 10470 5888 10471 5854 10471 5769 10471 5890 10472 5820 10472 5884 10472 5889 10473 5851 10473 5882 10473 5888 10474 5769 10474 5806 10474 5890 10475 5826 10475 5820 10475 5891 10476 5869 10476 1003 10476 5891 10477 5875 10477 5869 10477 5892 10478 5874 10478 5883 10478 5619 10479 5885 10479 5858 10479 5893 10480 5779 10480 5839 10480 5893 10481 5842 10481 5779 10481 5614 10482 5876 10482 5615 10482 5619 10483 5858 10483 5867 10483 5894 10484 5877 10484 5874 10484 5894 10485 5874 10485 5892 10485 5589 10486 5826 10486 5890 10486 5600 10487 5891 10487 1003 10487 5589 10488 5830 10488 5826 10488 5895 10489 5863 10489 5855 10489 5634 10490 5870 10490 5887 10490 5895 10491 5855 10491 5889 10491 5895 10492 5865 10492 5863 10492 5896 10493 5822 10493 5864 10493 5588 10494 5830 10494 5589 10494 5896 10495 5888 10495 5822 10495 5588 10496 5861 10496 5830 10496 5897 10497 5865 10497 5895 10497 4300 10498 4299 10498 5817 10498 5898 10499 5893 10499 5839 10499 5899 10500 5875 10500 5891 10500 5630 10501 5884 10501 5876 10501 5898 10502 5839 10502 5871 10502 5900 10503 5881 10503 5854 10503 5630 10504 5876 10504 5614 10504 5900 10505 5888 10505 5896 10505 5899 10506 5882 10506 5875 10506 5635 10507 5899 10507 5891 10507 5623 10508 5861 10508 5588 10508 5900 10509 5854 10509 5888 10509 5623 10510 5805 10510 5861 10510 5623 10511 5832 10511 5805 10511 5635 10512 5891 10512 5600 10512 5901 10513 5856 10513 5886 10513 5638 10514 5890 10514 5884 10514 5901 10515 5886 10515 1351 10515 5638 10516 5884 10516 5630 10516 5902 10517 5844 10517 5879 10517 5902 10518 5867 10518 5844 10518 5903 10519 5896 10519 5864 10519 5583 10520 5865 10520 5897 10520 5903 10521 5864 10521 5877 10521 5583 10522 5902 10522 5879 10522 5583 10523 5879 10523 5865 10523 5590 10524 5589 10524 5890 10524 5904 10525 5882 10525 5899 10525 5904 10526 5889 10526 5882 10526 5590 10527 5890 10527 5638 10527 5573 10528 5900 10528 5896 10528 5905 10529 5836 10529 5798 10529 5904 10530 5899 10530 5635 10530 4307 10531 4300 10531 5842 10531 4307 10532 5842 10532 5893 10532 5906 10533 5901 10533 1351 10533 5905 10534 5870 10534 5634 10534 5906 10535 5868 10535 5856 10535 5905 10536 5798 10536 5870 10536 5907 10537 5889 10537 5904 10537 5906 10538 5856 10538 5901 10538 5605 10539 5871 10539 5881 10539 5605 10540 5898 10540 5871 10540 5907 10541 5895 10541 5889 10541 5624 10542 5623 10542 5588 10542 5640 10543 5904 10543 5635 10543 5908 10544 5903 10544 5877 10544 5909 10545 5872 10545 877 10545 5908 10546 5877 10546 5894 10546 5647 10547 5907 10547 5904 10547 5910 10548 5878 10548 5868 10548 5601 10549 5905 10549 5634 10549 5647 10550 5904 10550 5640 10550 5910 10551 5883 10551 5878 10551 5911 10552 5897 10552 5895 10552 5910 10553 5868 10553 5906 10553 5910 10554 5906 10554 1351 10554 5911 10555 5895 10555 5907 10555 5911 10556 5907 10556 5647 10556 5912 10557 5910 10557 1351 10557 5581 10558 5880 10558 5872 10558 5912 10559 5883 10559 5910 10559 5581 10560 5872 10560 5909 10560 5913 10561 5897 10561 5911 10561 5914 10562 5892 10562 5883 10562 5580 10563 5887 10563 5880 10563 5580 10564 5880 10564 5581 10564 5914 10565 5912 10565 1351 10565 5914 10566 5883 10566 5912 10566 5654 10567 5911 10567 5647 10567 5574 10568 5896 10568 5903 10568 5607 10569 5634 10569 5887 10569 5574 10570 5903 10570 5908 10570 5607 10571 5887 10571 5580 10571 5574 10572 5573 10572 5896 10572 4292 10573 5679 10573 4294 10573 4292 10574 5847 10574 5679 10574 5597 10575 5857 10575 5836 10575 5593 10576 5913 10576 5911 10576 5594 10577 5894 10577 5892 10577 5593 10578 5911 10578 5654 10578 5594 10579 5892 10579 5914 10579 5594 10580 5914 10580 1351 10580 5597 10581 5836 10581 5905 10581 5582 10582 5902 10582 5583 10582 5598 10583 5908 10583 5894 10583 5598 10584 5894 10584 5594 10584 5597 10585 5905 10585 5601 10585 4276 10586 5809 10586 5873 10586 5915 10587 877 10587 873 10587 4276 10588 4275 10588 5809 10588 5915 10589 5909 10589 877 10589 4276 10590 5873 10590 5885 10590 5586 10591 5574 10591 5908 10591 5620 10592 5619 10592 5867 10592 5620 10593 5902 10593 5582 10593 5622 10594 5832 10594 5623 10594 5620 10595 5867 10595 5902 10595 5606 10596 5605 10596 5881 10596 5606 10597 5881 10597 5900 10597 5622 10598 5679 10598 5832 10598 5596 10599 5615 10599 5857 10599 5576 10600 5897 10600 5913 10600 5578 10601 5900 10601 5573 10601 5576 10602 5583 10602 5897 10602 5578 10603 5606 10603 5900 10603 4277 10604 4276 10604 5885 10604 4277 10605 5885 10605 5619 10605 5603 10606 5908 10606 5598 10606 5584 10607 5620 10607 5582 10607 5603 10608 5586 10608 5908 10608 5596 10609 5857 10609 5597 10609 5577 10610 5576 10610 5913 10610 5627 10611 5909 10611 5915 10611 4308 10612 4307 10612 5893 10612 4308 10613 5605 10613 4303 10613 5627 10614 5581 10614 5909 10614 4308 10615 5898 10615 5605 10615 5627 10616 5915 10616 873 10616 5577 10617 5913 10617 5593 10617 4308 10618 5893 10618 5898 10618 5572 10619 5578 10619 5573 10619 5579 10620 5581 10620 5627 10620 5916 10621 5917 10621 5918 10621 5919 10622 5920 10622 5921 10622 5922 10623 5923 10623 5924 10623 5922 10624 5925 10624 5923 10624 5926 10625 4246 10625 5927 10625 5926 10626 5928 10626 5929 10626 5926 10627 5927 10627 5928 10627 5930 10628 5931 10628 5925 10628 5932 10629 5933 10629 5934 10629 5930 10630 5925 10630 5922 10630 5932 10631 5935 10631 5933 10631 5936 10632 1036 10632 1032 10632 5937 10633 5931 10633 5930 10633 5936 10634 5938 10634 1036 10634 5937 10635 5939 10635 5931 10635 5940 10636 5916 10636 5941 10636 5942 10637 5943 10637 5944 10637 5942 10638 5944 10638 5945 10638 5942 10639 5934 10639 5943 10639 5940 10640 5941 10640 5946 10640 5947 10641 5929 10641 5917 10641 5947 10642 5917 10642 5916 10642 5948 10643 5949 10643 5938 10643 5948 10644 5938 10644 5936 10644 5950 10645 4360 10645 5951 10645 5952 10646 5929 10646 5947 10646 5950 10647 5951 10647 5935 10647 5952 10648 4247 10648 4246 10648 5950 10649 5935 10649 5932 10649 5952 10650 5926 10650 5929 10650 5952 10651 4246 10651 5926 10651 5953 10652 5947 10652 5916 10652 5954 10653 5955 10653 5956 10653 5954 10654 5956 10654 5919 10654 5957 10655 5946 10655 5939 10655 5957 10656 5940 10656 5946 10656 5958 10657 5959 10657 5955 10657 5960 10658 5916 10658 5940 10658 5960 10659 5953 10659 5916 10659 5958 10660 5955 10660 5954 10660 5961 10661 5940 10661 5957 10661 5961 10662 5960 10662 5940 10662 5962 10663 5919 10663 5949 10663 5963 10664 5957 10664 5939 10664 5963 10665 5939 10665 5937 10665 5964 10666 5942 10666 5945 10666 5965 10667 5966 10667 1026 10667 5965 10668 5924 10668 5966 10668 5967 10669 5968 10669 5959 10669 5969 10670 5922 10670 5924 10670 5967 10671 5959 10671 5958 10671 5969 10672 5924 10672 5965 10672 5970 10673 5953 10673 5960 10673 5971 10674 5932 10674 5934 10674 5971 10675 5934 10675 5942 10675 5972 10676 5948 10676 5936 10676 5973 10677 5930 10677 5922 10677 5974 10678 5968 10678 5967 10678 5973 10679 5922 10679 5969 10679 5975 10680 4247 10680 5952 10680 5975 10681 4248 10681 4247 10681 5975 10682 4253 10682 4248 10682 5975 10683 5952 10683 5947 10683 5974 10684 5976 10684 5968 10684 5977 10685 5930 10685 5973 10685 5978 10686 5950 10686 5932 10686 5977 10687 5937 10687 5930 10687 5978 10688 5932 10688 5971 10688 5978 10689 4360 10689 5950 10689 5979 10690 5972 10690 5936 10690 5980 10691 5965 10691 1026 10691 5980 10692 5969 10692 5965 10692 5979 10693 5936 10693 1032 10693 5981 10694 5969 10694 5980 10694 5981 10695 5973 10695 5969 10695 5982 10696 5976 10696 5974 10696 5982 10697 5945 10697 5976 10697 5983 10698 5961 10698 5957 10698 5984 10699 5954 10699 5919 10699 5983 10700 5957 10700 5963 10700 5984 10701 5958 10701 5954 10701 5985 10702 5963 10702 5937 10702 5984 10703 5919 10703 5962 10703 5985 10704 5937 10704 5977 10704 5986 10705 4254 10705 4253 10705 5987 10706 5958 10706 5984 10706 5986 10707 5947 10707 5953 10707 5986 10708 5953 10708 5970 10708 5986 10709 4253 10709 5975 10709 5986 10710 5975 10710 5947 10710 5988 10711 5973 10711 5981 10711 5989 10712 5962 10712 5949 10712 5988 10713 5977 10713 5973 10713 5990 10714 5960 10714 5961 10714 5989 10715 5949 10715 5948 10715 5990 10716 5970 10716 5960 10716 5991 10717 5985 10717 5977 10717 5992 10718 5942 10718 5964 10718 5991 10719 5977 10719 5988 10719 5992 10720 5971 10720 5942 10720 5993 10721 1026 10721 1027 10721 5994 10722 5967 10722 5958 10722 5993 10723 5980 10723 1026 10723 5995 10724 5981 10724 5980 10724 5995 10725 5988 10725 5981 10725 5995 10726 5980 10726 5993 10726 5994 10727 5958 10727 5987 10727 5996 10728 5985 10728 5991 10728 5997 10729 5967 10729 5994 10729 5998 10730 1027 10730 1074 10730 5997 10731 5974 10731 5967 10731 5998 10732 5993 10732 1027 10732 5998 10733 5995 10733 5993 10733 5999 10734 5988 10734 5995 10734 6000 10735 5989 10735 5948 10735 6000 10736 5948 10736 5972 10736 6001 10737 5982 10737 5974 10737 6001 10738 5974 10738 5997 10738 6002 10739 5988 10739 5999 10739 6002 10740 5991 10740 5988 10740 6003 10741 5961 10741 5983 10741 6004 10742 6000 10742 5972 10742 6004 10743 5972 10743 5979 10743 6003 10744 5990 10744 5961 10744 6005 10745 5998 10745 1074 10745 6005 10746 5999 10746 5995 10746 6006 10747 5984 10747 5962 10747 6005 10748 5995 10748 5998 10748 6006 10749 5962 10749 5989 10749 6007 10750 5996 10750 5991 10750 6007 10751 5991 10751 6002 10751 6008 10752 6005 10752 1074 10752 6008 10753 6002 10753 5999 10753 6008 10754 5999 10754 6005 10754 6009 10755 5984 10755 6006 10755 6010 10756 6007 10756 6002 10756 6009 10757 5987 10757 5984 10757 6010 10758 6002 10758 6008 10758 6011 10759 944 10759 941 10759 6011 10760 946 10760 944 10760 6012 10761 5978 10761 5971 10761 6012 10762 5971 10762 5992 10762 6013 10763 5963 10763 5985 10763 6014 10764 946 10764 6011 10764 6015 10765 5994 10765 5987 10765 6016 10766 946 10766 6014 10766 6013 10767 5983 10767 5963 10767 6013 10768 5985 10768 5996 10768 6015 10769 5987 10769 6009 10769 6017 10770 5986 10770 5970 10770 6018 10771 946 10771 6016 10771 6018 10772 1173 10772 946 10772 6017 10773 4255 10773 4254 10773 6017 10774 4254 10774 5986 10774 6019 10775 941 10775 939 10775 6020 10776 6013 10776 5996 10776 6021 10777 6012 10777 5992 10777 6019 10778 6011 10778 941 10778 6019 10779 6014 10779 6011 10779 6022 10780 5994 10780 6015 10780 6022 10781 5997 10781 5994 10781 6023 10782 6016 10782 6014 10782 6024 10783 6003 10783 5983 10783 6023 10784 6019 10784 939 10784 6023 10785 6014 10785 6019 10785 6025 10786 6006 10786 5989 10786 6024 10787 6013 10787 6020 10787 6025 10788 5989 10788 6000 10788 6024 10789 5983 10789 6013 10789 6026 10790 6018 10790 6016 10790 6027 10791 5970 10791 5990 10791 6026 10792 6016 10792 6023 10792 6027 10793 4255 10793 6017 10793 6027 10794 6017 10794 5970 10794 6028 10795 6020 10795 5996 10795 6029 10796 6009 10796 6006 10796 6029 10797 6006 10797 6025 10797 6030 10798 1173 10798 6018 10798 6028 10799 5996 10799 6007 10799 6031 10800 6023 10800 939 10800 6031 10801 939 10801 935 10801 6031 10802 6026 10802 6023 10802 6032 10803 6000 10803 6004 10803 6032 10804 6025 10804 6000 10804 6033 10805 6030 10805 6018 10805 6033 10806 6018 10806 6026 10806 6034 10807 6024 10807 6020 10807 6035 10808 6007 10808 6010 10808 6036 10809 6029 10809 6025 10809 6037 10810 1173 10810 6030 10810 6036 10811 6025 10811 6032 10811 6035 10812 6028 10812 6007 10812 6038 10813 1173 10813 6037 10813 4255 10814 4256 10814 6039 10814 6040 10815 6001 10815 5997 10815 6039 10816 5990 10816 6003 10816 6040 10817 5997 10817 6022 10817 6039 10818 6027 10818 5990 10818 6039 10819 4255 10819 6027 10819 6041 10820 6026 10820 6031 10820 6042 10821 5964 10821 5945 10821 6043 10822 6020 10822 6028 10822 6043 10823 6034 10823 6020 10823 6044 10824 1173 10824 6038 10824 6045 10825 1173 10825 6044 10825 6046 10826 6003 10826 6024 10826 6046 10827 6039 10827 6003 10827 6042 10828 5945 10828 5982 10828 6046 10829 6024 10829 6034 10829 6047 10830 6015 10830 6009 10830 6047 10831 6009 10831 6029 10831 6048 10832 6037 10832 6030 10832 6049 10833 6028 10833 6035 10833 6049 10834 6043 10834 6028 10834 6048 10835 6030 10835 6033 10835 6050 10836 6008 10836 1074 10836 6051 10837 6022 10837 6015 10837 6050 10838 6010 10838 6008 10838 6051 10839 6015 10839 6047 10839 6052 10840 6035 10840 6010 10840 6053 10841 6029 10841 6036 10841 6054 10842 6037 10842 6048 10842 6053 10843 6047 10843 6029 10843 6054 10844 6038 10844 6037 10844 6052 10845 6010 10845 6050 10845 6055 10846 6051 10846 6047 10846 6056 10847 1173 10847 6045 10847 6057 10848 6034 10848 6043 10848 6055 10849 6047 10849 6053 10849 6057 10850 6046 10850 6034 10850 6058 10851 6044 10851 6038 10851 6059 10852 6022 10852 6051 10852 6060 10853 6057 10853 6043 10853 6058 10854 6038 10854 6054 10854 6059 10855 6040 10855 6022 10855 6060 10856 6043 10856 6049 10856 6061 10857 6051 10857 6055 10857 6061 10858 6059 10858 6051 10858 6062 10859 6044 10859 6058 10859 6063 10860 6050 10860 1074 10860 6063 10861 6052 10861 6050 10861 6062 10862 6045 10862 6044 10862 6064 10863 6060 10863 6049 10863 6065 10864 5992 10864 5964 10864 6066 10865 6033 10865 6026 10865 6065 10866 5964 10866 6042 10866 6066 10867 6026 10867 6041 10867 6067 10868 6063 10868 1074 10868 6068 10869 1074 10869 1072 10869 6069 10870 5982 10870 6001 10870 6070 10871 6056 10871 6045 10871 6070 10872 6045 10872 6062 10872 6068 10873 6067 10873 1074 10873 6071 10874 4256 10874 6039 10874 6071 10875 6046 10875 6057 10875 6069 10876 6042 10876 5982 10876 6071 10877 6039 10877 6046 10877 4362 10878 4360 10878 5978 10878 6072 10879 6052 10879 6063 10879 4362 10880 5978 10880 6012 10880 6073 10881 6031 10881 935 10881 6073 10882 6041 10882 6031 10882 6074 10883 6048 10883 6033 10883 6072 10884 6035 10884 6052 10884 6075 10885 6042 10885 6069 10885 6074 10886 6033 10886 6066 10886 6072 10887 6049 10887 6035 10887 6075 10888 6065 10888 6042 10888 6076 10889 6071 10889 6057 10889 6076 10890 4259 10890 4256 10890 6077 10891 6040 10891 6059 10891 6076 10892 4256 10892 6071 10892 6078 10893 1072 10893 1071 10893 6077 10894 6001 10894 6040 10894 6079 10895 6048 10895 6074 10895 6078 10896 6068 10896 1072 10896 6077 10897 6069 10897 6001 10897 6080 10898 4363 10898 4362 10898 6079 10899 6054 10899 6048 10899 6080 10900 6012 10900 6021 10900 6081 10901 6064 10901 6049 10901 6080 10902 4362 10902 6012 10902 6081 10903 6049 10903 6072 10903 6082 10904 1173 10904 6056 10904 6082 10905 1167 10905 1173 10905 6083 10906 6021 10906 5992 10906 6082 10907 6056 10907 6070 10907 6083 10908 5992 10908 6065 10908 6083 10909 6065 10909 6075 10909 6084 10910 6063 10910 6067 10910 6085 10911 6058 10911 6054 10911 6085 10912 6054 10912 6079 10912 6084 10913 6081 10913 6072 10913 6086 10914 6077 10914 6059 10914 6084 10915 6072 10915 6063 10915 6087 10916 6057 10916 6060 10916 6088 10917 6059 10917 6061 10917 6088 10918 6086 10918 6059 10918 6089 10919 6062 10919 6058 10919 6087 10920 6076 10920 6057 10920 6089 10921 6070 10921 6062 10921 6087 10922 4259 10922 6076 10922 6089 10923 6058 10923 6085 10923 6087 10924 4260 10924 4259 10924 6090 10925 6067 10925 6068 10925 6091 10926 6075 10926 6069 10926 6092 10927 6066 10927 6041 10927 6090 10928 6084 10928 6067 10928 6091 10929 6069 10929 6077 10929 6092 10930 6041 10930 6073 10930 6093 10931 6060 10931 6064 10931 6093 10932 4260 10932 6087 10932 6093 10933 6087 10933 6060 10933 6094 10934 6070 10934 6089 10934 6095 10935 5979 10935 1032 10935 6096 10936 935 10936 932 10936 6097 10937 6090 10937 6068 10937 6095 10938 6004 10938 5979 10938 6096 10939 6073 10939 935 10939 6098 10940 6083 10940 6075 10940 6098 10941 6075 10941 6091 10941 6099 10942 6082 10942 6070 10942 6100 10943 6084 10943 6090 10943 6100 10944 6081 10944 6084 10944 6101 10945 6100 10945 6090 10945 6102 10946 6095 10946 1032 10946 6101 10947 6090 10947 6097 10947 6103 10948 6092 10948 6073 10948 6103 10949 6073 10949 6096 10949 6104 10950 6064 10950 6081 10950 6105 10951 1167 10951 6082 10951 6106 10952 6077 10952 6086 10952 6106 10953 6091 10953 6077 10953 6107 10954 6074 10954 6066 10954 6104 10955 6081 10955 6100 10955 6104 10956 6093 10956 6064 10956 6107 10957 6066 10957 6092 10957 6108 10958 6068 10958 6078 10958 6109 10959 6106 10959 6086 10959 6108 10960 6097 10960 6068 10960 6109 10961 6086 10961 6088 10961 6110 10962 6079 10962 6074 10962 6111 10963 6101 10963 6097 10963 6110 10964 6074 10964 6107 10964 6112 10965 6032 10965 6004 10965 6113 10966 6100 10966 6101 10966 6112 10967 6004 10967 6095 10967 6114 10968 6085 10968 6079 10968 6113 10969 6104 10969 6100 10969 6114 10970 6079 10970 6110 10970 6115 10971 6097 10971 6108 10971 6115 10972 6111 10972 6097 10972 6116 10973 6082 10973 6099 10973 6116 10974 6105 10974 6082 10974 6117 10975 6032 10975 6112 10975 6118 10976 6101 10976 6111 10976 6119 10977 932 10977 928 10977 6118 10978 6113 10978 6101 10978 6117 10979 6036 10979 6032 10979 6120 10980 6118 10980 6111 10980 6121 10981 6089 10981 6085 10981 6122 10982 1070 10982 1068 10982 6123 10983 6102 10983 1032 10983 6121 10984 6094 10984 6089 10984 6124 10985 6053 10985 6036 10985 6121 10986 6085 10986 6114 10986 6125 10987 6078 10987 1071 10987 6125 10988 6108 10988 6078 10988 6126 10989 6103 10989 6096 10989 6127 10990 1071 10990 1070 10990 6126 10991 6096 10991 932 10991 6126 10992 932 10992 6119 10992 6124 10993 6036 10993 6117 10993 6127 10994 6125 10994 1071 10994 6128 10995 6112 10995 6095 10995 6129 10996 1067 10996 1066 10996 6128 10997 6117 10997 6112 10997 6129 10998 1068 10998 1067 10998 6129 10999 6122 10999 1068 10999 6128 11000 6095 11000 6102 11000 6130 11001 6094 11001 6121 11001 6131 11002 6098 11002 6091 11002 4260 11003 4261 11003 6132 11003 6093 11004 4260 11004 6132 11004 6132 11005 6093 11005 6104 11005 6131 11006 6091 11006 6106 11006 6132 11007 6104 11007 6113 11007 6133 11008 6107 11008 6092 11008 6134 11009 6127 11009 1070 11009 6133 11010 6092 11010 6103 11010 6134 11011 1070 11011 6122 11011 6135 11012 6117 11012 6128 11012 6136 11013 6111 11013 6115 11013 6136 11014 6120 11014 6111 11014 6137 11015 6119 11015 928 11015 6138 11016 6133 11016 6103 11016 6139 11017 1066 11017 6140 11017 6139 11018 6129 11018 1066 11018 6141 11019 6053 11019 6124 11019 6138 11020 6103 11020 6126 11020 6139 11021 6122 11021 6129 11021 6141 11022 6055 11022 6053 11022 6139 11023 6134 11023 6122 11023 6142 11024 6061 11024 6055 11024 6143 11025 6115 11025 6108 11025 6144 11026 6070 11026 6094 11026 6144 11027 6099 11027 6070 11027 6144 11028 6116 11028 6099 11028 6143 11029 6108 11029 6125 11029 6145 11030 4261 11030 6132 11030 6142 11031 6055 11031 6141 11031 6146 11032 1164 11032 1167 11032 6145 11033 6132 11033 6113 11033 6146 11034 1167 11034 6105 11034 6145 11035 6113 11035 6118 11035 6146 11036 6105 11036 6116 11036 6147 11037 6145 11037 6118 11037 6148 11038 6126 11038 6119 11038 6148 11039 6119 11039 6137 11039 6147 11040 4262 11040 4261 11040 6149 11041 6124 11041 6117 11041 6149 11042 6117 11042 6135 11042 6147 11043 4261 11043 6145 11043 6147 11044 6118 11044 6120 11044 6150 11045 6120 11045 6136 11045 6151 11046 6138 11046 6126 11046 6150 11047 4262 11047 6147 11047 6150 11048 4263 11048 4262 11048 6151 11049 6126 11049 6148 11049 6150 11050 6147 11050 6120 11050 6152 11051 4364 11051 4363 11051 6152 11052 4363 11052 6080 11052 6152 11053 6080 11053 6021 11053 6153 11054 6125 11054 6127 11054 6152 11055 6021 11055 6083 11055 6153 11056 6143 11056 6125 11056 6154 11057 6110 11057 6107 11057 6155 11058 6153 11058 6127 11058 6154 11059 6107 11059 6133 11059 6156 11060 6141 11060 6124 11060 6155 11061 6127 11061 6134 11061 6156 11062 6124 11062 6149 11062 6157 11063 6155 11063 6134 11063 6158 11064 6110 11064 6154 11064 6157 11065 6139 11065 6140 11065 6159 11066 6106 11066 6109 11066 6157 11067 6134 11067 6139 11067 6160 11068 4263 11068 6150 11068 6159 11069 6131 11069 6106 11069 6158 11070 6114 11070 6110 11070 6160 11071 6150 11071 6136 11071 6161 11072 6138 11072 6151 11072 6160 11073 4265 11073 4263 11073 6162 11074 6159 11074 6109 11074 6160 11075 6136 11075 6115 11075 6160 11076 6115 11076 6143 11076 6163 11077 6102 11077 6123 11077 6164 11078 6160 11078 6143 11078 6163 11079 6128 11079 6102 11079 6165 11080 1164 11080 6146 11080 6163 11081 6135 11081 6128 11081 6164 11082 6143 11082 6153 11082 6165 11083 6146 11083 6116 11083 6166 11084 6153 11084 6155 11084 6167 11085 6135 11085 6163 11085 6168 11086 6116 11086 6144 11086 6168 11087 6165 11087 6116 11087 6166 11088 6164 11088 6153 11088 6169 11089 6121 11089 6114 11089 6170 11090 6166 11090 6155 11090 6170 11091 6157 11091 6140 11091 6170 11092 6140 11092 6171 11092 6170 11093 6155 11093 6157 11093 6172 11094 4265 11094 6160 11094 6172 11095 6160 11095 6164 11095 6169 11096 6114 11096 6158 11096 6173 11097 6142 11097 6141 11097 6172 11098 6164 11098 6166 11098 6173 11099 6141 11099 6156 11099 6174 11100 4265 11100 6172 11100 6174 11101 6166 11101 6170 11101 6175 11102 6154 11102 6133 11102 6174 11103 6172 11103 6166 11103 6176 11104 6171 11104 4265 11104 6176 11105 4265 11105 6174 11105 6177 11106 6135 11106 6167 11106 6175 11107 6133 11107 6138 11107 6176 11108 6170 11108 6171 11108 6175 11109 6138 11109 6161 11109 6176 11110 6174 11110 6170 11110 6177 11111 6156 11111 6149 11111 6177 11112 6149 11112 6135 11112 6178 11113 6156 11113 6177 11113 6179 11114 6130 11114 6121 11114 6179 11115 6121 11115 6169 11115 6180 11116 6083 11116 6098 11116 4364 11117 4365 11117 6180 11117 6180 11118 4364 11118 6152 11118 6181 11119 6130 11119 6179 11119 6180 11120 6152 11120 6083 11120 6182 11121 6137 11121 928 11121 6182 11122 6148 11122 6137 11122 6183 11123 6156 11123 6178 11123 6183 11124 6173 11124 6156 11124 6184 11125 6144 11125 6094 11125 6184 11126 6094 11126 6130 11126 6184 11127 6130 11127 6181 11127 6185 11128 6161 11128 6151 11128 6185 11129 6151 11129 6148 11129 6186 11130 6123 11130 1032 11130 6186 11131 6163 11131 6123 11131 6185 11132 6148 11132 6182 11132 6187 11133 6175 11133 6161 11133 6188 11134 6088 11134 6061 11134 6188 11135 6061 11135 6142 11135 6189 11136 4365 11136 6180 11136 6190 11137 6182 11137 928 11137 6189 11138 6098 11138 6131 11138 6189 11139 4366 11139 4365 11139 6189 11140 6180 11140 6098 11140 6191 11141 6186 11141 1032 11141 6192 11142 6154 11142 6175 11142 6192 11143 6158 11143 6154 11143 6193 11144 6142 11144 6173 11144 6192 11145 6175 11145 6187 11145 6193 11146 6173 11146 6183 11146 6194 11147 6169 11147 6158 11147 6193 11148 6188 11148 6142 11148 6195 11149 6167 11149 6163 11149 6194 11150 6158 11150 6192 11150 6195 11151 6163 11151 6186 11151 6196 11152 6161 11152 6185 11152 6197 11153 6185 11153 6182 11153 6198 11154 6177 11154 6167 11154 6197 11155 6182 11155 6190 11155 6199 11156 1164 11156 6165 11156 6198 11157 6167 11157 6195 11157 6199 11158 6165 11158 6168 11158 6200 11159 6144 11159 6184 11159 6200 11160 6168 11160 6144 11160 6200 11161 6199 11161 6168 11161 6201 11162 6088 11162 6188 11162 6201 11163 6109 11163 6088 11163 6202 11164 6179 11164 6169 11164 6203 11165 4245 11165 4366 11165 6203 11166 6189 11166 6131 11166 6203 11167 4366 11167 6189 11167 6202 11168 6169 11168 6194 11168 6203 11169 6131 11169 6159 11169 6204 11170 4245 11170 6203 11170 6204 11171 6203 11171 6159 11171 6204 11172 6159 11172 6162 11172 5920 11173 6196 11173 6185 11173 6205 11174 6178 11174 6177 11174 5920 11175 6185 11175 6197 11175 6205 11176 6177 11176 6198 11176 6206 11177 6181 11177 6179 11177 6206 11178 6179 11178 6202 11178 6207 11179 6195 11179 6186 11179 6207 11180 6186 11180 6191 11180 6208 11181 6192 11181 6187 11181 6208 11182 6194 11182 6192 11182 6209 11183 6195 11183 6207 11183 6209 11184 6198 11184 6195 11184 6210 11185 6183 11185 6178 11185 6211 11186 6194 11186 6208 11186 6210 11187 6178 11187 6205 11187 6211 11188 6202 11188 6194 11188 6212 11189 6181 11189 6206 11189 6213 11190 6193 11190 6183 11190 6214 11191 6201 11191 6188 11191 6215 11192 6187 11192 6161 11192 6215 11193 6161 11193 6196 11193 6214 11194 6188 11194 6193 11194 6216 11195 6183 11195 6210 11195 6217 11196 6202 11196 6211 11196 6216 11197 6213 11197 6183 11197 6217 11198 6206 11198 6202 11198 6218 11199 6205 11199 6198 11199 6219 11200 6181 11200 6212 11200 6218 11201 6198 11201 6209 11201 6219 11202 6184 11202 6181 11202 6219 11203 6200 11203 6184 11203 6220 11204 6205 11204 6218 11204 6221 11205 6212 11205 6206 11205 6220 11206 6210 11206 6205 11206 6220 11207 6216 11207 6210 11207 6221 11208 6206 11208 6217 11208 5943 11209 6212 11209 6221 11209 6222 11210 6216 11210 6220 11210 5956 11211 6215 11211 6196 11211 6223 11212 6191 11212 1032 11212 6223 11213 6207 11213 6191 11213 5956 11214 6196 11214 5920 11214 6224 11215 6193 11215 6213 11215 6225 11216 4360 11216 1164 11216 6224 11217 6214 11217 6193 11217 6225 11218 1164 11218 6199 11218 6225 11219 6199 11219 6200 11219 6226 11220 6109 11220 6201 11220 6226 11221 6204 11221 6162 11221 6226 11222 6201 11222 6214 11222 6227 11223 6208 11223 6187 11223 6226 11224 6162 11224 6109 11224 6227 11225 6187 11225 6215 11225 6228 11226 6211 11226 6208 11226 5928 11227 6214 11227 6224 11227 5928 11228 6226 11228 6214 11228 6228 11229 6208 11229 6227 11229 6229 11230 1032 11230 1026 11230 6229 11231 6223 11231 1032 11231 6230 11232 6209 11232 6207 11232 6231 11233 6200 11233 6219 11233 6231 11234 6225 11234 6200 11234 6230 11235 6207 11235 6223 11235 6232 11236 928 11236 1036 11236 6232 11237 6190 11237 928 11237 6233 11238 6218 11238 6209 11238 6233 11239 6209 11239 6230 11239 5955 11240 6227 11240 6215 11240 5918 11241 6224 11241 6213 11241 5918 11242 6213 11242 6216 11242 5955 11243 6215 11243 5956 11243 6234 11244 6221 11244 6217 11244 6234 11245 6211 11245 6228 11245 6234 11246 6217 11246 6211 11246 6235 11247 6220 11247 6218 11247 5959 11248 6228 11248 6227 11248 6235 11249 6218 11249 6233 11249 5959 11250 6227 11250 5955 11250 6236 11251 6220 11251 6235 11251 6236 11252 6222 11252 6220 11252 6237 11253 6221 11253 6234 11253 6238 11254 6190 11254 6232 11254 5929 11255 5928 11255 6224 11255 6238 11256 6197 11256 6190 11256 5933 11257 6219 11257 6212 11257 6239 11258 6223 11258 6229 11258 5933 11259 6212 11259 5943 11259 5933 11260 6231 11260 6219 11260 6239 11261 6230 11261 6223 11261 5944 11262 5943 11262 6221 11262 5946 11263 6222 11263 6236 11263 5944 11264 6221 11264 6237 11264 5923 11265 6230 11265 6239 11265 5968 11266 6234 11266 6228 11266 5923 11267 6233 11267 6230 11267 5941 11268 5918 11268 6216 11268 5968 11269 6228 11269 5959 11269 5941 11270 6216 11270 6222 11270 5941 11271 6222 11271 5946 11271 5917 11272 5929 11272 6224 11272 5921 11273 6197 11273 6238 11273 5917 11274 6224 11274 5918 11274 5921 11275 5920 11275 6197 11275 5925 11276 6235 11276 6233 11276 5925 11277 6233 11277 5923 11277 5976 11278 6237 11278 6234 11278 5976 11279 6234 11279 5968 11279 5931 11280 6235 11280 5925 11280 5945 11281 5944 11281 6237 11281 5945 11282 6237 11282 5976 11282 5931 11283 6236 11283 6235 11283 5939 11284 6236 11284 5931 11284 5934 11285 5933 11285 5943 11285 5939 11286 5946 11286 6236 11286 5935 11287 6231 11287 5933 11287 5951 11288 6225 11288 6231 11288 5966 11289 6229 11289 1026 11289 5951 11290 4360 11290 6225 11290 5966 11291 6239 11291 6229 11291 5951 11292 6231 11292 5935 11292 5924 11293 5923 11293 6239 11293 5938 11294 6238 11294 6232 11294 5924 11295 6239 11295 5966 11295 5938 11296 6232 11296 1036 11296 4245 11297 4246 11297 5927 11297 5927 11298 6204 11298 6226 11298 5927 11299 6226 11299 5928 11299 5927 11300 4245 11300 6204 11300 5916 11301 5918 11301 5941 11301 5949 11302 5921 11302 6238 11302 5949 11303 6238 11303 5938 11303 5919 11304 5921 11304 5949 11304 5919 11305 5956 11305 5920 11305 6240 11306 6241 11306 6242 11306 6240 11307 6243 11307 6241 11307 6244 11308 6245 11308 6246 11308 6240 11309 6247 11309 6243 11309 6244 11310 6248 11310 6245 11310 6240 11311 6249 11311 6247 11311 6250 11312 985 11312 6251 11312 6252 11313 6253 11313 6254 11313 6252 11314 6255 11314 6253 11314 6252 11315 6254 11315 6256 11315 6257 11316 6251 11316 6249 11316 6257 11317 6250 11317 6251 11317 6258 11318 6240 11318 6242 11318 6258 11319 6249 11319 6240 11319 6259 11320 6246 11320 6260 11320 6259 11321 6244 11321 6246 11321 6261 11322 986 11322 985 11322 6262 11323 982 11323 979 11323 6261 11324 985 11324 6250 11324 6262 11325 6244 11325 6259 11325 6262 11326 979 11326 6248 11326 6262 11327 6248 11327 6244 11327 6263 11328 986 11328 6261 11328 6264 11329 6265 11329 6241 11329 6264 11330 6266 11330 6265 11330 6263 11331 6250 11331 6257 11331 6263 11332 6261 11332 6250 11332 6264 11333 6267 11333 6266 11333 6264 11334 6268 11334 6267 11334 6269 11335 6257 11335 6249 11335 6269 11336 6258 11336 6242 11336 6269 11337 6249 11337 6258 11337 6269 11338 6263 11338 6257 11338 6270 11339 6259 11339 6260 11339 6271 11340 6269 11340 6242 11340 6271 11341 6263 11341 6269 11341 6272 11342 6263 11342 6271 11342 6273 11343 6259 11343 6270 11343 6272 11344 988 11344 986 11344 6273 11345 982 11345 6262 11345 6272 11346 6242 11346 988 11346 6272 11347 986 11347 6263 11347 6273 11348 6262 11348 6259 11348 6272 11349 6271 11349 6242 11349 6274 11350 6260 11350 6255 11350 6274 11351 6255 11351 6252 11351 6275 11352 6274 11352 6252 11352 6275 11353 6252 11353 6256 11353 6276 11354 6275 11354 6256 11354 6276 11355 6256 11355 6268 11355 6276 11356 6268 11356 6264 11356 6277 11357 6273 11357 6270 11357 6278 11358 983 11358 982 11358 6278 11359 982 11359 6273 11359 990 11360 988 11360 6242 11360 6279 11361 5682 11361 4268 11361 6279 11362 4268 11362 6280 11362 6281 11363 6274 11363 6275 11363 6282 11364 6270 11364 6260 11364 6282 11365 6274 11365 6281 11365 6283 11366 6279 11366 6280 11366 6282 11367 6260 11367 6274 11367 6284 11368 983 11368 6278 11368 6284 11369 6273 11369 6277 11369 6284 11370 6278 11370 6273 11370 6285 11371 6283 11371 6280 11371 6286 11372 6281 11372 6275 11372 6286 11373 6275 11373 6276 11373 6253 11374 6285 11374 6280 11374 6287 11375 6280 11375 6288 11375 6289 11376 6270 11376 6282 11376 6289 11377 6277 11377 6270 11377 6290 11378 5676 11378 5682 11378 6291 11379 6276 11379 6264 11379 6291 11380 6264 11380 6241 11380 6290 11381 5682 11381 6279 11381 6292 11382 6281 11382 6286 11382 6292 11383 6289 11383 6282 11383 6267 11384 6287 11384 6288 11384 6292 11385 6282 11385 6281 11385 6293 11386 6284 11386 6277 11386 6294 11387 978 11387 5676 11387 6293 11388 6277 11388 6289 11388 6294 11389 5676 11389 6290 11389 6295 11390 6279 11390 6283 11390 6296 11391 6292 11391 6286 11391 6295 11392 6290 11392 6279 11392 6297 11393 6289 11393 6292 11393 6295 11394 6283 11394 6285 11394 6297 11395 6293 11395 6289 11395 6297 11396 6292 11396 6296 11396 6298 11397 6286 11397 6276 11397 6298 11398 6276 11398 6291 11398 6254 11399 6253 11399 6280 11399 6298 11400 6291 11400 6241 11400 6254 11401 6280 11401 6287 11401 6299 11402 6285 11402 6253 11402 6300 11403 6297 11403 6296 11403 6299 11404 6295 11404 6285 11404 6301 11405 985 11405 983 11405 6265 11406 6288 11406 6266 11406 6301 11407 983 11407 6284 11407 6301 11408 6284 11408 6293 11408 6288 11409 6267 11409 6266 11409 6302 11410 6301 11410 6293 11410 6245 11411 6294 11411 6290 11411 6302 11412 6293 11412 6297 11412 6245 11413 6290 11413 6295 11413 6245 11414 6295 11414 6299 11414 6255 11415 6299 11415 6253 11415 6248 11416 979 11416 978 11416 6247 11417 6297 11417 6300 11417 6248 11418 6294 11418 6245 11418 6247 11419 6302 11419 6297 11419 6303 11420 6286 11420 6298 11420 6248 11421 978 11421 6294 11421 6303 11422 6296 11422 6286 11422 6303 11423 6298 11423 6241 11423 6256 11424 6254 11424 6287 11424 6251 11425 985 11425 6301 11425 6251 11426 6301 11426 6302 11426 6268 11427 6287 11427 6267 11427 6268 11428 6256 11428 6287 11428 6243 11429 6300 11429 6296 11429 6243 11430 6303 11430 6241 11430 6243 11431 6247 11431 6300 11431 6243 11432 6296 11432 6303 11432 6246 11433 6245 11433 6299 11433 6246 11434 6299 11434 6255 11434 6249 11435 6302 11435 6247 11435 6249 11436 6251 11436 6302 11436 6260 11437 6246 11437 6255 11437 6304 11438 6305 11438 6306 11438 6304 11439 6307 11439 6305 11439 6308 11440 6309 11440 6310 11440 6308 11441 6310 11441 6311 11441 6312 11442 6304 11442 6306 11442 6312 11443 6306 11443 6313 11443 6314 11444 6315 11444 6316 11444 6314 11445 6317 11445 6315 11445 6318 11446 6311 11446 6317 11446 6318 11447 6317 11447 6314 11447 6319 11448 6320 11448 6309 11448 6319 11449 6309 11449 6308 11449 6321 11450 6307 11450 6304 11450 6321 11451 6316 11451 6307 11451 6322 11452 6304 11452 6312 11452 6322 11453 6321 11453 6304 11453 6323 11454 6313 11454 6324 11454 6323 11455 6312 11455 6313 11455 6325 11456 6311 11456 6318 11456 6325 11457 6308 11457 6311 11457 1053 11458 6326 11458 1057 11458 6327 11459 6326 11459 6320 11459 6328 11460 6329 11460 6330 11460 6327 11461 6320 11461 6319 11461 6328 11462 6330 11462 6331 11462 6332 11463 6323 11463 6324 11463 6332 11464 6171 11464 6140 11464 6332 11465 6333 11465 6171 11465 6334 11466 6328 11466 6331 11466 6332 11467 6324 11467 6333 11467 6335 11468 6314 11468 6316 11468 6335 11469 6316 11469 6321 11469 6336 11470 6329 11470 6328 11470 6337 11471 6319 11471 6308 11471 6305 11472 6331 11472 6338 11472 6337 11473 1058 11473 6319 11473 6337 11474 6308 11474 6325 11474 6305 11475 6334 11475 6331 11475 6339 11476 6335 11476 6321 11476 6339 11477 6321 11477 6322 11477 6340 11478 6328 11478 6334 11478 6341 11479 6326 11479 6327 11479 6341 11480 1057 11480 6326 11480 6340 11481 6336 11481 6328 11481 6342 11482 6322 11482 6312 11482 6342 11483 6312 11483 6323 11483 6343 11484 6329 11484 6336 11484 6344 11485 6314 11485 6335 11485 6306 11486 6305 11486 6338 11486 6344 11487 6335 11487 6339 11487 6344 11488 6318 11488 6314 11488 6313 11489 6306 11489 6338 11489 6345 11490 6327 11490 6319 11490 6345 11491 6319 11491 1058 11491 6315 11492 6343 11492 6336 11492 6346 11493 6344 11493 6339 11493 6315 11494 6336 11494 6340 11494 6347 11495 6325 11495 6318 11495 6348 11496 6329 11496 6343 11496 6347 11497 6318 11497 6344 11497 6349 11498 6140 11498 1066 11498 6307 11499 6334 11499 6305 11499 6349 11500 6332 11500 6140 11500 6349 11501 6342 11501 6323 11501 6307 11502 6340 11502 6334 11502 6349 11503 6323 11503 6332 11503 6350 11504 1064 11504 1061 11504 6350 11505 6344 11505 6346 11505 6350 11506 6347 11506 6344 11506 6350 11507 6346 11507 1064 11507 6351 11508 1058 11508 1057 11508 6351 11509 1057 11509 6341 11509 6351 11510 6341 11510 6327 11510 6310 11511 6329 11511 6348 11511 6351 11512 6327 11512 6345 11512 6351 11513 6345 11513 1058 11513 6352 11514 6322 11514 6342 11514 6309 11515 6329 11515 6310 11515 6324 11516 6338 11516 4265 11516 6352 11517 6339 11517 6322 11517 6353 11518 1061 11518 1058 11518 6353 11519 1058 11519 6337 11519 6324 11520 6313 11520 6338 11520 6353 11521 6337 11521 6325 11521 6353 11522 6350 11522 1061 11522 6353 11523 6325 11523 6347 11523 6353 11524 6347 11524 6350 11524 6354 11525 1065 11525 1064 11525 6354 11526 6346 11526 6339 11526 6317 11527 6343 11527 6315 11527 6354 11528 6339 11528 6352 11528 6317 11529 6348 11529 6343 11529 6354 11530 1064 11530 6346 11530 6354 11531 6352 11531 1065 11531 6355 11532 6352 11532 6342 11532 6355 11533 1066 11533 1065 11533 6355 11534 6349 11534 1066 11534 6355 11535 6342 11535 6349 11535 6355 11536 1065 11536 6352 11536 6316 11537 6315 11537 6340 11537 6316 11538 6340 11538 6307 11538 6311 11539 6310 11539 6348 11539 6311 11540 6348 11540 6317 11540 6333 11541 4265 11541 6171 11541 6333 11542 6324 11542 4265 11542 6320 11543 6326 11543 6329 11543 6320 11544 6329 11544 6309 11544 5516 11545 162 11545 4713 11545 162 11546 166 11546 4713 11546 166 11547 4714 11547 4713 11547 5482 11548 5571 11548 4711 11548 4710 11549 5482 11549 4711 11549 3731 11550 2817 11550 4680 11550 5571 11551 5568 11551 4712 11551 5568 11552 5516 11552 4712 11552 5516 11553 4713 11553 4712 11553 4711 11554 5571 11554 4712 11554 4680 11555 2817 11555 2815 11555 4680 11556 2815 11556 4681 11556 4681 11557 2815 11557 2814 11557 4681 11558 2814 11558 4682 11558 4682 11559 2814 11559 2812 11559 4682 11560 2812 11560 5543 11560 4682 11561 5543 11561 4683 11561 4683 11562 5543 11562 5541 11562 4683 11563 5541 11563 5539 11563 5539 11564 5536 11564 4684 11564 4683 11565 5539 11565 4684 11565 4684 11566 5536 11566 5532 11566 4685 11567 4684 11567 242 11567 242 11568 4684 11568 240 11568 4684 11569 5532 11569 240 11569 4685 11570 242 11570 244 11570 5532 11571 5534 11571 239 11571 240 11572 5532 11572 239 11572 4685 11573 244 11573 197 11573 239 11574 5534 11574 237 11574 5534 11575 5545 11575 237 11575 4685 11576 197 11576 4686 11576 4686 11577 197 11577 196 11577 5545 11578 5547 11578 235 11578 237 11579 5545 11579 235 11579 5547 11580 5549 11580 235 11580 4686 11581 196 11581 200 11581 235 11582 5549 11582 232 11582 232 11583 5549 11583 5465 11583 4686 11584 200 11584 202 11584 232 11585 5465 11585 230 11585 230 11586 5465 11586 5463 11586 230 11587 5463 11587 5460 11587 230 11588 5460 11588 228 11588 4686 11589 202 11589 4687 11589 202 11590 208 11590 4687 11590 228 11591 5460 11591 5459 11591 4687 11592 208 11592 212 11592 228 11593 5459 11593 5557 11593 226 11594 228 11594 5557 11594 4687 11595 212 11595 216 11595 226 11596 5557 11596 5559 11596 224 11597 226 11597 5559 11597 222 11598 224 11598 5474 11598 224 11599 5559 11599 5474 11599 222 11600 5474 11600 220 11600 220 11601 5474 11601 218 11601 205 11602 204 11602 4688 11602 4687 11603 216 11603 4688 11603 216 11604 205 11604 4688 11604 204 11605 210 11605 4689 11605 4688 11606 204 11606 4689 11606 210 11607 214 11607 5476 11607 214 11608 218 11608 5476 11608 218 11609 5474 11609 5476 11609 4689 11610 210 11610 5476 11610 4690 11611 4689 11611 5476 11611 4690 11612 5476 11612 5567 11612 4690 11613 5567 11613 5564 11613 4690 11614 5564 11614 4691 11614 4691 11615 5564 11615 5480 11615 4691 11616 5480 11616 4692 11616 4692 11617 5480 11617 5515 11617 4692 11618 5515 11618 4693 11618 4693 11619 5515 11619 5513 11619 4693 11620 5513 11620 4694 11620 4694 11621 5513 11621 5511 11621 4694 11622 5511 11622 4695 11622 4695 11623 5511 11623 5510 11623 4695 11624 5510 11624 4696 11624 4696 11625 5510 11625 5508 11625 4696 11626 5508 11626 4697 11626 4697 11627 5508 11627 5506 11627 4697 11628 5506 11628 4698 11628 4698 11629 5506 11629 5504 11629 4698 11630 5504 11630 4699 11630 4699 11631 5504 11631 5502 11631 4699 11632 5502 11632 4700 11632 4700 11633 5502 11633 5500 11633 4700 11634 5500 11634 4701 11634 2836 11635 2834 11635 4722 11635 2834 11636 3707 11636 4722 11636 4701 11637 5500 11637 4702 11637 5500 11638 5498 11638 4702 11638 5563 11639 5473 11639 192 11639 5473 11640 5471 11640 192 11640 192 11641 5471 11641 190 11641 5468 11642 5467 11642 190 11642 5471 11643 5468 11643 190 11643 5561 11644 5563 11644 194 11644 5563 11645 192 11645 194 11645 5467 11646 5551 11646 189 11646 190 11647 5467 11647 189 11647 2836 11648 4722 11648 4721 11648 2838 11649 2836 11649 4721 11649 5498 11650 5496 11650 4703 11650 4702 11651 5498 11651 4703 11651 5561 11652 194 11652 147 11652 5519 11653 5561 11653 147 11653 5551 11654 5553 11654 187 11654 5553 11655 5555 11655 187 11655 189 11656 5551 11656 187 11656 5519 11657 147 11657 146 11657 187 11658 5555 11658 185 11658 5555 11659 5520 11659 185 11659 5519 11660 146 11660 150 11660 5520 11661 5523 11661 182 11661 185 11662 5520 11662 182 11662 5524 11663 2839 11663 4720 11663 2839 11664 2838 11664 4720 11664 2838 11665 4721 11665 4720 11665 5496 11666 5494 11666 4704 11666 4703 11667 5496 11667 4704 11667 5519 11668 150 11668 152 11668 182 11669 5523 11669 180 11669 5527 11670 5524 11670 4719 11670 5529 11671 5527 11671 4719 11671 5524 11672 4720 11672 4719 11672 5494 11673 5492 11673 4705 11673 4704 11674 5494 11674 4705 11674 4705 11675 5492 11675 4706 11675 5492 11676 5490 11676 4706 11676 180 11677 5523 11677 4718 11677 5529 11678 4719 11678 4718 11678 178 11679 180 11679 4718 11679 5531 11680 5529 11680 4718 11680 5523 11681 5531 11681 4718 11681 174 11682 176 11682 4717 11682 176 11683 178 11683 4717 11683 178 11684 4718 11684 4717 11684 5490 11685 5488 11685 4707 11685 4706 11686 5490 11686 4707 11686 5519 11687 152 11687 5516 11687 152 11688 158 11688 5516 11688 158 11689 162 11689 5516 11689 168 11690 170 11690 4716 11690 170 11691 172 11691 4716 11691 172 11692 174 11692 4716 11692 174 11693 4717 11693 4716 11693 5488 11694 5486 11694 4708 11694 4707 11695 5488 11695 4708 11695 154 11696 160 11696 4715 11696 160 11697 164 11697 4715 11697 164 11698 168 11698 4715 11698 168 11699 4716 11699 4715 11699 5486 11700 5483 11700 4709 11700 4708 11701 5486 11701 4709 11701 155 11702 154 11702 4714 11702 166 11703 155 11703 4714 11703 154 11704 4715 11704 4714 11704 5483 11705 5482 11705 4710 11705 4709 11706 5483 11706 4710 11706 3937 11707 4217 11707 4755 11707 3937 11708 4755 11708 3940 11708 4265 11709 6338 11709 4266 11709 6356 11710 6357 11710 6358 11710 6358 11711 6359 11711 6360 11711 6358 11712 6360 11712 6361 11712 6356 11713 6358 11713 6362 11713 6358 11714 6361 11714 6362 11714 4272 11715 6363 11715 4223 11715 6338 11716 6331 11716 6364 11716 6331 11717 6330 11717 6364 11717 4266 11718 6338 11718 6364 11718 6330 11719 6363 11719 6365 11719 6364 11720 6330 11720 6365 11720 4266 11721 6364 11721 6365 11721 4272 11722 4266 11722 6366 11722 6365 11723 6363 11723 6366 11723 4266 11724 6365 11724 6366 11724 6363 11725 4272 11725 6366 11725 6330 11726 6367 11726 6368 11726 6369 11727 6363 11727 6368 11727 6363 11728 6330 11728 6368 11728 6367 11729 6370 11729 6371 11729 6370 11730 6357 11730 6371 11730 6356 11731 6369 11731 6371 11731 6368 11732 6367 11732 6371 11732 6369 11733 6368 11733 6371 11733 6357 11734 6356 11734 6371 11734 6372 11735 6360 11735 6359 11735 6372 11736 6361 11736 6360 11736 6372 11737 6362 11737 6361 11737 6373 11738 6372 11738 6359 11738 6374 11739 6372 11739 6373 11739 6375 11740 6376 11740 6374 11740 6375 11741 6374 11741 6373 11741 6377 11742 6376 11742 6375 11742 6378 11743 6377 11743 6375 11743 6379 11744 6377 11744 6378 11744 6380 11745 6379 11745 6378 11745 6381 11746 6379 11746 6380 11746 4754 11747 6382 11747 6383 11747 3940 11748 4755 11748 4754 11748 6384 11749 4754 11749 6383 11749 6384 11750 3940 11750 4754 11750 6385 11751 6383 11751 6386 11751 6385 11752 6384 11752 6383 11752 6387 11753 6386 11753 6388 11753 6387 11754 6385 11754 6386 11754 6389 11755 6388 11755 6390 11755 6389 11756 6387 11756 6388 11756 6391 11757 6390 11757 6392 11757 6391 11758 6389 11758 6390 11758 6393 11759 6392 11759 6394 11759 6393 11760 6391 11760 6392 11760 6395 11761 6382 11761 6396 11761 6397 11762 6396 11762 6398 11762 6397 11763 6395 11763 6396 11763 6399 11764 6398 11764 6381 11764 6399 11765 6397 11765 6398 11765 6400 11766 6383 11766 6382 11766 6400 11767 6382 11767 6395 11767 6400 11768 6395 11768 6397 11768 6401 11769 6397 11769 6399 11769 6401 11770 6400 11770 6397 11770 6402 11771 6386 11771 6383 11771 6402 11772 6383 11772 6400 11772 6403 11773 6381 11773 6380 11773 6403 11774 6399 11774 6381 11774 6404 11775 6399 11775 6403 11775 6404 11776 6401 11776 6399 11776 6405 11777 6400 11777 6401 11777 6405 11778 6402 11778 6400 11778 6406 11779 6405 11779 6401 11779 6406 11780 6401 11780 6404 11780 6407 11781 6403 11781 6380 11781 6408 11782 6386 11782 6402 11782 6409 11783 6402 11783 6405 11783 6409 11784 6408 11784 6402 11784 6410 11785 6405 11785 6406 11785 6410 11786 6409 11786 6405 11786 6411 11787 6404 11787 6403 11787 6412 11788 6388 11788 6386 11788 6412 11789 6386 11789 6408 11789 6413 11790 6406 11790 6404 11790 6413 11791 6404 11791 6411 11791 6414 11792 6408 11792 6409 11792 6414 11793 6412 11793 6408 11793 6415 11794 6403 11794 6407 11794 6415 11795 6411 11795 6403 11795 6416 11796 6380 11796 6378 11796 6416 11797 6407 11797 6380 11797 6417 11798 6409 11798 6410 11798 6417 11799 6414 11799 6409 11799 6418 11800 6411 11800 6415 11800 6418 11801 6413 11801 6411 11801 6419 11802 6416 11802 6378 11802 6420 11803 6388 11803 6412 11803 6420 11804 6412 11804 6414 11804 6421 11805 6414 11805 6417 11805 6421 11806 6420 11806 6414 11806 6422 11807 6421 11807 6417 11807 6423 11808 6406 11808 6413 11808 6423 11809 6410 11809 6406 11809 6424 11810 6423 11810 6413 11810 6424 11811 6413 11811 6418 11811 6425 11812 6390 11812 6388 11812 6425 11813 6388 11813 6420 11813 6426 11814 6417 11814 6410 11814 6426 11815 6410 11815 6423 11815 6426 11816 6422 11816 6417 11816 6427 11817 6407 11817 6416 11817 6427 11818 6416 11818 6419 11818 6427 11819 6415 11819 6407 11819 6428 11820 6420 11820 6421 11820 6428 11821 6425 11821 6420 11821 6429 11822 6427 11822 6419 11822 6430 11823 6428 11823 6421 11823 6430 11824 6421 11824 6422 11824 6431 11825 6418 11825 6415 11825 6431 11826 6427 11826 6429 11826 6431 11827 6415 11827 6427 11827 6432 11828 6423 11828 6424 11828 6432 11829 6426 11829 6423 11829 6433 11830 6431 11830 6429 11830 6434 11831 6390 11831 6425 11831 6434 11832 6425 11832 6428 11832 6435 11833 6378 11833 6375 11833 6435 11834 6419 11834 6378 11834 6436 11835 6428 11835 6430 11835 6436 11836 6434 11836 6428 11836 6437 11837 6435 11837 6375 11837 6438 11838 6436 11838 6430 11838 6439 11839 6422 11839 6426 11839 6439 11840 6426 11840 6432 11840 6440 11841 6439 11841 6432 11841 6441 11842 6418 11842 6431 11842 6441 11843 6424 11843 6418 11843 6442 11844 6392 11844 6390 11844 6442 11845 6390 11845 6434 11845 6443 11846 6441 11846 6431 11846 6443 11847 6431 11847 6433 11847 6444 11848 6430 11848 6422 11848 6444 11849 6422 11849 6439 11849 6445 11850 6442 11850 6434 11850 6445 11851 6434 11851 6436 11851 6446 11852 6394 11852 6392 11852 6446 11853 6392 11853 6442 11853 6447 11854 6436 11854 6438 11854 6447 11855 6445 11855 6436 11855 6448 11856 6432 11856 6424 11856 6448 11857 6424 11857 6441 11857 6449 11858 6429 11858 6419 11858 6449 11859 6419 11859 6435 11859 6450 11860 6439 11860 6440 11860 6450 11861 6444 11861 6439 11861 6451 11862 6442 11862 6445 11862 6451 11863 6394 11863 6446 11863 6451 11864 6446 11864 6442 11864 6452 11865 6441 11865 6443 11865 6452 11866 6448 11866 6441 11866 6453 11867 6451 11867 6445 11867 6453 11868 6454 11868 6394 11868 6453 11869 6394 11869 6451 11869 6453 11870 6445 11870 6447 11870 6455 11871 6449 11871 6435 11871 6455 11872 6435 11872 6437 11872 6456 11873 6433 11873 6429 11873 6456 11874 6429 11874 6449 11874 6457 11875 6444 11875 6450 11875 6457 11876 6438 11876 6430 11876 6457 11877 6430 11877 6444 11877 6458 11878 6375 11878 6373 11878 6458 11879 6455 11879 6437 11879 6458 11880 6437 11880 6375 11880 6459 11881 6456 11881 6449 11881 6459 11882 6449 11882 6455 11882 6460 11883 6457 11883 6450 11883 6461 11884 6458 11884 6373 11884 6462 11885 6448 11885 6452 11885 6462 11886 6432 11886 6448 11886 6462 11887 6440 11887 6432 11887 6462 11888 6450 11888 6440 11888 6463 11889 6462 11889 6452 11889 6464 11890 6453 11890 6447 11890 6464 11891 6438 11891 6457 11891 6464 11892 6447 11892 6438 11892 6465 11893 6433 11893 6456 11893 6465 11894 6443 11894 6433 11894 6466 11895 6373 11895 6359 11895 6466 11896 6461 11896 6373 11896 6467 11897 6450 11897 6462 11897 6467 11898 6462 11898 6463 11898 6468 11899 6456 11899 6459 11899 6468 11900 6465 11900 6456 11900 6469 11901 6454 11901 6453 11901 6469 11902 6453 11902 6464 11902 6470 11903 6457 11903 6460 11903 6470 11904 6464 11904 6457 11904 6471 11905 6467 11905 6463 11905 6472 11906 6452 11906 6443 11906 6472 11907 6443 11907 6465 11907 6473 11908 6455 11908 6458 11908 6474 11909 6454 11909 6469 11909 6474 11910 6469 11910 6464 11910 6474 11911 6464 11911 6470 11911 6475 11912 6465 11912 6468 11912 6475 11913 6472 11913 6465 11913 6476 11914 6455 11914 6473 11914 6476 11915 6459 11915 6455 11915 6476 11916 6468 11916 6459 11916 6477 11917 6450 11917 6467 11917 6477 11918 6467 11918 6471 11918 6477 11919 6460 11919 6450 11919 6478 11920 6458 11920 6461 11920 6478 11921 6461 11921 6466 11921 6478 11922 6473 11922 6458 11922 6479 11923 6477 11923 6471 11923 6480 11924 6476 11924 6473 11924 6480 11925 6473 11925 6478 11925 6481 11926 6452 11926 6472 11926 6481 11927 6463 11927 6452 11927 6481 11928 6472 11928 6475 11928 6482 11929 6481 11929 6475 11929 6483 11930 6359 11930 6484 11930 6483 11931 6466 11931 6359 11931 6483 11932 6480 11932 6478 11932 6483 11933 6478 11933 6466 11933 6485 11934 6470 11934 6460 11934 6485 11935 6460 11935 6477 11935 6485 11936 6477 11936 6479 11936 6486 11937 6480 11937 6483 11937 6486 11938 6483 11938 6484 11938 6487 11939 6468 11939 6476 11939 6488 11940 6485 11940 6479 11940 6489 11941 6471 11941 6463 11941 6489 11942 6463 11942 6481 11942 6490 11943 6470 11943 6485 11943 6490 11944 6474 11944 6470 11944 6491 11945 6487 11945 6476 11945 6491 11946 6480 11946 6486 11946 6491 11947 6476 11947 6480 11947 6492 11948 6490 11948 6485 11948 6492 11949 6493 11949 6494 11949 6492 11950 6494 11950 6490 11950 6492 11951 6485 11951 6488 11951 6495 11952 6489 11952 6481 11952 6495 11953 6481 11953 6482 11953 6496 11954 6468 11954 6487 11954 6496 11955 6475 11955 6468 11955 6496 11956 6482 11956 6475 11956 6497 11957 6471 11957 6489 11957 6497 11958 6488 11958 6479 11958 6497 11959 6489 11959 6495 11959 6497 11960 6479 11960 6471 11960 6498 11961 6496 11961 6487 11961 6498 11962 6487 11962 6491 11962 6499 11963 6497 11963 6495 11963 6500 11964 6486 11964 6484 11964 6500 11965 6484 11965 6501 11965 6500 11966 6491 11966 6486 11966 6500 11967 6498 11967 6491 11967 6502 11968 6496 11968 6498 11968 6502 11969 6495 11969 6482 11969 6502 11970 6482 11970 6496 11970 6503 11971 6502 11971 6498 11971 6504 11972 6503 11972 6498 11972 6504 11973 6500 11973 6501 11973 6504 11974 6498 11974 6500 11974 6494 11975 6474 11975 6490 11975 6494 11976 6454 11976 6474 11976 6505 11977 6488 11977 6497 11977 6506 11978 6505 11978 6497 11978 6506 11979 6497 11979 6499 11979 6507 11980 6495 11980 6502 11980 6508 11981 6488 11981 6505 11981 6508 11982 6492 11982 6488 11982 6509 11983 6508 11983 6505 11983 6509 11984 6505 11984 6506 11984 6510 11985 6502 11985 6503 11985 6510 11986 6507 11986 6502 11986 6511 11987 6501 11987 6512 11987 6511 11988 6504 11988 6501 11988 6511 11989 6503 11989 6504 11989 6511 11990 6510 11990 6503 11990 6513 11991 6495 11991 6507 11991 6513 11992 6499 11992 6495 11992 6513 11993 6507 11993 6510 11993 6514 11994 6513 11994 6510 11994 6515 11995 6511 11995 6512 11995 6515 11996 6510 11996 6511 11996 6515 11997 6514 11997 6510 11997 6493 11998 6492 11998 6508 11998 6493 11999 6508 11999 6509 11999 6516 12000 6499 12000 6513 12000 6516 12001 6506 12001 6499 12001 6517 12002 6512 12002 6518 12002 6517 12003 6515 12003 6512 12003 6517 12004 6514 12004 6515 12004 6519 12005 6509 12005 6506 12005 6519 12006 6506 12006 6516 12006 6520 12007 6516 12007 6513 12007 6520 12008 6513 12008 6514 12008 6520 12009 6514 12009 6517 12009 6521 12010 6516 12010 6520 12010 6521 12011 6519 12011 6516 12011 6522 12012 6517 12012 6518 12012 6522 12013 6520 12013 6517 12013 6522 12014 6521 12014 6520 12014 6523 12015 6521 12015 6522 12015 6523 12016 6518 12016 6524 12016 6523 12017 6522 12017 6518 12017 6525 12018 6493 12018 6509 12018 6525 12019 6509 12019 6519 12019 6525 12020 6519 12020 6521 12020 6525 12021 6521 12021 6526 12021 6526 12022 6523 12022 6524 12022 6526 12023 6521 12023 6523 12023 4737 12024 4735 12024 6527 12024 6528 12025 6527 12025 6529 12025 6528 12026 4737 12026 6527 12026 6530 12027 6529 12027 6531 12027 6530 12028 6528 12028 6529 12028 6532 12029 6530 12029 6531 12029 6533 12030 6534 12030 6535 12030 6536 12031 6537 12031 6538 12031 6533 12032 6535 12032 6539 12032 6540 12033 3931 12033 3933 12033 6541 12034 6542 12034 6543 12034 6541 12035 6538 12035 6542 12035 6540 12036 6544 12036 3931 12036 6540 12037 6545 12037 6544 12037 6546 12038 6547 12038 6387 12038 6548 12039 4735 12039 4734 12039 6546 12040 6387 12040 6389 12040 6546 12041 6543 12041 6547 12041 6548 12042 6527 12042 4735 12042 6548 12043 6529 12043 6527 12043 6546 12044 6541 12044 6543 12044 6548 12045 6549 12045 6529 12045 6550 12046 6551 12046 6536 12046 6550 12047 6536 12047 6538 12047 6550 12048 6538 12048 6541 12048 6552 12049 6533 12049 6539 12049 6553 12050 6546 12050 6389 12050 6554 12051 4736 12051 6534 12051 6553 12052 6541 12052 6546 12052 6554 12053 6534 12053 6533 12053 6555 12054 6556 12054 6551 12054 6555 12055 6551 12055 6550 12055 6555 12056 6550 12056 6541 12056 6557 12057 3933 12057 3935 12057 6555 12058 6541 12058 6553 12058 6557 12059 6540 12059 3933 12059 6558 12060 6391 12060 6393 12060 6558 12061 6389 12061 6391 12061 6558 12062 6393 12062 6556 12062 6558 12063 6556 12063 6555 12063 6558 12064 6553 12064 6389 12064 6558 12065 6555 12065 6553 12065 6559 12066 6539 12066 6560 12066 6559 12067 6560 12067 6545 12067 6559 12068 6552 12068 6539 12068 6561 12069 6545 12069 6540 12069 6561 12070 6540 12070 6557 12070 6562 12071 4734 12071 4736 12071 6562 12072 6563 12072 6549 12072 6562 12073 6548 12073 4734 12073 6562 12074 6549 12074 6548 12074 6564 12075 4736 12075 6554 12075 6564 12076 6533 12076 6552 12076 6564 12077 6554 12077 6533 12077 6565 12078 6557 12078 3935 12078 6566 12079 6557 12079 6565 12079 6549 12080 6531 12080 6529 12080 6566 12081 6561 12081 6557 12081 6567 12082 6563 12082 6562 12082 6567 12083 6562 12083 4736 12083 6568 12084 6552 12084 6559 12084 6569 12085 6568 12085 6559 12085 6384 12086 3939 12086 3940 12086 6569 12087 6561 12087 6566 12087 6569 12088 6545 12088 6561 12088 6569 12089 6559 12089 6545 12089 6570 12090 6566 12090 6565 12090 6571 12091 6567 12091 4736 12091 6571 12092 6572 12092 6563 12092 6571 12093 6563 12093 6567 12093 6571 12094 4736 12094 6564 12094 6573 12095 3935 12095 3939 12095 6573 12096 6570 12096 6565 12096 6573 12097 6565 12097 3935 12097 6573 12098 3939 12098 6384 12098 6574 12099 6564 12099 6552 12099 6574 12100 6552 12100 6568 12100 6574 12101 6571 12101 6564 12101 6575 12102 6569 12102 6566 12102 6576 12103 6568 12103 6569 12103 6576 12104 6569 12104 6575 12104 6577 12105 6578 12105 6579 12105 6577 12106 6579 12106 3930 12106 6577 12107 3930 12107 3928 12107 6580 12108 6384 12108 6385 12108 6580 12109 6570 12109 6573 12109 6580 12110 6573 12110 6384 12110 6581 12111 6577 12111 3928 12111 6582 12112 6566 12112 6570 12112 6582 12113 6575 12113 6566 12113 6583 12114 6584 12114 6578 12114 6582 12115 6570 12115 6580 12115 6583 12116 6578 12116 6577 12116 6583 12117 6577 12117 6581 12117 6542 12118 6576 12118 6575 12118 6560 12119 6583 12119 6581 12119 6585 12120 6572 12120 6571 12120 6585 12121 6571 12121 6574 12121 6535 12122 6534 12122 6584 12122 6537 12123 6568 12123 6576 12123 6535 12124 6584 12124 6583 12124 6537 12125 6574 12125 6568 12125 6537 12126 6585 12126 6574 12126 6544 12127 3928 12127 3931 12127 6544 12128 6560 12128 6581 12128 6547 12129 6385 12129 6387 12129 6547 12130 6582 12130 6580 12130 6544 12131 6581 12131 3928 12131 6547 12132 6580 12132 6385 12132 6543 12133 6575 12133 6582 12133 6539 12134 6583 12134 6560 12134 6543 12135 6542 12135 6575 12135 6539 12136 6535 12136 6583 12136 6543 12137 6582 12137 6547 12137 6538 12138 6537 12138 6576 12138 6538 12139 6576 12139 6542 12139 6545 12140 6560 12140 6544 12140 6536 12141 6585 12141 6537 12141 6536 12142 6551 12142 6572 12142 6536 12143 6572 12143 6585 12143 6586 12144 6587 12144 6588 12144 6589 12145 6590 12145 6591 12145 6592 12146 6593 12146 6594 12146 6589 12147 6591 12147 6595 12147 6589 12148 6595 12148 6586 12148 6596 12149 6597 12149 6598 12149 6596 12150 6598 12150 6599 12150 6592 12151 6600 12151 6593 12151 6596 12152 6599 12152 6601 12152 6602 12153 6603 12153 6604 12153 6605 12154 6606 12154 3947 12154 6602 12155 6601 12155 6603 12155 6607 12156 6608 12156 6609 12156 6607 12157 6586 12157 6608 12157 6610 12158 6611 12158 6612 12158 6607 12159 6589 12159 6586 12159 6613 12160 6604 12160 6590 12160 6610 12161 6612 12161 6614 12161 6613 12162 6590 12162 6589 12162 6615 12163 6592 12163 6594 12163 6616 12164 6597 12164 6596 12164 6616 12165 6596 12165 6601 12165 6616 12166 6601 12166 6602 12166 6615 12167 6606 12167 6605 12167 6615 12168 6594 12168 6606 12168 6617 12169 6609 12169 6618 12169 6617 12170 6618 12170 6613 12170 6617 12171 6607 12171 6609 12171 6619 12172 6592 12172 6615 12172 6617 12173 6589 12173 6607 12173 6619 12174 6614 12174 6600 12174 6617 12175 6613 12175 6589 12175 6620 12176 6618 12176 4739 12176 6620 12177 6613 12177 6618 12177 6620 12178 6604 12178 6613 12178 6619 12179 6600 12179 6592 12179 6620 12180 6602 12180 6604 12180 6621 12181 6622 12181 6597 12181 6621 12182 6597 12182 6616 12182 6621 12183 6616 12183 6602 12183 6623 12184 6615 12184 6605 12184 6621 12185 6602 12185 6620 12185 6624 12186 3947 12186 3949 12186 6625 12187 6622 12187 6621 12187 6625 12188 6620 12188 4739 12188 6625 12189 6621 12189 6620 12189 6624 12190 6605 12190 3947 12190 6626 12191 4739 12191 4738 12191 6626 12192 6627 12192 6622 12192 6628 12193 6629 12193 6611 12193 6626 12194 6625 12194 4739 12194 6626 12195 6622 12195 6625 12195 6630 12196 6528 12196 6530 12196 6628 12197 6611 12197 6610 12197 6630 12198 6626 12198 4738 12198 6630 12199 6627 12199 6626 12199 6630 12200 4738 12200 6528 12200 6630 12201 6530 12201 6627 12201 6631 12202 6615 12202 6623 12202 6631 12203 6619 12203 6615 12203 6632 12204 6614 12204 6619 12204 6632 12205 6610 12205 6614 12205 6633 12206 6631 12206 6623 12206 6634 12207 6635 12207 6636 12207 6634 12208 6636 12208 6629 12208 6634 12209 6629 12209 6628 12209 6591 12210 6623 12210 6605 12210 6591 12211 6605 12211 6624 12211 6637 12212 6631 12212 6633 12212 6637 12213 6619 12213 6631 12213 6637 12214 6632 12214 6619 12214 6638 12215 6632 12215 6637 12215 6638 12216 6628 12216 6610 12216 6638 12217 6610 12217 6632 12217 6639 12218 3949 12218 3953 12218 6639 12219 6624 12219 3949 12219 6603 12220 6637 12220 6633 12220 6590 12221 6623 12221 6591 12221 6528 12222 4738 12222 4737 12222 6590 12223 6633 12223 6623 12223 6587 12224 3953 12224 3954 12224 6587 12225 6639 12225 3953 12225 6640 12226 6637 12226 6603 12226 6532 12227 6627 12227 6530 12227 6640 12228 6638 12228 6637 12228 6593 12229 3944 12229 3942 12229 6593 12230 6641 12230 3944 12230 6642 12231 6634 12231 6628 12231 6642 12232 6598 12232 6635 12232 6642 12233 6635 12233 6634 12233 6642 12234 6628 12234 6638 12234 6595 12235 6591 12235 6624 12235 6600 12236 6643 12236 6641 12236 6595 12237 6639 12237 6587 12237 6595 12238 6624 12238 6639 12238 6600 12239 6641 12239 6593 12239 6588 12240 3954 12240 6644 12240 6588 12241 6644 12241 6645 12241 6594 12242 3942 12242 3945 12242 6588 12243 6587 12243 3954 12243 6601 12244 6640 12244 6603 12244 6594 12245 6593 12245 3942 12245 6604 12246 6633 12246 6590 12246 6614 12247 6612 12247 6643 12247 6604 12248 6603 12248 6633 12248 6614 12249 6643 12249 6600 12249 6599 12250 6640 12250 6601 12250 6599 12251 6638 12251 6640 12251 6606 12252 3945 12252 3947 12252 6599 12253 6642 12253 6638 12253 6599 12254 6598 12254 6642 12254 6586 12255 6645 12255 6608 12255 6586 12256 6595 12256 6587 12256 6606 12257 6594 12257 3945 12257 6586 12258 6588 12258 6645 12258 6646 12259 6647 12259 6648 12259 6649 12260 6647 12260 6646 12260 6650 12261 6649 12261 6646 12261 6651 12262 6652 12262 6649 12262 6651 12263 6649 12263 6650 12263 6653 12264 6654 12264 6652 12264 6653 12265 6652 12265 6651 12265 6655 12266 6654 12266 6653 12266 6656 12267 6654 12267 6655 12267 6657 12268 6656 12268 6655 12268 6658 12269 6657 12269 6655 12269 6659 12270 6658 12270 6655 12270 6660 12271 6661 12271 6662 12271 6660 12272 6663 12272 6664 12272 6660 12273 6662 12273 6665 12273 6660 12274 6664 12274 6661 12274 6660 12275 6665 12275 6663 12275 6666 12276 6667 12276 6662 12276 6666 12277 6668 12277 6667 12277 6669 12278 6659 12278 6655 12278 6670 12279 6655 12279 6653 12279 6670 12280 6669 12280 6655 12280 6671 12281 6670 12281 6653 12281 6672 12282 6673 12282 6659 12282 6672 12283 6659 12283 6669 12283 6672 12284 6669 12284 6670 12284 6674 12285 6673 12285 6672 12285 6675 12286 6672 12286 6670 12286 6675 12287 6670 12287 6671 12287 6676 12288 6674 12288 6672 12288 6676 12289 6672 12289 6675 12289 6677 12290 6675 12290 6671 12290 6678 12291 6653 12291 6651 12291 6678 12292 6671 12292 6653 12292 6679 12293 6676 12293 6675 12293 6679 12294 6675 12294 6677 12294 6680 12295 6681 12295 6673 12295 6680 12296 6673 12296 6674 12296 6680 12297 6674 12297 6676 12297 6682 12298 6678 12298 6651 12298 6683 12299 6681 12299 6680 12299 6684 12300 6676 12300 6679 12300 6684 12301 6680 12301 6676 12301 6685 12302 6684 12302 6679 12302 6686 12303 6677 12303 6671 12303 6686 12304 6671 12304 6678 12304 6686 12305 6678 12305 6682 12305 6687 12306 6683 12306 6680 12306 6687 12307 6684 12307 6685 12307 6687 12308 6680 12308 6684 12308 6688 12309 6689 12309 6681 12309 6688 12310 6683 12310 6687 12310 6688 12311 6681 12311 6683 12311 6690 12312 6679 12312 6677 12312 6690 12313 6677 12313 6686 12313 6691 12314 6686 12314 6682 12314 6692 12315 6687 12315 6685 12315 6693 12316 6651 12316 6650 12316 6693 12317 6691 12317 6682 12317 6693 12318 6682 12318 6651 12318 6694 12319 6690 12319 6686 12319 6694 12320 6686 12320 6691 12320 6695 12321 6693 12321 6650 12321 6696 12322 6688 12322 6687 12322 6697 12323 6689 12323 6688 12323 6698 12324 6696 12324 6687 12324 6698 12325 6687 12325 6692 12325 6699 12326 6692 12326 6685 12326 6699 12327 6679 12327 6690 12327 6699 12328 6685 12328 6679 12328 6699 12329 6690 12329 6694 12329 6700 12330 6689 12330 6697 12330 6700 12331 6701 12331 6689 12331 6702 12332 6697 12332 6688 12332 6702 12333 6700 12333 6697 12333 6702 12334 6688 12334 6696 12334 6703 12335 6699 12335 6694 12335 6704 12336 6691 12336 6693 12336 6704 12337 6694 12337 6691 12337 6704 12338 6693 12338 6695 12338 6705 12339 6692 12339 6699 12339 6705 12340 6698 12340 6692 12340 6705 12341 6699 12341 6703 12341 6706 12342 6696 12342 6698 12342 6706 12343 6702 12343 6696 12343 6707 12344 6704 12344 6695 12344 6708 12345 6703 12345 6694 12345 6708 12346 6704 12346 6707 12346 6708 12347 6694 12347 6704 12347 6709 12348 6705 12348 6703 12348 6710 12349 6700 12349 6702 12349 6710 12350 6702 12350 6706 12350 6711 12351 6650 12351 6646 12351 6711 12352 6695 12352 6650 12352 6711 12353 6707 12353 6695 12353 6712 12354 6708 12354 6707 12354 6713 12355 6711 12355 6646 12355 6714 12356 6701 12356 6700 12356 6715 12357 6710 12357 6706 12357 6716 12358 6698 12358 6705 12358 6717 12359 6718 12359 6719 12359 6717 12360 6719 12360 6701 12360 6717 12361 6701 12361 6714 12361 6720 12362 6705 12362 6709 12362 6720 12363 6716 12363 6705 12363 6721 12364 6703 12364 6708 12364 6721 12365 6709 12365 6703 12365 6721 12366 6708 12366 6712 12366 6722 12367 6700 12367 6710 12367 6722 12368 6714 12368 6700 12368 6722 12369 6717 12369 6714 12369 6723 12370 6721 12370 6712 12370 6724 12371 6646 12371 6648 12371 6724 12372 6713 12372 6646 12372 6725 12373 6706 12373 6698 12373 6725 12374 6715 12374 6706 12374 6725 12375 6698 12375 6716 12375 6726 12376 6718 12376 6717 12376 6726 12377 6717 12377 6722 12377 6727 12378 6710 12378 6715 12378 6727 12379 6722 12379 6710 12379 6728 12380 6707 12380 6711 12380 6728 12381 6711 12381 6713 12381 6729 12382 6720 12382 6709 12382 6729 12383 6709 12383 6721 12383 6729 12384 6721 12384 6723 12384 6730 12385 6716 12385 6720 12385 6730 12386 6725 12386 6716 12386 6731 12387 6728 12387 6713 12387 6732 12388 6718 12388 6726 12388 6732 12389 6726 12389 6722 12389 6732 12390 6733 12390 6718 12390 6732 12391 6722 12391 6727 12391 6734 12392 6729 12392 6723 12392 6735 12393 6707 12393 6728 12393 6735 12394 6712 12394 6707 12394 6736 12395 6725 12395 6730 12395 6736 12396 6715 12396 6725 12396 6737 12397 6728 12397 6731 12397 6737 12398 6735 12398 6728 12398 6738 12399 6648 12399 6739 12399 6738 12400 6724 12400 6648 12400 6740 12401 6739 12401 6741 12401 6740 12402 6738 12402 6739 12402 6742 12403 6736 12403 6730 12403 6743 12404 6741 12404 6744 12404 6743 12405 6740 12405 6741 12405 6745 12406 6720 12406 6729 12406 6745 12407 6730 12407 6720 12407 6745 12408 6729 12408 6734 12408 6746 12409 6745 12409 6734 12409 6747 12410 6731 12410 6713 12410 6747 12411 6713 12411 6724 12411 6748 12412 6712 12412 6735 12412 6748 12413 6735 12413 6737 12413 6748 12414 6723 12414 6712 12414 6749 12415 6727 12415 6715 12415 6749 12416 6715 12416 6736 12416 6750 12417 6737 12417 6731 12417 6750 12418 6731 12418 6747 12418 6751 12419 6748 12419 6737 12419 6752 12420 6730 12420 6745 12420 6752 12421 6742 12421 6730 12421 6753 12422 6749 12422 6736 12422 6753 12423 6736 12423 6742 12423 6754 12424 6732 12424 6727 12424 6754 12425 6749 12425 6753 12425 6754 12426 6727 12426 6749 12426 6755 12427 6752 12427 6745 12427 6755 12428 6745 12428 6746 12428 6756 12429 6724 12429 6738 12429 6756 12430 6738 12430 6740 12430 6756 12431 6747 12431 6724 12431 6757 12432 6723 12432 6748 12432 6757 12433 6734 12433 6723 12433 6757 12434 6746 12434 6734 12434 6758 12435 6754 12435 6753 12435 6759 12436 6748 12436 6751 12436 6759 12437 6757 12437 6748 12437 6760 12438 6740 12438 6743 12438 6760 12439 6756 12439 6740 12439 6761 12440 6750 12440 6747 12440 6761 12441 6747 12441 6756 12441 6762 12442 6752 12442 6755 12442 6762 12443 6742 12443 6752 12443 6762 12444 6753 12444 6742 12444 6763 12445 6744 12445 6764 12445 6763 12446 6743 12446 6744 12446 6763 12447 6760 12447 6743 12447 6765 12448 6756 12448 6760 12448 6765 12449 6761 12449 6756 12449 6766 12450 6762 12450 6755 12450 6767 12451 6760 12451 6763 12451 6767 12452 6764 12452 6768 12452 6767 12453 6765 12453 6760 12453 6767 12454 6763 12454 6764 12454 6769 12455 6751 12455 6737 12455 6769 12456 6737 12456 6750 12456 6770 12457 6746 12457 6757 12457 6771 12458 6770 12458 6757 12458 6771 12459 6757 12459 6759 12459 6772 12460 6759 12460 6751 12460 6772 12461 6751 12461 6769 12461 6733 12462 6732 12462 6754 12462 6733 12463 6754 12463 6758 12463 6773 12464 6761 12464 6765 12464 6773 12465 6769 12465 6750 12465 6773 12466 6750 12466 6761 12466 6774 12467 6758 12467 6753 12467 6774 12468 6753 12468 6762 12468 6775 12469 6765 12469 6767 12469 6775 12470 6773 12470 6765 12470 6776 12471 6762 12471 6766 12471 6776 12472 6774 12472 6762 12472 6777 12473 6746 12473 6770 12473 6777 12474 6755 12474 6746 12474 6778 12475 6758 12475 6774 12475 6778 12476 6774 12476 6776 12476 6779 12477 6775 12477 6767 12477 6779 12478 6767 12478 6768 12478 6780 12479 6770 12479 6771 12479 6780 12480 6777 12480 6770 12480 6781 12481 6782 12481 6783 12481 6781 12482 6778 12482 6776 12482 6784 12483 6772 12483 6769 12483 6784 12484 6769 12484 6773 12484 6785 12485 6759 12485 6772 12485 6785 12486 6771 12486 6759 12486 6786 12487 6773 12487 6775 12487 6786 12488 6784 12488 6773 12488 6787 12489 6766 12489 6755 12489 6787 12490 6777 12490 6780 12490 6787 12491 6755 12491 6777 12491 6788 12492 6775 12492 6779 12492 6788 12493 6768 12493 6789 12493 6788 12494 6779 12494 6768 12494 6788 12495 6786 12495 6775 12495 6790 12496 6787 12496 6780 12496 6791 12497 6785 12497 6772 12497 6791 12498 6772 12498 6784 12498 6792 12499 6780 12499 6771 12499 6792 12500 6771 12500 6785 12500 6793 12501 6784 12501 6786 12501 6793 12502 6786 12502 6788 12502 6793 12503 6791 12503 6784 12503 6794 12504 6788 12504 6789 12504 6794 12505 6793 12505 6788 12505 6783 12506 6758 12506 6778 12506 6783 12507 6778 12507 6781 12507 6783 12508 6733 12508 6758 12508 6795 12509 6766 12509 6787 12509 6795 12510 6776 12510 6766 12510 6796 12511 6790 12511 6780 12511 6796 12512 6780 12512 6792 12512 6797 12513 6795 12513 6787 12513 6797 12514 6787 12514 6790 12514 6798 12515 6785 12515 6791 12515 6798 12516 6792 12516 6785 12516 6799 12517 6781 12517 6776 12517 6799 12518 6795 12518 6797 12518 6799 12519 6776 12519 6795 12519 6800 12520 6666 12520 6782 12520 6800 12521 6782 12521 6799 12521 6800 12522 6799 12522 6797 12522 6801 12523 6791 12523 6793 12523 6801 12524 6798 12524 6791 12524 6802 12525 6789 12525 6803 12525 6802 12526 6794 12526 6789 12526 6802 12527 6793 12527 6794 12527 6802 12528 6801 12528 6793 12528 6804 12529 6792 12529 6798 12529 6804 12530 6796 12530 6792 12530 6804 12531 6798 12531 6801 12531 6805 12532 6801 12532 6802 12532 6805 12533 6804 12533 6801 12533 6806 12534 6805 12534 6802 12534 6806 12535 6802 12535 6803 12535 6807 12536 6790 12536 6796 12536 6807 12537 6797 12537 6790 12537 6668 12538 6797 12538 6807 12538 6668 12539 6666 12539 6800 12539 6668 12540 6800 12540 6797 12540 6782 12541 6781 12541 6799 12541 6808 12542 6796 12542 6804 12542 6808 12543 6807 12543 6796 12543 6663 12544 6804 12544 6805 12544 6663 12545 6808 12545 6804 12545 6667 12546 6807 12546 6808 12546 6667 12547 6668 12547 6807 12547 6664 12548 6663 12548 6805 12548 6664 12549 6805 12549 6806 12549 6664 12550 6806 12550 6803 12550 6664 12551 6803 12551 6661 12551 6665 12552 6662 12552 6667 12552 6665 12553 6808 12553 6663 12553 6665 12554 6667 12554 6808 12554 3749 12555 3748 12555 3944 12555 3749 12556 3944 12556 4750 12556 4251 12557 6280 12557 4268 12557 6809 12558 6656 12558 6657 12558 6809 12559 6657 12559 6658 12559 6810 12560 6809 12560 6659 12560 6809 12561 6658 12561 6659 12561 4242 12562 3762 12562 6811 12562 4251 12563 4242 12563 6812 12563 4242 12564 6811 12564 6812 12564 6812 12565 6811 12565 6813 12565 4251 12566 6812 12566 6813 12566 6811 12567 6265 12567 6813 12567 6265 12568 6288 12568 6814 12568 6288 12569 6280 12569 6814 12569 6280 12570 4251 12570 6814 12570 4251 12571 6813 12571 6814 12571 6813 12572 6265 12572 6814 12572 6810 12573 6815 12573 6816 12573 6815 12574 6265 12574 6816 12574 6811 12575 6817 12575 6816 12575 6265 12576 6811 12576 6816 12576 6817 12577 6809 12577 6818 12577 6810 12578 6816 12578 6818 12578 6816 12579 6817 12579 6818 12579 6809 12580 6810 12580 6818 12580 4328 12581 4491 12581 4489 12581 4347 12582 4348 12582 4509 12582 4289 12583 4465 12583 4280 12583 4347 12584 4509 12584 4507 12584 4271 12585 4232 12585 4368 12585 4345 12586 4347 12586 4507 12586 4541 12587 4271 12587 4368 12587 4345 12588 4507 12588 4505 12588 4264 12589 4271 12589 4541 12589 4503 12590 4345 12590 4505 12590 4326 12591 4328 12591 4487 12591 4539 12592 4264 12592 4541 12592 4343 12593 4345 12593 4503 12593 4258 12594 4264 12594 4539 12594 4537 12595 4258 12595 4539 12595 4297 12596 4465 12596 4289 12596 4297 12597 4467 12597 4465 12597 4297 12598 4469 12598 4467 12598 4252 12599 4258 12599 4537 12599 4535 12600 4252 12600 4537 12600 4341 12601 4503 12601 4501 12601 4341 12602 4343 12602 4503 12602 4533 12603 4252 12603 4535 12603 4533 12604 4244 12604 4252 12604 4249 12605 4244 12605 4533 12605 4339 12606 4341 12606 4501 12606 4339 12607 4501 12607 4499 12607 4531 12608 4249 12608 4533 12608 4324 12609 4326 12609 4487 12609 4361 12610 4249 12610 4531 12610 4497 12611 4339 12611 4499 12611 4529 12612 4361 12612 4531 12612 4324 12613 4487 12613 4485 12613 4302 12614 4469 12614 4297 12614 4359 12615 4361 12615 4529 12615 4337 12616 4339 12616 4497 12616 4250 12617 4457 12617 4455 12617 4250 12618 4455 12618 4241 12618 4527 12619 4359 12619 4529 12619 4322 12620 4324 12620 4485 12620 4322 12621 4483 12621 4481 12621 4495 12622 4337 12622 4497 12622 4322 12623 4485 12623 4483 12623 4309 12624 4469 12624 4302 12624 4459 12625 4457 12625 4250 12625 4309 12626 4471 12626 4469 12626 4525 12627 4359 12627 4527 12627 4309 12628 4473 12628 4471 12628 4525 12629 4357 12629 4359 12629 4356 12630 4357 12630 4525 12630 4319 12631 4481 12631 4479 12631 4319 12632 4322 12632 4481 12632 4523 12633 4356 12633 4525 12633 4335 12634 4495 12634 4493 12634 4335 12635 4337 12635 4495 12635 4311 12636 4473 12636 4309 12636 4355 12637 4356 12637 4523 12637 4267 12638 4461 12638 4459 12638 4267 12639 4459 12639 4250 12639 4317 12640 4319 12640 4479 12640 4521 12641 4355 12641 4523 12641 4313 12642 4475 12642 4473 12642 4313 12643 4473 12643 4311 12643 4315 12644 4477 12644 4475 12644 4315 12645 4479 12645 4477 12645 4315 12646 4317 12646 4479 12646 4315 12647 4475 12647 4313 12647 4332 12648 4335 12648 4493 12648 4354 12649 4355 12649 4521 12649 4354 12650 4521 12650 4519 12650 4273 12651 4461 12651 4267 12651 4353 12652 4354 12652 4519 12652 4353 12653 4519 12653 4517 12653 4330 12654 4332 12654 4493 12654 4351 12655 4353 12655 4517 12655 4330 12656 4493 12656 4491 12656 4351 12657 4517 12657 4515 12657 4280 12658 4461 12658 4273 12658 4280 12659 4463 12659 4461 12659 4280 12660 4465 12660 4463 12660 4350 12661 4351 12661 4515 12661 4350 12662 4515 12662 4513 12662 4349 12663 4350 12663 4513 12663 4349 12664 4513 12664 4511 12664 4348 12665 4349 12665 4511 12665 4328 12666 4330 12666 4491 12666 4348 12667 4511 12667 4509 12667 4328 12668 4489 12668 4487 12668 1241 12669 934 12669 930 12669 1241 12670 937 12670 934 12670 1261 12671 940 12671 937 12671 1261 12672 937 12672 1241 12672 1287 12673 940 12673 1261 12673 1308 12674 940 12674 1287 12674 1328 12675 940 12675 1308 12675 1080 12676 940 12676 1328 12676 1079 12677 940 12677 1080 12677 1101 12678 940 12678 1079 12678 1112 12679 940 12679 1101 12679 1123 12680 940 12680 1112 12680 1139 12681 940 12681 1123 12681 883 12682 1139 12682 1149 12682 883 12683 1149 12683 1162 12683 883 12684 1162 12684 1191 12684 883 12685 1191 12685 1213 12685 883 12686 940 12686 1139 12686 1234 12687 883 12687 1213 12687 1255 12688 883 12688 1234 12688 1283 12689 883 12689 1255 12689 1307 12690 883 12690 1283 12690 1327 12691 885 12691 883 12691 1327 12692 883 12692 1307 12692 1354 12693 891 12693 885 12693 1354 12694 894 12694 891 12694 1354 12695 885 12695 1327 12695 6819 12696 6820 12696 6821 12696 6822 12697 6823 12697 6824 12697 6825 12698 6826 12698 6827 12698 6828 12699 6829 12699 6830 12699 6828 12700 6330 12700 6831 12700 6832 12701 6833 12701 6834 12701 6828 12702 6831 12702 6829 12702 6825 12703 6835 12703 6826 12703 6836 12704 6837 12704 6838 12704 6836 12705 6838 12705 6839 12705 6832 12706 6840 12706 6833 12706 6841 12707 6370 12707 6367 12707 6836 12708 6839 12708 6842 12708 6843 12709 6326 12709 6844 12709 6841 12710 6845 12710 6820 12710 6841 12711 6820 12711 6819 12711 6841 12712 6367 12712 6845 12712 6846 12713 6844 12713 6847 12713 6848 12714 6849 12714 6850 12714 6851 12715 6834 12715 6852 12715 6846 12716 6843 12716 6844 12716 6851 12717 6832 12717 6834 12717 6848 12718 6850 12718 6823 12718 6853 12719 6854 12719 6855 12719 6853 12720 6855 12720 6849 12720 6856 12721 6857 12721 6840 12721 6858 12722 6847 12722 6859 12722 6860 12723 1047 12723 1045 12723 6858 12724 6846 12724 6847 12724 6853 12725 6849 12725 6848 12725 6856 12726 6832 12726 6851 12726 6861 12727 6862 12727 6858 12727 6863 12728 6864 12728 6860 12728 6856 12729 6840 12729 6832 12729 6861 12730 6859 12730 6837 12730 6865 12731 6866 12731 6857 12731 6867 12732 6868 12732 6835 12732 6865 12733 6841 12733 6819 12733 6861 12734 6858 12734 6859 12734 6865 12735 6819 12735 6866 12735 6867 12736 6835 12736 6825 12736 6869 12737 6512 12737 6501 12737 6869 12738 6870 12738 6512 12738 6869 12739 6852 12739 6870 12739 6833 12740 6836 12740 6842 12740 6871 12741 6329 12741 6326 12741 6869 12742 6851 12742 6852 12742 6871 12743 6326 12743 6843 12743 6872 12744 6370 12744 6841 12744 6872 12745 6841 12745 6865 12745 6873 12746 6848 12746 6823 12746 6873 12747 6853 12747 6848 12747 6874 12748 6843 12748 6846 12748 6875 12749 6856 12749 6851 12749 6874 12750 6871 12750 6843 12750 6876 12751 6853 12751 6873 12751 6877 12752 6869 12752 6501 12752 6878 12753 6827 12753 6879 12753 6878 12754 6879 12754 6864 12754 6880 12755 6854 12755 6853 12755 6878 12756 6864 12756 6863 12756 6877 12757 6851 12757 6869 12757 6880 12758 6853 12758 6876 12758 6877 12759 6875 12759 6851 12759 6881 12760 6822 12760 6518 12760 6881 12761 6823 12761 6822 12761 6862 12762 6846 12762 6858 12762 6882 12763 6865 12763 6857 12763 6881 12764 6873 12764 6823 12764 6881 12765 6876 12765 6873 12765 6862 12766 6874 12766 6846 12766 6882 12767 6857 12767 6856 12767 6883 12768 6881 12768 6518 12768 6884 12769 6825 12769 6827 12769 6883 12770 6876 12770 6881 12770 6884 12771 6827 12771 6878 12771 6885 12772 6370 12772 6872 12772 6821 12773 6862 12773 6861 12773 6885 12774 6872 12774 6865 12774 6824 12775 6863 12775 6860 12775 6885 12776 6865 12776 6882 12776 6886 12777 6856 12777 6875 12777 6838 12778 6887 12778 6868 12778 6886 12779 6882 12779 6856 12779 6888 12780 6880 12780 6876 12780 6886 12781 6885 12781 6882 12781 6838 12782 6868 12782 6867 12782 6849 12783 6884 12783 6878 12783 6889 12784 6885 12784 6886 12784 6826 12785 1050 12785 1047 12785 6890 12786 6501 12786 6484 12786 6891 12787 6837 12787 6836 12787 6890 12788 6877 12788 6501 12788 6835 12789 1052 12789 1050 12789 6890 12790 6875 12790 6877 12790 6891 12791 6861 12791 6837 12791 6849 12792 6878 12792 6863 12792 6890 12793 6886 12793 6875 12793 6835 12794 1050 12794 6826 12794 6890 12795 6889 12795 6886 12795 6892 12796 6484 12796 6359 12796 6893 12797 6842 12797 6854 12797 6892 12798 6358 12798 6357 12798 6892 12799 6359 12799 6358 12799 6893 12800 6854 12800 6880 12800 6855 12801 6884 12801 6849 12801 6894 12802 1052 12802 6835 12802 6892 12803 6890 12803 6484 12803 6892 12804 6889 12804 6890 12804 6357 12805 6370 12805 6885 12805 6893 12806 6880 12806 6888 12806 6868 12807 6894 12807 6835 12807 6357 12808 6885 12808 6889 12808 6895 12809 6884 12809 6855 12809 6357 12810 6889 12810 6892 12810 6896 12811 6883 12811 6518 12811 6895 12812 6867 12812 6825 12812 6896 12813 6876 12813 6883 12813 6897 12814 1053 12814 1052 12814 6896 12815 6888 12815 6876 12815 6895 12816 6825 12816 6884 12816 6837 12817 6887 12817 6838 12817 6897 12818 1052 12818 6894 12818 6866 12819 6821 12819 6861 12819 6837 12820 6859 12820 6887 12820 6866 12821 6861 12821 6891 12821 6898 12822 6893 12822 6888 12822 6899 12823 6897 12823 6894 12823 6854 12824 6895 12824 6855 12824 6887 12825 6894 12825 6868 12825 6887 12826 6899 12826 6894 12826 6840 12827 6836 12827 6833 12827 6840 12828 6891 12828 6836 12828 6840 12829 6866 12829 6891 12829 6844 12830 6326 12830 1053 12830 6850 12831 6849 12831 6863 12831 6844 12832 1053 12832 6897 12832 6850 12833 6863 12833 6824 12833 6900 12834 6518 12834 6512 12834 6839 12835 6895 12835 6854 12835 6839 12836 6867 12836 6895 12836 6900 12837 6898 12837 6888 12837 6900 12838 6888 12838 6896 12838 6839 12839 6838 12839 6867 12839 6900 12840 6896 12840 6518 12840 6847 12841 6897 12841 6899 12841 6901 12842 6329 12842 6871 12842 6847 12843 6844 12843 6897 12843 6834 12844 6833 12844 6842 12844 6834 12845 6893 12845 6898 12845 6834 12846 6842 12846 6893 12846 6857 12847 6866 12847 6840 12847 6829 12848 6901 12848 6871 12848 6829 12849 6871 12849 6874 12849 6859 12850 6847 12850 6899 12850 6859 12851 6899 12851 6887 12851 6852 12852 6834 12852 6898 12852 6823 12853 6850 12853 6824 12853 6830 12854 6874 12854 6862 12854 6879 12855 1047 12855 6860 12855 6830 12856 6829 12856 6874 12856 6820 12857 6862 12857 6821 12857 6842 12858 6839 12858 6854 12858 6820 12859 6830 12859 6862 12859 6864 12860 6879 12860 6860 12860 6870 12861 6898 12861 6900 12861 6870 12862 6900 12862 6512 12862 6870 12863 6852 12863 6898 12863 6902 12864 6330 12864 6329 12864 6845 12865 6367 12865 6330 12865 6902 12866 6329 12866 6901 12866 6827 12867 6826 12867 1047 12867 6845 12868 6830 12868 6820 12868 6827 12869 1047 12869 6879 12869 6845 12870 6330 12870 6828 12870 6831 12871 6901 12871 6829 12871 6845 12872 6828 12872 6830 12872 6831 12873 6330 12873 6902 12873 6819 12874 6821 12874 6866 12874 6831 12875 6902 12875 6901 12875 6822 12876 6824 12876 6524 12876 6822 12877 6524 12877 6518 12877 4751 12878 4750 12878 3944 12878 6641 12879 4751 12879 3944 12879 6764 12880 6641 12880 6643 12880 6764 12881 6744 12881 4751 12881 6764 12882 4751 12882 6641 12882 6768 12883 6643 12883 6612 12883 6768 12884 6764 12884 6643 12884 6789 12885 6612 12885 6611 12885 6789 12886 6768 12886 6612 12886 6803 12887 6611 12887 6629 12887 6803 12888 6789 12888 6611 12888 6661 12889 6629 12889 6636 12889 6661 12890 6803 12890 6629 12890 6662 12891 6661 12891 6636 12891 6903 12892 6904 12892 6905 12892 6906 12893 6907 12893 6908 12893 6909 12894 6910 12894 6911 12894 6909 12895 6911 12895 6912 12895 6913 12896 6914 12896 6915 12896 6916 12897 6810 12897 6910 12897 6913 12898 6917 12898 6914 12898 6916 12899 6910 12899 6909 12899 6918 12900 6912 12900 6919 12900 6920 12901 6921 12901 997 12901 6918 12902 6909 12902 6912 12902 6920 12903 6908 12903 6921 12903 6918 12904 6916 12904 6909 12904 6920 12905 6906 12905 6908 12905 6922 12906 6923 12906 6904 12906 6922 12907 6924 12907 6923 12907 6925 12908 6920 12908 993 12908 6922 12909 6919 12909 6924 12909 6925 12910 6906 12910 6920 12910 6922 12911 6904 12911 6903 12911 6926 12912 6903 12912 6242 12912 6926 12913 6922 12913 6903 12913 6927 12914 6928 12914 6917 12914 6927 12915 6917 12915 6913 12915 6929 12916 6916 12916 6918 12916 6930 12917 6931 12917 6906 12917 6930 12918 6915 12918 6931 12918 6932 12919 6919 12919 6922 12919 6933 12920 6242 12920 6241 12920 6930 12921 6906 12921 6925 12921 6933 12922 6926 12922 6242 12922 6933 12923 6922 12923 6926 12923 6933 12924 6932 12924 6922 12924 6934 12925 6915 12925 6930 12925 6934 12926 6913 12926 6915 12926 6935 12927 6918 12927 6919 12927 6935 12928 6919 12928 6932 12928 6936 12929 6681 12929 6689 12929 6815 12930 6810 12930 6916 12930 6815 12931 6916 12931 6929 12931 6936 12932 6689 12932 6928 12932 6936 12933 6928 12933 6927 12933 6937 12934 6933 12934 6241 12934 6937 12935 6932 12935 6933 12935 6937 12936 6935 12936 6932 12936 6938 12937 6925 12937 993 12937 6939 12938 6265 12938 6815 12938 6938 12939 6930 12939 6925 12939 6939 12940 6918 12940 6935 12940 6938 12941 6934 12941 6930 12941 6939 12942 6815 12942 6929 12942 6939 12943 6929 12943 6918 12943 6940 12944 6681 12944 6936 12944 6941 12945 6241 12945 6265 12945 6941 12946 6937 12946 6241 12946 6941 12947 6265 12947 6939 12947 6941 12948 6935 12948 6937 12948 6941 12949 6939 12949 6935 12949 6942 12950 6934 12950 6938 12950 6943 12951 6927 12951 6913 12951 6943 12952 6913 12952 6934 12952 6943 12953 6934 12953 6942 12953 6944 12954 6936 12954 6927 12954 6945 12955 995 12955 993 12955 6945 12956 997 12956 995 12956 6945 12957 6920 12957 997 12957 6945 12958 993 12958 6920 12958 6946 12959 6936 12959 6944 12959 6946 12960 6940 12960 6936 12960 6947 12961 6719 12961 6948 12961 6949 12962 6943 12962 6942 12962 6950 12963 6944 12963 6927 12963 6951 12964 6701 12964 6719 12964 6950 12965 6927 12965 6943 12965 6950 12966 6943 12966 6949 12966 6951 12967 6719 12967 6947 12967 6952 12968 6948 12968 6921 12968 6953 12969 6673 12969 6681 12969 6953 12970 6681 12970 6940 12970 6952 12971 6947 12971 6948 12971 6923 12972 6950 12972 6949 12972 6954 12973 6701 12973 6951 12973 6955 12974 6810 12974 6659 12974 6955 12975 6659 12975 6673 12975 6955 12976 6673 12976 6953 12976 6956 12977 993 12977 992 12977 6956 12978 6938 12978 993 12978 6956 12979 6942 12979 6938 12979 6914 12980 6701 12980 6954 12980 6957 12981 6946 12981 6944 12981 6957 12982 6950 12982 6923 12982 6957 12983 6944 12983 6950 12983 6907 12984 6951 12984 6947 12984 6911 12985 6940 12985 6946 12985 6911 12986 6953 12986 6940 12986 6907 12987 6947 12987 6952 12987 6931 12988 6951 12988 6907 12988 6910 12989 6810 12989 6955 12989 6910 12990 6955 12990 6953 12990 6931 12991 6954 12991 6951 12991 6910 12992 6953 12992 6911 12992 6912 12993 6946 12993 6957 12993 6912 12994 6911 12994 6946 12994 6917 12995 6689 12995 6701 12995 6917 12996 6701 12996 6914 12996 6924 12997 6957 12997 6923 12997 6924 12998 6912 12998 6957 12998 6915 12999 6914 12999 6954 12999 6958 13000 6949 13000 6942 13000 6915 13001 6954 13001 6931 13001 6958 13002 6942 13002 6956 13002 6958 13003 6956 13003 992 13003 6905 13004 992 13004 990 13004 6905 13005 6958 13005 992 13005 6908 13006 6907 13006 6952 13006 6908 13007 6952 13007 6921 13007 6919 13008 6912 13008 6924 13008 6904 13009 6923 13009 6949 13009 6928 13010 6689 13010 6917 13010 6904 13011 6949 13011 6958 13011 6904 13012 6958 13012 6905 13012 6903 13013 990 13013 6242 13013 6903 13014 6905 13014 990 13014 6906 13015 6931 13015 6907 13015 2196 13016 47 13016 53 13016 2196 13017 53 13017 4749 13017 4747 13018 6817 13018 6811 13018 4746 13019 6809 13019 6817 13019 4746 13020 6817 13020 4747 13020 4748 13021 6656 13021 6809 13021 4748 13022 6809 13022 4746 13022 4749 13023 6656 13023 4748 13023 62 13024 6654 13024 6656 13024 62 13025 4749 13025 53 13025 62 13026 6656 13026 4749 13026 67 13027 6652 13027 6654 13027 67 13028 6654 13028 62 13028 27 13029 6649 13029 6652 13029 27 13030 6652 13030 67 13030 2 13031 6647 13031 6649 13031 2 13032 6649 13032 27 13032 1 13033 6739 13033 6648 13033 1 13034 6741 13034 6739 13034 1 13035 6648 13035 6647 13035 1 13036 6647 13036 2 13036 6744 13037 6741 13037 1 13037 42 13038 6744 13038 1 13038 51 13039 6744 13039 42 13039 2201 13040 59 13040 64 13040 2201 13041 51 13041 59 13041 2201 13042 6744 13042 51 13042 4753 13043 6744 13043 2201 13043 4752 13044 6744 13044 4753 13044 4751 13045 6744 13045 4752 13045 3762 13046 4745 13046 6811 13046 4745 13047 4747 13047 6811 13047 3954 13048 3951 13048 4733 13048 6644 13049 3954 13049 4733 13049 6645 13050 6644 13050 4733 13050 6618 13051 4733 13051 4739 13051 6609 13052 4733 13052 6618 13052 6608 13053 6645 13053 4733 13053 6608 13054 4733 13054 6609 13054 4732 13055 6534 13055 4736 13055 4732 13056 6584 13056 6534 13056 4732 13057 6578 13057 6584 13057 4732 13058 6579 13058 6578 13058 4732 13059 3930 13059 6579 13059 3925 13060 3930 13060 4732 13060 6382 13061 4756 13061 4757 13061 2199 13062 6382 13062 4757 13062 142 13063 6396 13063 6382 13063 142 13064 6398 13064 6396 13064 142 13065 6381 13065 6398 13065 133 13066 142 13066 6382 13066 79 13067 6379 13067 6381 13067 79 13068 6381 13068 142 13068 125 13069 6382 13069 2199 13069 125 13070 133 13070 6382 13070 81 13071 6377 13071 6379 13071 81 13072 6379 13072 79 13072 117 13073 125 13073 2199 13073 91 13074 6376 13074 6377 13074 91 13075 6374 13075 6376 13075 91 13076 6377 13076 81 13076 108 13077 117 13077 2199 13077 99 13078 6372 13078 6374 13078 99 13079 6374 13079 91 13079 107 13080 6362 13080 6372 13080 107 13081 6372 13081 99 13081 2197 13082 107 13082 115 13082 4728 13083 6356 13083 6362 13083 4728 13084 6362 13084 107 13084 4728 13085 107 13085 2197 13085 4730 13086 6356 13086 4728 13086 4731 13087 6356 13087 4730 13087 6369 13088 6356 13088 4731 13088 6363 13089 6369 13089 4731 13089 6382 13090 4754 13090 4756 13090 6363 13091 4731 13091 4729 13091 6363 13092 4729 13092 4223 13092 1073 13093 792 13093 1069 13093 1069 13094 792 13094 794 13094 807 13095 1042 13095 1044 13095 824 13096 807 13096 1044 13096 1055 13097 1060 13097 787 13097 1069 13098 794 13098 1062 13098 1051 13099 1055 13099 783 13099 1055 13100 787 13100 783 13100 794 13101 814 13101 1062 13101 1060 13102 1063 13102 788 13102 787 13103 1060 13103 788 13103 1048 13104 1051 13104 782 13104 1051 13105 783 13105 782 13105 824 13106 1044 13106 1046 13106 796 13107 824 13107 1046 13107 1062 13108 814 13108 1059 13108 1063 13109 1028 13109 812 13109 814 13110 815 13110 1059 13110 788 13111 1063 13111 812 13111 1040 13112 1048 13112 781 13112 796 13113 1046 13113 1049 13113 1048 13114 782 13114 781 13114 819 13115 796 13115 1049 13115 1059 13116 815 13116 1056 13116 815 13117 816 13117 1056 13117 812 13118 1028 13118 778 13118 816 13119 819 13119 1054 13119 819 13120 1049 13120 1054 13120 1056 13121 816 13121 1054 13121 1035 13122 1040 13122 837 13122 1040 13123 781 13123 837 13123 778 13124 1028 13124 1029 13124 778 13125 1029 13125 843 13125 1031 13126 1035 13126 836 13126 1035 13127 837 13127 836 13127 843 13128 1029 13128 1033 13128 843 13129 1033 13129 842 13129 1031 13130 836 13130 829 13130 1031 13131 829 13131 1024 13131 842 13132 1033 13132 1037 13132 842 13133 1037 13133 834 13133 1024 13134 829 13134 828 13134 1024 13135 828 13135 1025 13135 834 13136 1037 13136 1039 13136 834 13137 1039 13137 833 13137 1025 13138 828 13138 793 13138 1025 13139 793 13139 1073 13139 833 13140 1039 13140 1042 13140 807 13141 833 13141 1042 13141 1073 13142 793 13142 792 13142 1020 13143 657 13143 1019 13143 1019 13144 657 13144 659 13144 674 13145 991 13145 994 13145 691 13146 674 13146 994 13146 1019 13147 659 13147 1017 13147 659 13148 681 13148 1017 13148 1002 13149 1007 13149 654 13149 999 13150 1002 13150 650 13150 1002 13151 654 13151 650 13151 1007 13152 1012 13152 655 13152 691 13153 994 13153 998 13153 654 13154 1007 13154 655 13154 981 13155 999 13155 649 13155 663 13156 691 13156 998 13156 999 13157 650 13157 649 13157 1017 13158 681 13158 1014 13158 681 13159 682 13159 1014 13159 1012 13160 976 13160 679 13160 663 13161 998 13161 1004 13161 655 13162 1012 13162 679 13162 686 13163 663 13163 1004 13163 974 13164 981 13164 648 13164 1014 13165 682 13165 1010 13165 682 13166 683 13166 1010 13166 981 13167 649 13167 648 13167 683 13168 686 13168 1005 13168 686 13169 1004 13169 1005 13169 1010 13170 683 13170 1005 13170 679 13171 976 13171 645 13171 975 13172 974 13172 704 13172 974 13173 648 13173 704 13173 645 13174 976 13174 980 13174 645 13175 980 13175 710 13175 1023 13176 975 13176 703 13176 975 13177 704 13177 703 13177 710 13178 980 13178 984 13178 710 13179 984 13179 709 13179 1023 13180 703 13180 696 13180 1023 13181 696 13181 1022 13181 709 13182 984 13182 987 13182 709 13183 987 13183 701 13183 1022 13184 696 13184 695 13184 1022 13185 695 13185 1021 13185 701 13186 987 13186 989 13186 701 13187 989 13187 700 13187 1021 13188 695 13188 658 13188 1021 13189 658 13189 1020 13189 700 13190 989 13190 991 13190 674 13191 700 13191 991 13191 1020 13192 658 13192 657 13192 969 13193 236 13193 963 13193 223 13194 936 13194 942 13194 963 13195 236 13195 960 13195 234 13196 233 13196 960 13196 236 13197 234 13197 960 13197 931 13198 938 13198 209 13198 223 13199 942 13199 947 13199 225 13200 223 13200 947 13200 927 13201 931 13201 203 13201 931 13202 209 13202 203 13202 938 13203 945 13203 213 13203 233 13204 231 13204 959 13204 945 13205 949 13205 213 13205 960 13206 233 13206 959 13206 209 13207 938 13207 213 13207 227 13208 225 13208 952 13208 225 13209 947 13209 952 13209 231 13210 229 13210 958 13210 959 13211 231 13211 958 13211 927 13212 203 13212 201 13212 227 13213 952 13213 955 13213 229 13214 227 13214 955 13214 958 13215 229 13215 955 13215 213 13216 949 13216 217 13216 920 13217 924 13217 198 13217 924 13218 927 13218 198 13218 927 13219 201 13219 198 13219 917 13220 916 13220 207 13220 949 13221 917 13221 207 13221 217 13222 949 13222 207 13222 911 13223 920 13223 199 13223 920 13224 198 13224 199 13224 207 13225 916 13225 206 13225 911 13226 199 13226 245 13226 916 13227 922 13227 211 13227 206 13228 916 13228 211 13228 911 13229 245 13229 912 13229 912 13230 245 13230 243 13230 922 13231 929 13231 215 13231 211 13232 922 13232 215 13232 243 13233 241 13233 972 13233 912 13234 243 13234 972 13234 215 13235 929 13235 933 13235 219 13236 215 13236 933 13236 972 13237 241 13237 238 13237 219 13238 933 13238 221 13238 972 13239 238 13239 969 13239 238 13240 236 13240 969 13240 221 13241 933 13241 936 13241 223 13242 221 13242 936 13242 171 13243 867 13243 872 13243 173 13244 171 13244 872 13244 852 13245 186 13245 853 13245 173 13246 872 13246 881 13246 175 13247 173 13247 881 13247 853 13248 186 13248 906 13248 184 13249 183 13249 906 13249 186 13250 184 13250 906 13250 175 13251 881 13251 886 13251 884 13252 890 13252 153 13252 890 13253 159 13253 153 13253 890 13254 893 13254 163 13254 893 13255 898 13255 163 13255 183 13256 181 13256 903 13256 159 13257 890 13257 163 13257 906 13258 183 13258 903 13258 177 13259 175 13259 888 13259 179 13260 177 13260 888 13260 175 13261 886 13261 888 13261 879 13262 884 13262 151 13262 884 13263 153 13263 151 13263 903 13264 181 13264 900 13264 900 13265 181 13265 895 13265 181 13266 179 13266 895 13266 179 13267 888 13267 895 13267 163 13268 898 13268 167 13268 870 13269 875 13269 148 13269 875 13270 879 13270 148 13270 879 13271 151 13271 148 13271 849 13272 848 13272 157 13272 898 13273 849 13273 157 13273 167 13274 898 13274 157 13274 870 13275 148 13275 149 13275 157 13276 848 13276 156 13276 156 13277 848 13277 855 13277 865 13278 870 13278 195 13278 870 13279 149 13279 195 13279 156 13280 855 13280 161 13280 865 13281 195 13281 859 13281 859 13282 195 13282 193 13282 855 13283 861 13283 165 13283 161 13284 855 13284 165 13284 193 13285 191 13285 857 13285 859 13286 193 13286 857 13286 165 13287 861 13287 867 13287 169 13288 165 13288 867 13288 857 13289 191 13289 188 13289 169 13290 867 13290 171 13290 857 13291 188 13291 852 13291 188 13292 186 13292 852 13292 6959 13293 6960 13293 6961 13293 6961 13294 6960 13294 6962 13294 6960 13295 6963 13295 6964 13295 6962 13296 6960 13296 6964 13296 6963 13297 6965 13297 6966 13297 6964 13298 6963 13298 6966 13298 6967 13299 6959 13299 6968 13299 6959 13300 6961 13300 6968 13300 6968 13301 6961 13301 6969 13301 6961 13302 6962 13302 6969 13302 6969 13303 6962 13303 6970 13303 6962 13304 6964 13304 6970 13304 6965 13305 6971 13305 6972 13305 6964 13306 6966 13306 6972 13306 6966 13307 6965 13307 6972 13307 6970 13308 6964 13308 6972 13308 6973 13309 6967 13309 6974 13309 6975 13310 6973 13310 6974 13310 6967 13311 6968 13311 6974 13311 6968 13312 6969 13312 6976 13312 6974 13313 6968 13313 6976 13313 6976 13314 6969 13314 6977 13314 6969 13315 6970 13315 6977 13315 6971 13316 6978 13316 6979 13316 6978 13317 6980 13317 6979 13317 6972 13318 6971 13318 6979 13318 6970 13319 6972 13319 6979 13319 6977 13320 6970 13320 6979 13320 6981 13321 6975 13321 6982 13321 6975 13322 6974 13322 6982 13322 6974 13323 6976 13323 6982 13323 6983 13324 6981 13324 6984 13324 6981 13325 6982 13325 6984 13325 6976 13326 6977 13326 6984 13326 6982 13327 6976 13327 6984 13327 6983 13328 6984 13328 6985 13328 6977 13329 6979 13329 6985 13329 6984 13330 6977 13330 6985 13330 6980 13331 6983 13331 6986 13331 6979 13332 6980 13332 6986 13332 6983 13333 6985 13333 6986 13333 6985 13334 6979 13334 6986 13334 6963 13335 6960 13335 6987 13335 6960 13336 6988 13336 6987 13336 6989 13337 6990 13337 6987 13337 6988 13338 6989 13338 6987 13338 6991 13339 6992 13339 6990 13339 6989 13340 6991 13340 6990 13340 6993 13341 6994 13341 6995 13341 6996 13342 6993 13342 6995 13342 6991 13343 6996 13343 6992 13343 6996 13344 6995 13344 6992 13344 6997 13345 6998 13345 6999 13345 7000 13346 6997 13346 6999 13346 7001 13347 7000 13347 7002 13347 7000 13348 6999 13348 7002 13348 7003 13349 7001 13349 7004 13349 7001 13350 7002 13350 7004 13350 7005 13351 7003 13351 7006 13351 7003 13352 7004 13352 7006 13352 7007 13353 7005 13353 7008 13353 7005 13354 7006 13354 7008 13354 6993 13355 7007 13355 6994 13355 7007 13356 7008 13356 6994 13356 7009 13357 7010 13357 7011 13357 7012 13358 7009 13358 7011 13358 7013 13359 7012 13359 7014 13359 7012 13360 7011 13360 7014 13360 7015 13361 7013 13361 7016 13361 7013 13362 7014 13362 7016 13362 6997 13363 7015 13363 6998 13363 7015 13364 7016 13364 6998 13364 7017 13365 7018 13365 7019 13365 7020 13366 7017 13366 7019 13366 7020 13367 7019 13367 7009 13367 7009 13368 7019 13368 7010 13368 7021 13369 7018 13369 7017 13369 7022 13370 7021 13370 7017 13370 7023 13371 7024 13371 7022 13371 7022 13372 7024 13372 7021 13372 7025 13373 7026 13373 7027 13373 7027 13374 7026 13374 7028 13374 7027 13375 7028 13375 7023 13375 7023 13376 7028 13376 7024 13376 7029 13377 7026 13377 7025 13377 7030 13378 7029 13378 7025 13378 7031 13379 7032 13379 7029 13379 7031 13380 7029 13380 7030 13380 7033 13381 7034 13381 7035 13381 7036 13382 7033 13382 7035 13382 7031 13383 7036 13383 7032 13383 7036 13384 7035 13384 7032 13384 7037 13385 7038 13385 7034 13385 7033 13386 7037 13386 7034 13386 7039 13387 7040 13387 7038 13387 7039 13388 7038 13388 7037 13388 7041 13389 7040 13389 7039 13389 7042 13390 7041 13390 7039 13390 7043 13391 7044 13391 7045 13391 7046 13392 7043 13392 7045 13392 7047 13393 7046 13393 7048 13393 7046 13394 7045 13394 7048 13394 7049 13395 7047 13395 7050 13395 7047 13396 7048 13396 7050 13396 7049 13397 7050 13397 7051 13397 7051 13398 7050 13398 7052 13398 7042 13399 7051 13399 7041 13399 7051 13400 7052 13400 7041 13400 7053 13401 7044 13401 7043 13401 7054 13402 7053 13402 7043 13402 7055 13403 7053 13403 7054 13403 7056 13404 7055 13404 7054 13404 7055 13405 7056 13405 7057 13405 7056 13406 7058 13406 7057 13406 7059 13407 7060 13407 7061 13407 7061 13408 7060 13408 7062 13408 7061 13409 7062 13409 7063 13409 7063 13410 7062 13410 7064 13410 7065 13411 7063 13411 7066 13411 7063 13412 7064 13412 7066 13412 7065 13413 7066 13413 7067 13413 7067 13414 7066 13414 7068 13414 7058 13415 7067 13415 7057 13415 7067 13416 7068 13416 7057 13416 7060 13417 7059 13417 6981 13417 7060 13418 6981 13418 6983 13418 6975 13419 7069 13419 6989 13419 7017 13420 7070 13420 7071 13420 6975 13421 6989 13421 6973 13421 7012 13422 7013 13422 7072 13422 7073 13423 7012 13423 7072 13423 7030 13424 7025 13424 7027 13424 7017 13425 7071 13425 7074 13425 7030 13426 7027 13426 7031 13426 7037 13427 7017 13427 7074 13427 7031 13428 7027 13428 7023 13428 7013 13429 7015 13429 7075 13429 6960 13430 6959 13430 6988 13430 7072 13431 7013 13431 7075 13431 7031 13432 7023 13432 7036 13432 6959 13433 6967 13433 6988 13433 6967 13434 6973 13434 6988 13434 7036 13435 7023 13435 7033 13435 6973 13436 6989 13436 6988 13436 7022 13437 7037 13437 7033 13437 7037 13438 7074 13438 7076 13438 7075 13439 7015 13439 7077 13439 7015 13440 6997 13440 7077 13440 7054 13441 7043 13441 7046 13441 7077 13442 6997 13442 7078 13442 7039 13443 7037 13443 7079 13443 7054 13444 7046 13444 7047 13444 7037 13445 7076 13445 7079 13445 7039 13446 7079 13446 7080 13446 7054 13447 7047 13447 7049 13447 6997 13448 7000 13448 7081 13448 7000 13449 7001 13449 7081 13449 7078 13450 6997 13450 7081 13450 7001 13451 7003 13451 7082 13451 7081 13452 7001 13452 7082 13452 7082 13453 7003 13453 7083 13453 7061 13454 7042 13454 7059 13454 7039 13455 7080 13455 7059 13455 7042 13456 7039 13456 7059 13456 7056 13457 7065 13457 7067 13457 7083 13458 7003 13458 7005 13458 7056 13459 7067 13459 7058 13459 7056 13460 7054 13460 7063 13460 7065 13461 7056 13461 7063 13461 7083 13462 7005 13462 7084 13462 7054 13463 7049 13463 7063 13463 7063 13464 7049 13464 7061 13464 7049 13465 7051 13465 7061 13465 7084 13466 7005 13466 7007 13466 7033 13467 7023 13467 7022 13467 7059 13468 7080 13468 6981 13468 7085 13469 7084 13469 6993 13469 7061 13470 7051 13470 7042 13470 7084 13471 7007 13471 6993 13471 7022 13472 7017 13472 7037 13472 6981 13473 7080 13473 7069 13473 7086 13474 7085 13474 6996 13474 7087 13475 7086 13475 6996 13475 7088 13476 7087 13476 6996 13476 7017 13477 7020 13477 7070 13477 7085 13478 6993 13478 6996 13478 7020 13479 7009 13479 7070 13479 7069 13480 7088 13480 6991 13480 7088 13481 6996 13481 6991 13481 7070 13482 7009 13482 7073 13482 6981 13483 7069 13483 6975 13483 7009 13484 7012 13484 7073 13484 7069 13485 6991 13485 6989 13485 7089 13486 7090 13486 7078 13486 7089 13487 7078 13487 7081 13487 7082 13488 7089 13488 7081 13488 7091 13489 7089 13489 7082 13489 7092 13490 7082 13490 7083 13490 7092 13491 7091 13491 7082 13491 7093 13492 7083 13492 7084 13492 7093 13493 7092 13493 7083 13493 7085 13494 7093 13494 7084 13494 7094 13495 7093 13495 7085 13495 7095 13496 7085 13496 7086 13496 7095 13497 7094 13497 7085 13497 7096 13498 7086 13498 7087 13498 7096 13499 7095 13499 7086 13499 7097 13500 7087 13500 7088 13500 7097 13501 7096 13501 7087 13501 7078 13502 7090 13502 7098 13502 7078 13503 7098 13503 7077 13503 7099 13504 7100 13504 7071 13504 7099 13505 7071 13505 7070 13505 7101 13506 7070 13506 7073 13506 7101 13507 7099 13507 7070 13507 7102 13508 7073 13508 7072 13508 7102 13509 7101 13509 7073 13509 7103 13510 7072 13510 7075 13510 7103 13511 7102 13511 7072 13511 7098 13512 7075 13512 7077 13512 7098 13513 7103 13513 7075 13513 7076 13514 7104 13514 7079 13514 7105 13515 7104 13515 7076 13515 7074 13516 7105 13516 7076 13516 7106 13517 7105 13517 7074 13517 7071 13518 7106 13518 7074 13518 7100 13519 7106 13519 7071 13519 7104 13520 7107 13520 7080 13520 7104 13521 7080 13521 7079 13521 7108 13522 7069 13522 7080 13522 7108 13523 7080 13523 7107 13523 7069 13524 7097 13524 7088 13524 7108 13525 7097 13525 7069 13525 7101 13526 7100 13526 7099 13526 7102 13527 7100 13527 7101 13527 7108 13528 7107 13528 7104 13528 7103 13529 7106 13529 7100 13529 7103 13530 7100 13530 7102 13530 7097 13531 7104 13531 7105 13531 7097 13532 7105 13532 7106 13532 7097 13533 7108 13533 7104 13533 7097 13534 7106 13534 7103 13534 7098 13535 7097 13535 7103 13535 7096 13536 7098 13536 7090 13536 7096 13537 7097 13537 7098 13537 7095 13538 7096 13538 7090 13538 7089 13539 7095 13539 7090 13539 7094 13540 7095 13540 7089 13540 7091 13541 7094 13541 7089 13541 7093 13542 7094 13542 7091 13542 7092 13543 7093 13543 7091 13543 7109 13544 7110 13544 7111 13544 7112 13545 7109 13545 7111 13545 7112 13546 7111 13546 7113 13546 7113 13547 7111 13547 7114 13547 7113 13548 7114 13548 7115 13548 7115 13549 7114 13549 7116 13549 7115 13550 7116 13550 7117 13550 7117 13551 7116 13551 7118 13551 7117 13552 7118 13552 7119 13552 7119 13553 7118 13553 7120 13553 7121 13554 7119 13554 7122 13554 7119 13555 7120 13555 7122 13555 7121 13556 7122 13556 7123 13556 7123 13557 7122 13557 7124 13557 7125 13558 7126 13558 7127 13558 7127 13559 7126 13559 7128 13559 7127 13560 7128 13560 7129 13560 7129 13561 7128 13561 7130 13561 7129 13562 7130 13562 7131 13562 7131 13563 7130 13563 7132 13563 7131 13564 7132 13564 7133 13564 7133 13565 7132 13565 7134 13565 7133 13566 7134 13566 7135 13566 7135 13567 7134 13567 7136 13567 7135 13568 7136 13568 7137 13568 7137 13569 7136 13569 7138 13569 7109 13570 7137 13570 7110 13570 7137 13571 7138 13571 7110 13571 7139 13572 7140 13572 7141 13572 7141 13573 7140 13573 7142 13573 7141 13574 7142 13574 7143 13574 7143 13575 7142 13575 7144 13575 7143 13576 7144 13576 7145 13576 7145 13577 7144 13577 7146 13577 7147 13578 7145 13578 7148 13578 7145 13579 7146 13579 7148 13579 7147 13580 7148 13580 7149 13580 7149 13581 7148 13581 7150 13581 7151 13582 7149 13582 7152 13582 7149 13583 7150 13583 7152 13583 7151 13584 7152 13584 7125 13584 7125 13585 7152 13585 7126 13585 7153 13586 7154 13586 7155 13586 7156 13587 7153 13587 7155 13587 7157 13588 7156 13588 7158 13588 7156 13589 7155 13589 7158 13589 7159 13590 7157 13590 7160 13590 7157 13591 7158 13591 7160 13591 7161 13592 7159 13592 7162 13592 7159 13593 7160 13593 7162 13593 7163 13594 7161 13594 7164 13594 7161 13595 7162 13595 7164 13595 7165 13596 7163 13596 7166 13596 7163 13597 7164 13597 7166 13597 7165 13598 7166 13598 7167 13598 7167 13599 7166 13599 7168 13599 7139 13600 7167 13600 7140 13600 7167 13601 7168 13601 7140 13601 7124 13602 7154 13602 7153 13602 7123 13603 7124 13603 7153 13603 7117 13604 7169 13604 7115 13604 7117 13605 7170 13605 7169 13605 7143 13606 7145 13606 7171 13606 7143 13607 7171 13607 7172 13607 7119 13608 7170 13608 7117 13608 7119 13609 7173 13609 7170 13609 7174 13610 7131 13610 7133 13610 7119 13611 7175 13611 7173 13611 7174 13612 7176 13612 7131 13612 7177 13613 7129 13613 7131 13613 7177 13614 7131 13614 7176 13614 7178 13615 7133 13615 7135 13615 7178 13616 7174 13616 7133 13616 7179 13617 7135 13617 7137 13617 7141 13618 7143 13618 7172 13618 7141 13619 7172 13619 7180 13619 7179 13620 7178 13620 7135 13620 7181 13621 7127 13621 7129 13621 7181 13622 7129 13622 7177 13622 7121 13623 7182 13623 7175 13623 7121 13624 7175 13624 7119 13624 7183 13625 7137 13625 7109 13625 7183 13626 7179 13626 7137 13626 7184 13627 7183 13627 7109 13627 7185 13628 7151 13628 7125 13628 7185 13629 7125 13629 7127 13629 7185 13630 7127 13630 7181 13630 7139 13631 7180 13631 7186 13631 7139 13632 7141 13632 7180 13632 7187 13633 7149 13633 7151 13633 7187 13634 7151 13634 7185 13634 7188 13635 7109 13635 7112 13635 7123 13636 7182 13636 7121 13636 7123 13637 7189 13637 7182 13637 7188 13638 7184 13638 7109 13638 7153 13639 7189 13639 7123 13639 7153 13640 7190 13640 7189 13640 7191 13641 7149 13641 7187 13641 7167 13642 7139 13642 7186 13642 7192 13643 7112 13643 7113 13643 7192 13644 7188 13644 7112 13644 7167 13645 7186 13645 7193 13645 7147 13646 7149 13646 7191 13646 7156 13647 7190 13647 7153 13647 7194 13648 7192 13648 7113 13648 7165 13649 7193 13649 7195 13649 7165 13650 7167 13650 7193 13650 7163 13651 7165 13651 7195 13651 7163 13652 7195 13652 7196 13652 7197 13653 7147 13653 7191 13653 7157 13654 7198 13654 7190 13654 7115 13655 7194 13655 7113 13655 7157 13656 7190 13656 7156 13656 7161 13657 7196 13657 7199 13657 7169 13658 7194 13658 7115 13658 7161 13659 7163 13659 7196 13659 7159 13660 7199 13660 7198 13660 7159 13661 7161 13661 7199 13661 7159 13662 7198 13662 7157 13662 7145 13663 7147 13663 7197 13663 7171 13664 7145 13664 7197 13664 7190 13665 7200 13665 7189 13665 7201 13666 7200 13666 7190 13666 7198 13667 7201 13667 7190 13667 7202 13668 7201 13668 7198 13668 7199 13669 7202 13669 7198 13669 7203 13670 7202 13670 7199 13670 7204 13671 7199 13671 7196 13671 7204 13672 7203 13672 7199 13672 7195 13673 7204 13673 7196 13673 7205 13674 7204 13674 7195 13674 7206 13675 7195 13675 7193 13675 7206 13676 7205 13676 7195 13676 7207 13677 7193 13677 7186 13677 7207 13678 7206 13678 7193 13678 7189 13679 7200 13679 7208 13679 7189 13680 7208 13680 7182 13680 7209 13681 7210 13681 7184 13681 7209 13682 7184 13682 7188 13682 7211 13683 7188 13683 7192 13683 7211 13684 7209 13684 7188 13684 7212 13685 7192 13685 7194 13685 7212 13686 7211 13686 7192 13686 7169 13687 7212 13687 7194 13687 7213 13688 7212 13688 7169 13688 7214 13689 7169 13689 7170 13689 7214 13690 7213 13690 7169 13690 7215 13691 7170 13691 7173 13691 7215 13692 7214 13692 7170 13692 7175 13693 7215 13693 7173 13693 7216 13694 7215 13694 7175 13694 7182 13695 7216 13695 7175 13695 7208 13696 7216 13696 7182 13696 7217 13697 7218 13697 7185 13697 7217 13698 7185 13698 7181 13698 7177 13699 7217 13699 7181 13699 7219 13700 7217 13700 7177 13700 7220 13701 7177 13701 7176 13701 7220 13702 7219 13702 7177 13702 7221 13703 7176 13703 7174 13703 7221 13704 7220 13704 7176 13704 7222 13705 7174 13705 7178 13705 7222 13706 7221 13706 7174 13706 7223 13707 7178 13707 7179 13707 7223 13708 7222 13708 7178 13708 7224 13709 7179 13709 7183 13709 7224 13710 7223 13710 7179 13710 7210 13711 7183 13711 7184 13711 7210 13712 7224 13712 7183 13712 7225 13713 7207 13713 7186 13713 7225 13714 7186 13714 7180 13714 7226 13715 7180 13715 7172 13715 7226 13716 7225 13716 7180 13716 7171 13717 7226 13717 7172 13717 7227 13718 7226 13718 7171 13718 7228 13719 7171 13719 7197 13719 7228 13720 7227 13720 7171 13720 7191 13721 7228 13721 7197 13721 7229 13722 7228 13722 7191 13722 7187 13723 7229 13723 7191 13723 7230 13724 7229 13724 7187 13724 7218 13725 7187 13725 7185 13725 7218 13726 7230 13726 7187 13726 7223 13727 7220 13727 7221 13727 7223 13728 7221 13728 7222 13728 7224 13729 7219 13729 7220 13729 7224 13730 7220 13730 7223 13730 7212 13731 7209 13731 7211 13731 7213 13732 7209 13732 7212 13732 7214 13733 7210 13733 7209 13733 7214 13734 7209 13734 7213 13734 7215 13735 7217 13735 7219 13735 7215 13736 7224 13736 7210 13736 7215 13737 7219 13737 7224 13737 7215 13738 7210 13738 7214 13738 7225 13739 7226 13739 7227 13739 7225 13740 7227 13740 7228 13740 7225 13741 7228 13741 7229 13741 7216 13742 7218 13742 7217 13742 7216 13743 7217 13743 7215 13743 7208 13744 7218 13744 7216 13744 7200 13745 7230 13745 7218 13745 7200 13746 7218 13746 7208 13746 7207 13747 7225 13747 7229 13747 7201 13748 7229 13748 7230 13748 7201 13749 7230 13749 7200 13749 7202 13750 7207 13750 7229 13750 7202 13751 7229 13751 7201 13751 7204 13752 7205 13752 7206 13752 7203 13753 7206 13753 7207 13753 7203 13754 7207 13754 7202 13754 7203 13755 7204 13755 7206 13755 7231 13756 7232 13756 7233 13756 7234 13757 7231 13757 7233 13757 7235 13758 7234 13758 7236 13758 7234 13759 7233 13759 7236 13759 7235 13760 7236 13760 7237 13760 7237 13761 7236 13761 7238 13761 7237 13762 7238 13762 7239 13762 7239 13763 7238 13763 7240 13763 7239 13764 7240 13764 7241 13764 7241 13765 7240 13765 7242 13765 7243 13766 7244 13766 7245 13766 7245 13767 7244 13767 7246 13767 7247 13768 7245 13768 7248 13768 7245 13769 7246 13769 7248 13769 7231 13770 7247 13770 7232 13770 7247 13771 7248 13771 7232 13771 7249 13772 7250 13772 7244 13772 7243 13773 7249 13773 7244 13773 7251 13774 7252 13774 7250 13774 7249 13775 7251 13775 7250 13775 7252 13776 7251 13776 7253 13776 7251 13777 7254 13777 7253 13777 7255 13778 7256 13778 7257 13778 7258 13779 7255 13779 7257 13779 7259 13780 7258 13780 7260 13780 7258 13781 7257 13781 7260 13781 7261 13782 7259 13782 7262 13782 7259 13783 7260 13783 7262 13783 7263 13784 7261 13784 7264 13784 7261 13785 7262 13785 7264 13785 7265 13786 7263 13786 7266 13786 7263 13787 7264 13787 7266 13787 7254 13788 7265 13788 7253 13788 7265 13789 7266 13789 7253 13789 7256 13790 7255 13790 7267 13790 7256 13791 7267 13791 7268 13791 7269 13792 7270 13792 7271 13792 7272 13793 7269 13793 7271 13793 7273 13794 7272 13794 7274 13794 7272 13795 7271 13795 7274 13795 7275 13796 7273 13796 7276 13796 7273 13797 7274 13797 7276 13797 7277 13798 7275 13798 7278 13798 7275 13799 7276 13799 7278 13799 7267 13800 7277 13800 7268 13800 7277 13801 7278 13801 7268 13801 7270 13802 7269 13802 7279 13802 7269 13803 7280 13803 7279 13803 7281 13804 7282 13804 7279 13804 7280 13805 7281 13805 7279 13805 7283 13806 7284 13806 7282 13806 7281 13807 7283 13807 7282 13807 7285 13808 7286 13808 7287 13808 7288 13809 7285 13809 7287 13809 7283 13810 7288 13810 7284 13810 7288 13811 7287 13811 7284 13811 7289 13812 7290 13812 7291 13812 7291 13813 7290 13813 7292 13813 7293 13814 7291 13814 7294 13814 7291 13815 7292 13815 7294 13815 7293 13816 7294 13816 7295 13816 7295 13817 7294 13817 7296 13817 7295 13818 7296 13818 7297 13818 7297 13819 7296 13819 7298 13819 7297 13820 7298 13820 7299 13820 7299 13821 7298 13821 7300 13821 7299 13822 7300 13822 7301 13822 7301 13823 7300 13823 7302 13823 7285 13824 7301 13824 7286 13824 7301 13825 7302 13825 7286 13825 7303 13826 7304 13826 7305 13826 7305 13827 7304 13827 7306 13827 7305 13828 7306 13828 7307 13828 7307 13829 7306 13829 7308 13829 7307 13830 7308 13830 7309 13830 7309 13831 7308 13831 7310 13831 7311 13832 7309 13832 7312 13832 7309 13833 7310 13833 7312 13833 7313 13834 7311 13834 7314 13834 7311 13835 7312 13835 7314 13835 7313 13836 7314 13836 7289 13836 7289 13837 7314 13837 7290 13837 7315 13838 7304 13838 7303 13838 7316 13839 7315 13839 7303 13839 7317 13840 7318 13840 7319 13840 7319 13841 7318 13841 7320 13841 7319 13842 7320 13842 7321 13842 7321 13843 7320 13843 7322 13843 7321 13844 7322 13844 7323 13844 7323 13845 7322 13845 7324 13845 7325 13846 7323 13846 7326 13846 7323 13847 7324 13847 7326 13847 7325 13848 7326 13848 7327 13848 7327 13849 7326 13849 7328 13849 7327 13850 7328 13850 7316 13850 7316 13851 7328 13851 7315 13851 7242 13852 7318 13852 7317 13852 7241 13853 7242 13853 7317 13853 7285 13854 7288 13854 7329 13854 7325 13855 7330 13855 7331 13855 7301 13856 7285 13856 7332 13856 7323 13857 7333 13857 7321 13857 7323 13858 7325 13858 7331 13858 7323 13859 7331 13859 7333 13859 7280 13860 7269 13860 7272 13860 7280 13861 7272 13861 7273 13861 7293 13862 7334 13862 7291 13862 7265 13863 7254 13863 7251 13863 7299 13864 7332 13864 7335 13864 7299 13865 7301 13865 7332 13865 7263 13866 7265 13866 7251 13866 7295 13867 7335 13867 7334 13867 7305 13868 7336 13868 7303 13868 7295 13869 7334 13869 7293 13869 7261 13870 7263 13870 7251 13870 7337 13871 7336 13871 7305 13871 7297 13872 7299 13872 7335 13872 7297 13873 7335 13873 7295 13873 7249 13874 7261 13874 7251 13874 7338 13875 7277 13875 7267 13875 7249 13876 7258 13876 7259 13876 7249 13877 7259 13877 7261 13877 7338 13878 7267 13878 7339 13878 7339 13879 7267 13879 7340 13879 7307 13880 7337 13880 7305 13880 7237 13881 7341 13881 7235 13881 7307 13882 7342 13882 7337 13882 7343 13883 7344 13883 7249 13883 7237 13884 7345 13884 7341 13884 7343 13885 7249 13885 7243 13885 7346 13886 7258 13886 7249 13886 7346 13887 7249 13887 7344 13887 7347 13888 7339 13888 7340 13888 7281 13889 7280 13889 7273 13889 7348 13890 7343 13890 7243 13890 7281 13891 7277 13891 7338 13891 7347 13892 7340 13892 7349 13892 7281 13893 7273 13893 7275 13893 7281 13894 7275 13894 7277 13894 7350 13895 7258 13895 7346 13895 7239 13896 7345 13896 7237 13896 7239 13897 7351 13897 7345 13897 7352 13898 7348 13898 7243 13898 7353 13899 7258 13899 7350 13899 7354 13900 7347 13900 7349 13900 7355 13901 7352 13901 7243 13901 7354 13902 7349 13902 7356 13902 7355 13903 7243 13903 7245 13903 7241 13904 7351 13904 7239 13904 7357 13905 7355 13905 7245 13905 7309 13906 7342 13906 7307 13906 7255 13907 7258 13907 7353 13907 7317 13908 7358 13908 7359 13908 7317 13909 7351 13909 7241 13909 7317 13910 7359 13910 7351 13910 7360 13911 7357 13911 7245 13911 7361 13912 7360 13912 7245 13912 7361 13913 7245 13913 7247 13913 7362 13914 7354 13914 7356 13914 7363 13915 7361 13915 7247 13915 7363 13916 7247 13916 7231 13916 7316 13917 7362 13917 7356 13917 7316 13918 7364 13918 7365 13918 7316 13919 7356 13919 7364 13919 7311 13920 7366 13920 7342 13920 7367 13921 7363 13921 7231 13921 7303 13922 7362 13922 7316 13922 7368 13923 7362 13923 7303 13923 7311 13924 7342 13924 7309 13924 7283 13925 7281 13925 7338 13925 7234 13926 7367 13926 7231 13926 7283 13927 7338 13927 7369 13927 7319 13928 7358 13928 7317 13928 7340 13929 7255 13929 7353 13929 7319 13930 7333 13930 7358 13930 7340 13931 7267 13931 7255 13931 7327 13932 7316 13932 7365 13932 7313 13933 7370 13933 7371 13933 7313 13934 7366 13934 7311 13934 7313 13935 7371 13935 7366 13935 7327 13936 7365 13936 7330 13936 7321 13937 7333 13937 7319 13937 7289 13938 7370 13938 7313 13938 7289 13939 7372 13939 7370 13939 7336 13940 7368 13940 7303 13940 7288 13941 7283 13941 7369 13941 7288 13942 7373 13942 7329 13942 7288 13943 7369 13943 7373 13943 7291 13944 7372 13944 7289 13944 7291 13945 7334 13945 7372 13945 7235 13946 7367 13946 7234 13946 7235 13947 7341 13947 7367 13947 7285 13948 7374 13948 7332 13948 7285 13949 7329 13949 7374 13949 7325 13950 7327 13950 7330 13950 7375 13951 7376 13951 7358 13951 7375 13952 7358 13952 7333 13952 7377 13953 7333 13953 7331 13953 7377 13954 7375 13954 7333 13954 7330 13955 7377 13955 7331 13955 7378 13956 7377 13956 7330 13956 7379 13957 7330 13957 7365 13957 7379 13958 7378 13958 7330 13958 7364 13959 7379 13959 7365 13959 7380 13960 7379 13960 7364 13960 7381 13961 7364 13961 7356 13961 7381 13962 7380 13962 7364 13962 7358 13963 7376 13963 7382 13963 7358 13964 7382 13964 7359 13964 7383 13965 7384 13965 7361 13965 7383 13966 7361 13966 7363 13966 7385 13967 7363 13967 7367 13967 7385 13968 7383 13968 7363 13968 7386 13969 7367 13969 7341 13969 7386 13970 7385 13970 7367 13970 7387 13971 7341 13971 7345 13971 7387 13972 7386 13972 7341 13972 7388 13973 7345 13973 7351 13973 7388 13974 7387 13974 7345 13974 7382 13975 7351 13975 7359 13975 7382 13976 7388 13976 7351 13976 7357 13977 7389 13977 7355 13977 7390 13978 7389 13978 7357 13978 7391 13979 7357 13979 7360 13979 7391 13980 7390 13980 7357 13980 7361 13981 7391 13981 7360 13981 7384 13982 7391 13982 7361 13982 7389 13983 7392 13983 7352 13983 7389 13984 7352 13984 7355 13984 7393 13985 7394 13985 7353 13985 7393 13986 7353 13986 7350 13986 7395 13987 7350 13987 7346 13987 7395 13988 7393 13988 7350 13988 7396 13989 7346 13989 7344 13989 7396 13990 7395 13990 7346 13990 7397 13991 7344 13991 7343 13991 7397 13992 7396 13992 7344 13992 7398 13993 7343 13993 7348 13993 7398 13994 7397 13994 7343 13994 7392 13995 7348 13995 7352 13995 7392 13996 7398 13996 7348 13996 7399 13997 7340 13997 7353 13997 7399 13998 7353 13998 7394 13998 7399 13999 7400 13999 7349 13999 7399 14000 7349 14000 7340 14000 7400 14001 7381 14001 7356 14001 7400 14002 7356 14002 7349 14002 7401 14003 7402 14003 7370 14003 7401 14004 7370 14004 7372 14004 7334 14005 7401 14005 7372 14005 7403 14006 7401 14006 7334 14006 7404 14007 7334 14007 7335 14007 7404 14008 7403 14008 7334 14008 7405 14009 7335 14009 7332 14009 7405 14010 7404 14010 7335 14010 7406 14011 7332 14011 7374 14011 7406 14012 7405 14012 7332 14012 7407 14013 7374 14013 7329 14013 7407 14014 7406 14014 7374 14014 7373 14015 7407 14015 7329 14015 7408 14016 7407 14016 7373 14016 7409 14017 7373 14017 7369 14017 7409 14018 7408 14018 7373 14018 7370 14019 7402 14019 7410 14019 7370 14020 7410 14020 7371 14020 7411 14021 7412 14021 7362 14021 7411 14022 7362 14022 7368 14022 7413 14023 7368 14023 7336 14023 7413 14024 7411 14024 7368 14024 7414 14025 7336 14025 7337 14025 7414 14026 7413 14026 7336 14026 7342 14027 7414 14027 7337 14027 7415 14028 7414 14028 7342 14028 7366 14029 7415 14029 7342 14029 7416 14030 7415 14030 7366 14030 7410 14031 7366 14031 7371 14031 7410 14032 7416 14032 7366 14032 7417 14033 7418 14033 7347 14033 7417 14034 7347 14034 7354 14034 7362 14035 7417 14035 7354 14035 7412 14036 7417 14036 7362 14036 7418 14037 7419 14037 7339 14037 7418 14038 7339 14038 7347 14038 7420 14039 7338 14039 7339 14039 7420 14040 7339 14040 7419 14040 7420 14041 7409 14041 7369 14041 7420 14042 7369 14042 7338 14042 7395 14043 7396 14043 7397 14043 7393 14044 7397 14044 7398 14044 7393 14045 7395 14045 7397 14045 7392 14046 7393 14046 7398 14046 7394 14047 7393 14047 7392 14047 7389 14048 7394 14048 7392 14048 7400 14049 7399 14049 7394 14049 7400 14050 7389 14050 7390 14050 7400 14051 7394 14051 7389 14051 7387 14052 7385 14052 7386 14052 7388 14053 7383 14053 7385 14053 7388 14054 7385 14054 7387 14054 7382 14055 7383 14055 7388 14055 7381 14056 7390 14056 7391 14056 7381 14057 7391 14057 7384 14057 7381 14058 7400 14058 7390 14058 7380 14059 7384 14059 7383 14059 7380 14060 7381 14060 7384 14060 7379 14061 7382 14061 7376 14061 7379 14062 7383 14062 7382 14062 7379 14063 7380 14063 7383 14063 7378 14064 7376 14064 7375 14064 7378 14065 7375 14065 7377 14065 7378 14066 7379 14066 7376 14066 7420 14067 7419 14067 7418 14067 7415 14068 7413 14068 7414 14068 7416 14069 7411 14069 7413 14069 7416 14070 7413 14070 7415 14070 7409 14071 7418 14071 7417 14071 7409 14072 7420 14072 7418 14072 7410 14073 7412 14073 7411 14073 7410 14074 7411 14074 7416 14074 7408 14075 7410 14075 7402 14075 7408 14076 7417 14076 7412 14076 7408 14077 7409 14077 7417 14077 7408 14078 7412 14078 7410 14078 7407 14079 7402 14079 7401 14079 7407 14080 7408 14080 7402 14080 7406 14081 7407 14081 7401 14081 7403 14082 7406 14082 7401 14082 7405 14083 7406 14083 7403 14083 7404 14084 7405 14084 7403 14084 7421 14085 7422 14085 7423 14085 7424 14086 7421 14086 7423 14086 7425 14087 7424 14087 7426 14087 7424 14088 7423 14088 7426 14088 7427 14089 7425 14089 7428 14089 7425 14090 7426 14090 7428 14090 7429 14091 7427 14091 7430 14091 7427 14092 7428 14092 7430 14092 7431 14093 7429 14093 7432 14093 7429 14094 7430 14094 7432 14094 7433 14095 7431 14095 7434 14095 7431 14096 7432 14096 7434 14096 7435 14097 7433 14097 7436 14097 7433 14098 7434 14098 7436 14098 7437 14099 7438 14099 7439 14099 7439 14100 7438 14100 7440 14100 7439 14101 7440 14101 7441 14101 7441 14102 7440 14102 7442 14102 7441 14103 7442 14103 7443 14103 7443 14104 7442 14104 7444 14104 7443 14105 7444 14105 7445 14105 7445 14106 7444 14106 7446 14106 7447 14107 7445 14107 7448 14107 7445 14108 7446 14108 7448 14108 7449 14109 7447 14109 7450 14109 7447 14110 7448 14110 7450 14110 7421 14111 7449 14111 7422 14111 7449 14112 7450 14112 7422 14112 7451 14113 7452 14113 7453 14113 7454 14114 7451 14114 7453 14114 7455 14115 7454 14115 7456 14115 7454 14116 7453 14116 7456 14116 7457 14117 7455 14117 7458 14117 7455 14118 7456 14118 7458 14118 7459 14119 7457 14119 7460 14119 7457 14120 7458 14120 7460 14120 7461 14121 7459 14121 7462 14121 7459 14122 7460 14122 7462 14122 7461 14123 7462 14123 7463 14123 7463 14124 7462 14124 7464 14124 7463 14125 7464 14125 7437 14125 7437 14126 7464 14126 7438 14126 7465 14127 7466 14127 7467 14127 7468 14128 7465 14128 7467 14128 7469 14129 7468 14129 7470 14129 7468 14130 7467 14130 7470 14130 7469 14131 7470 14131 7471 14131 7471 14132 7470 14132 7472 14132 7471 14133 7472 14133 7473 14133 7473 14134 7472 14134 7474 14134 7475 14135 7473 14135 7476 14135 7473 14136 7474 14136 7476 14136 7475 14137 7476 14137 7477 14137 7477 14138 7476 14138 7478 14138 7479 14139 7477 14139 7480 14139 7477 14140 7478 14140 7480 14140 7451 14141 7479 14141 7452 14141 7479 14142 7480 14142 7452 14142 7436 14143 7466 14143 7465 14143 7435 14144 7436 14144 7465 14144 7429 14145 7481 14145 7427 14145 7429 14146 7482 14146 7481 14146 7455 14147 7457 14147 7483 14147 7455 14148 7483 14148 7484 14148 7431 14149 7482 14149 7429 14149 7431 14150 7485 14150 7482 14150 7486 14151 7443 14151 7445 14151 7431 14152 7487 14152 7485 14152 7486 14153 7488 14153 7443 14153 7489 14154 7441 14154 7443 14154 7489 14155 7443 14155 7488 14155 7490 14156 7445 14156 7447 14156 7490 14157 7486 14157 7445 14157 7491 14158 7447 14158 7449 14158 7454 14159 7455 14159 7484 14159 7454 14160 7484 14160 7492 14160 7491 14161 7490 14161 7447 14161 7493 14162 7439 14162 7441 14162 7493 14163 7441 14163 7489 14163 7433 14164 7494 14164 7487 14164 7433 14165 7487 14165 7431 14165 7495 14166 7449 14166 7421 14166 7495 14167 7491 14167 7449 14167 7496 14168 7495 14168 7421 14168 7497 14169 7463 14169 7437 14169 7497 14170 7437 14170 7439 14170 7497 14171 7439 14171 7493 14171 7451 14172 7492 14172 7498 14172 7451 14173 7454 14173 7492 14173 7499 14174 7461 14174 7463 14174 7499 14175 7463 14175 7497 14175 7500 14176 7421 14176 7424 14176 7435 14177 7494 14177 7433 14177 7435 14178 7501 14178 7494 14178 7500 14179 7496 14179 7421 14179 7465 14180 7501 14180 7435 14180 7465 14181 7502 14181 7501 14181 7503 14182 7461 14182 7499 14182 7479 14183 7451 14183 7498 14183 7504 14184 7424 14184 7425 14184 7504 14185 7500 14185 7424 14185 7479 14186 7498 14186 7505 14186 7459 14187 7461 14187 7503 14187 7468 14188 7502 14188 7465 14188 7506 14189 7504 14189 7425 14189 7477 14190 7505 14190 7507 14190 7477 14191 7479 14191 7505 14191 7475 14192 7477 14192 7507 14192 7475 14193 7507 14193 7508 14193 7509 14194 7459 14194 7503 14194 7469 14195 7510 14195 7502 14195 7427 14196 7506 14196 7425 14196 7469 14197 7502 14197 7468 14197 7473 14198 7508 14198 7511 14198 7481 14199 7506 14199 7427 14199 7473 14200 7475 14200 7508 14200 7471 14201 7511 14201 7510 14201 7471 14202 7473 14202 7511 14202 7471 14203 7510 14203 7469 14203 7457 14204 7459 14204 7509 14204 7483 14205 7457 14205 7509 14205 7512 14206 7513 14206 7501 14206 7512 14207 7501 14207 7502 14207 7514 14208 7502 14208 7510 14208 7514 14209 7512 14209 7502 14209 7515 14210 7510 14210 7511 14210 7515 14211 7514 14211 7510 14211 7516 14212 7511 14212 7508 14212 7516 14213 7515 14213 7511 14213 7517 14214 7508 14214 7507 14214 7517 14215 7516 14215 7508 14215 7518 14216 7507 14216 7505 14216 7518 14217 7517 14217 7507 14217 7498 14218 7518 14218 7505 14218 7519 14219 7518 14219 7498 14219 7501 14220 7513 14220 7520 14220 7501 14221 7520 14221 7494 14221 7521 14222 7522 14222 7496 14222 7521 14223 7496 14223 7500 14223 7523 14224 7500 14224 7504 14224 7523 14225 7521 14225 7500 14225 7524 14226 7504 14226 7506 14226 7524 14227 7523 14227 7504 14227 7525 14228 7506 14228 7481 14228 7525 14229 7524 14229 7506 14229 7526 14230 7481 14230 7482 14230 7526 14231 7525 14231 7481 14231 7485 14232 7526 14232 7482 14232 7527 14233 7526 14233 7485 14233 7528 14234 7485 14234 7487 14234 7528 14235 7527 14235 7485 14235 7494 14236 7528 14236 7487 14236 7520 14237 7528 14237 7494 14237 7529 14238 7530 14238 7497 14238 7529 14239 7497 14239 7493 14239 7531 14240 7493 14240 7489 14240 7531 14241 7529 14241 7493 14241 7532 14242 7489 14242 7488 14242 7532 14243 7531 14243 7489 14243 7486 14244 7532 14244 7488 14244 7533 14245 7532 14245 7486 14245 7534 14246 7486 14246 7490 14246 7534 14247 7533 14247 7486 14247 7535 14248 7490 14248 7491 14248 7535 14249 7534 14249 7490 14249 7536 14250 7491 14250 7495 14250 7536 14251 7535 14251 7491 14251 7522 14252 7495 14252 7496 14252 7522 14253 7536 14253 7495 14253 7537 14254 7519 14254 7498 14254 7537 14255 7498 14255 7492 14255 7484 14256 7537 14256 7492 14256 7538 14257 7537 14257 7484 14257 7483 14258 7538 14258 7484 14258 7539 14259 7538 14259 7483 14259 7509 14260 7539 14260 7483 14260 7540 14261 7539 14261 7509 14261 7541 14262 7509 14262 7503 14262 7541 14263 7540 14263 7509 14263 7542 14264 7503 14264 7499 14264 7542 14265 7541 14265 7503 14265 7530 14266 7499 14266 7497 14266 7530 14267 7542 14267 7499 14267 7535 14268 7532 14268 7533 14268 7535 14269 7533 14269 7534 14269 7536 14270 7531 14270 7532 14270 7536 14271 7532 14271 7535 14271 7524 14272 7521 14272 7523 14272 7525 14273 7521 14273 7524 14273 7526 14274 7522 14274 7521 14274 7526 14275 7521 14275 7525 14275 7527 14276 7529 14276 7531 14276 7527 14277 7536 14277 7522 14277 7527 14278 7531 14278 7536 14278 7527 14279 7522 14279 7526 14279 7537 14280 7538 14280 7539 14280 7537 14281 7539 14281 7540 14281 7537 14282 7540 14282 7541 14282 7528 14283 7530 14283 7529 14283 7528 14284 7529 14284 7527 14284 7520 14285 7530 14285 7528 14285 7513 14286 7542 14286 7530 14286 7513 14287 7530 14287 7520 14287 7519 14288 7537 14288 7541 14288 7512 14289 7541 14289 7542 14289 7512 14290 7542 14290 7513 14290 7514 14291 7519 14291 7541 14291 7514 14292 7541 14292 7512 14292 7516 14293 7517 14293 7518 14293 7515 14294 7518 14294 7519 14294 7515 14295 7519 14295 7514 14295 7515 14296 7516 14296 7518 14296 7543 14297 7544 14297 7545 14297 7546 14298 7543 14298 7545 14298 7547 14299 7546 14299 7548 14299 7546 14300 7545 14300 7548 14300 7547 14301 7548 14301 7549 14301 7549 14302 7548 14302 7550 14302 7551 14303 7549 14303 7552 14303 7549 14304 7550 14304 7552 14304 7553 14305 7544 14305 7543 14305 7554 14306 7553 14306 7543 14306 7553 14307 7554 14307 7555 14307 7554 14308 7556 14308 7555 14308 7555 14309 7556 14309 7557 14309 7556 14310 7558 14310 7557 14310 7559 14311 7557 14311 7558 14311 7560 14312 7559 14312 7558 14312 7561 14313 7559 14313 7560 14313 7562 14314 7561 14314 7560 14314 7563 14315 7564 14315 7565 14315 7566 14316 7563 14316 7565 14316 7567 14317 7566 14317 7568 14317 7566 14318 7565 14318 7568 14318 7567 14319 7568 14319 7569 14319 7569 14320 7568 14320 7570 14320 7562 14321 7569 14321 7561 14321 7569 14322 7570 14322 7561 14322 7571 14323 7564 14323 7563 14323 7572 14324 7571 14324 7563 14324 7573 14325 7571 14325 7572 14325 7574 14326 7573 14326 7572 14326 7575 14327 7576 14327 7577 14327 7578 14328 7575 14328 7577 14328 7579 14329 7578 14329 7580 14329 7578 14330 7577 14330 7580 14330 7581 14331 7579 14331 7582 14331 7579 14332 7580 14332 7582 14332 7583 14333 7581 14333 7584 14333 7581 14334 7582 14334 7584 14334 7585 14335 7583 14335 7586 14335 7583 14336 7584 14336 7586 14336 7587 14337 7585 14337 7588 14337 7585 14338 7586 14338 7588 14338 7589 14339 7587 14339 7590 14339 7587 14340 7588 14340 7590 14340 7589 14341 7590 14341 7574 14341 7574 14342 7590 14342 7573 14342 7591 14343 7576 14343 7575 14343 7592 14344 7591 14344 7575 14344 7593 14345 7591 14345 7592 14345 7594 14346 7593 14346 7592 14346 7593 14347 7594 14347 7595 14347 7594 14348 7596 14348 7595 14348 7597 14349 7598 14349 7599 14349 7600 14350 7597 14350 7599 14350 7600 14351 7599 14351 7601 14351 7601 14352 7599 14352 7602 14352 7603 14353 7601 14353 7604 14353 7601 14354 7602 14354 7604 14354 7603 14355 7604 14355 7605 14355 7605 14356 7604 14356 7606 14356 7596 14357 7605 14357 7595 14357 7605 14358 7606 14358 7595 14358 7598 14359 7597 14359 7607 14359 7597 14360 7608 14360 7607 14360 7552 14361 7607 14361 7608 14361 7551 14362 7552 14362 7608 14362 7592 14363 7575 14363 7578 14363 7592 14364 7578 14364 7579 14364 7592 14365 7579 14365 7581 14365 7592 14366 7581 14366 7583 14366 7592 14367 7583 14367 7585 14367 7592 14368 7585 14368 7594 14368 7605 14369 7594 14369 7603 14369 7594 14370 7605 14370 7596 14370 7585 14371 7587 14371 7601 14371 7594 14372 7585 14372 7601 14372 7603 14373 7594 14373 7601 14373 7587 14374 7589 14374 7600 14374 7601 14375 7587 14375 7600 14375 7562 14376 7560 14376 7569 14376 7589 14377 7574 14377 7597 14377 7600 14378 7589 14378 7597 14378 7563 14379 7566 14379 7558 14379 7566 14380 7567 14380 7558 14380 7567 14381 7569 14381 7558 14381 7569 14382 7560 14382 7558 14382 7597 14383 7574 14383 7572 14383 7563 14384 7558 14384 7572 14384 7597 14385 7572 14385 7608 14385 7572 14386 7558 14386 7608 14386 7543 14387 7546 14387 7554 14387 7546 14388 7547 14388 7556 14388 7547 14389 7549 14389 7556 14389 7549 14390 7551 14390 7556 14390 7551 14391 7608 14391 7556 14391 7608 14392 7558 14392 7556 14392 7554 14393 7546 14393 7556 14393 7609 14394 7610 14394 7611 14394 7612 14395 7609 14395 7611 14395 7613 14396 7612 14396 7614 14396 7612 14397 7611 14397 7614 14397 7613 14398 7614 14398 7615 14398 7615 14399 7614 14399 7616 14399 7617 14400 7615 14400 7618 14400 7615 14401 7616 14401 7618 14401 7619 14402 7610 14402 7609 14402 7620 14403 7619 14403 7609 14403 7621 14404 7619 14404 7620 14404 7622 14405 7621 14405 7620 14405 7621 14406 7622 14406 7623 14406 7622 14407 7624 14407 7623 14407 7625 14408 7626 14408 7627 14408 7628 14409 7625 14409 7627 14409 7628 14410 7627 14410 7629 14410 7629 14411 7627 14411 7630 14411 7629 14412 7630 14412 7631 14412 7631 14413 7630 14413 7632 14413 7624 14414 7631 14414 7623 14414 7631 14415 7632 14415 7623 14415 7626 14416 7625 14416 7633 14416 7625 14417 7634 14417 7633 14417 7635 14418 7636 14418 7637 14418 7638 14419 7635 14419 7637 14419 7639 14420 7638 14420 7640 14420 7638 14421 7637 14421 7640 14421 7641 14422 7639 14422 7642 14422 7639 14423 7640 14423 7642 14423 7634 14424 7641 14424 7633 14424 7641 14425 7642 14425 7633 14425 7636 14426 7635 14426 7643 14426 7635 14427 7644 14427 7643 14427 7643 14428 7644 14428 7645 14428 7644 14429 7646 14429 7645 14429 7647 14430 7645 14430 7646 14430 7648 14431 7647 14431 7646 14431 7649 14432 7650 14432 7651 14432 7652 14433 7649 14433 7651 14433 7653 14434 7652 14434 7654 14434 7652 14435 7651 14435 7654 14435 7655 14436 7653 14436 7656 14436 7653 14437 7654 14437 7656 14437 7648 14438 7655 14438 7647 14438 7655 14439 7656 14439 7647 14439 7617 14440 7618 14440 7650 14440 7617 14441 7650 14441 7649 14441 7620 14442 7609 14442 7612 14442 7620 14443 7612 14443 7613 14443 7620 14444 7613 14444 7622 14444 7622 14445 7631 14445 7624 14445 7622 14446 7613 14446 7629 14446 7631 14447 7622 14447 7629 14447 7613 14448 7615 14448 7628 14448 7629 14449 7613 14449 7628 14449 7615 14450 7617 14450 7625 14450 7628 14451 7615 14451 7625 14451 7617 14452 7649 14452 7634 14452 7625 14453 7617 14453 7634 14453 7653 14454 7655 14454 7646 14454 7655 14455 7648 14455 7646 14455 7649 14456 7652 14456 7641 14456 7634 14457 7649 14457 7641 14457 7652 14458 7653 14458 7639 14458 7641 14459 7652 14459 7639 14459 7653 14460 7646 14460 7639 14460 7635 14461 7638 14461 7644 14461 7638 14462 7639 14462 7644 14462 7639 14463 7646 14463 7644 14463 7657 14464 7658 14464 7659 14464 7659 14465 7658 14465 7660 14465 7659 14466 7660 14466 7661 14466 7661 14467 7660 14467 7662 14467 7661 14468 7662 14468 7663 14468 7663 14469 7662 14469 7664 14469 7665 14470 7666 14470 7667 14470 7667 14471 7666 14471 7668 14471 7667 14472 7668 14472 7669 14472 7669 14473 7668 14473 7670 14473 7657 14474 7669 14474 7658 14474 7669 14475 7670 14475 7658 14475 7671 14476 7666 14476 7665 14476 7672 14477 7671 14477 7665 14477 7673 14478 7674 14478 7671 14478 7672 14479 7673 14479 7671 14479 7675 14480 7676 14480 7673 14480 7673 14481 7676 14481 7674 14481 7677 14482 7678 14482 7676 14482 7675 14483 7677 14483 7676 14483 7677 14484 7679 14484 7678 14484 7679 14485 7680 14485 7678 14485 7681 14486 7682 14486 7680 14486 7679 14487 7681 14487 7680 14487 7683 14488 7684 14488 7685 14488 7686 14489 7683 14489 7685 14489 7687 14490 7686 14490 7688 14490 7686 14491 7685 14491 7688 14491 7689 14492 7687 14492 7690 14492 7687 14493 7688 14493 7690 14493 7691 14494 7689 14494 7692 14494 7689 14495 7690 14495 7692 14495 7681 14496 7691 14496 7682 14496 7691 14497 7692 14497 7682 14497 7693 14498 7694 14498 7683 14498 7683 14499 7694 14499 7684 14499 7695 14500 7696 14500 7694 14500 7693 14501 7695 14501 7694 14501 7697 14502 7698 14502 7696 14502 7695 14503 7697 14503 7696 14503 7699 14504 7700 14504 7697 14504 7697 14505 7700 14505 7698 14505 7701 14506 7702 14506 7703 14506 7704 14507 7701 14507 7703 14507 7705 14508 7704 14508 7706 14508 7704 14509 7703 14509 7706 14509 7705 14510 7706 14510 7707 14510 7707 14511 7706 14511 7708 14511 7709 14512 7707 14512 7710 14512 7707 14513 7708 14513 7710 14513 7711 14514 7709 14514 7712 14514 7709 14515 7710 14515 7712 14515 7713 14516 7711 14516 7714 14516 7711 14517 7712 14517 7714 14517 7715 14518 7713 14518 7716 14518 7713 14519 7714 14519 7716 14519 7715 14520 7716 14520 7699 14520 7699 14521 7716 14521 7700 14521 7717 14522 7718 14522 7719 14522 7720 14523 7717 14523 7719 14523 7720 14524 7719 14524 7721 14524 7721 14525 7719 14525 7722 14525 7723 14526 7721 14526 7724 14526 7721 14527 7722 14527 7724 14527 7725 14528 7723 14528 7726 14528 7723 14529 7724 14529 7726 14529 7727 14530 7725 14530 7728 14530 7725 14531 7726 14531 7728 14531 7727 14532 7728 14532 7729 14532 7729 14533 7728 14533 7730 14533 7731 14534 7729 14534 7732 14534 7729 14535 7730 14535 7732 14535 7701 14536 7731 14536 7702 14536 7731 14537 7732 14537 7702 14537 7733 14538 7734 14538 7735 14538 7736 14539 7733 14539 7735 14539 7737 14540 7736 14540 7738 14540 7736 14541 7735 14541 7738 14541 7739 14542 7737 14542 7740 14542 7737 14543 7738 14543 7740 14543 7739 14544 7740 14544 7741 14544 7741 14545 7740 14545 7742 14545 7743 14546 7741 14546 7744 14546 7741 14547 7742 14547 7744 14547 7745 14548 7743 14548 7746 14548 7743 14549 7744 14549 7746 14549 7747 14550 7745 14550 7748 14550 7745 14551 7746 14551 7748 14551 7747 14552 7748 14552 7717 14552 7717 14553 7748 14553 7718 14553 7664 14554 7734 14554 7733 14554 7663 14555 7664 14555 7733 14555 7749 14556 7750 14556 7695 14556 7672 14557 7695 14557 7693 14557 7665 14558 7749 14558 7695 14558 7665 14559 7695 14559 7672 14559 7725 14560 7727 14560 7751 14560 7673 14561 7693 14561 7683 14561 7717 14562 7752 14562 7753 14562 7717 14563 7720 14563 7752 14563 7673 14564 7672 14564 7693 14564 7663 14565 7754 14565 7755 14565 7663 14566 7755 14566 7756 14566 7757 14567 7749 14567 7665 14567 7663 14568 7756 14568 7661 14568 7733 14569 7758 14569 7754 14569 7759 14570 7725 14570 7751 14570 7733 14571 7754 14571 7663 14571 7667 14572 7757 14572 7665 14572 7747 14573 7717 14573 7753 14573 7760 14574 7707 14574 7709 14574 7675 14575 7683 14575 7681 14575 7736 14576 7758 14576 7733 14576 7675 14577 7673 14577 7683 14577 7761 14578 7757 14578 7667 14578 7745 14579 7747 14579 7753 14579 7762 14580 7709 14580 7711 14580 7745 14581 7753 14581 7763 14581 7762 14582 7760 14582 7709 14582 7737 14583 7758 14583 7736 14583 7737 14584 7764 14584 7758 14584 7723 14585 7725 14585 7759 14585 7765 14586 7705 14586 7707 14586 7765 14587 7707 14587 7760 14587 7743 14588 7745 14588 7763 14588 7679 14589 7677 14589 7675 14589 7743 14590 7763 14590 7766 14590 7739 14591 7764 14591 7737 14591 7679 14592 7675 14592 7681 14592 7767 14593 7711 14593 7713 14593 7739 14594 7768 14594 7764 14594 7769 14595 7723 14595 7759 14595 7767 14596 7762 14596 7711 14596 7741 14597 7743 14597 7766 14597 7741 14598 7768 14598 7739 14598 7669 14599 7761 14599 7667 14599 7741 14600 7766 14600 7768 14600 7770 14601 7704 14601 7705 14601 7770 14602 7705 14602 7765 14602 7771 14603 7761 14603 7669 14603 7772 14604 7767 14604 7713 14604 7772 14605 7713 14605 7715 14605 7657 14606 7771 14606 7669 14606 7773 14607 7772 14607 7715 14607 7773 14608 7715 14608 7699 14608 7773 14609 7699 14609 7697 14609 7774 14610 7771 14610 7657 14610 7775 14611 7731 14611 7701 14611 7775 14612 7701 14612 7704 14612 7775 14613 7704 14613 7770 14613 7721 14614 7769 14614 7776 14614 7721 14615 7723 14615 7769 14615 7750 14616 7773 14616 7697 14616 7750 14617 7697 14617 7695 14617 7659 14618 7774 14618 7657 14618 7777 14619 7727 14619 7729 14619 7777 14620 7729 14620 7731 14620 7777 14621 7731 14621 7775 14621 7720 14622 7778 14622 7752 14622 7689 14623 7686 14623 7687 14623 7720 14624 7776 14624 7778 14624 7720 14625 7721 14625 7776 14625 7661 14626 7756 14626 7774 14626 7691 14627 7686 14627 7689 14627 7661 14628 7774 14628 7659 14628 7681 14629 7683 14629 7686 14629 7681 14630 7686 14630 7691 14630 7751 14631 7727 14631 7777 14631 7779 14632 7780 14632 7754 14632 7779 14633 7754 14633 7758 14633 7781 14634 7758 14634 7764 14634 7781 14635 7779 14635 7758 14635 7782 14636 7764 14636 7768 14636 7782 14637 7781 14637 7764 14637 7783 14638 7768 14638 7766 14638 7783 14639 7782 14639 7768 14639 7784 14640 7766 14640 7763 14640 7784 14641 7783 14641 7766 14641 7785 14642 7763 14642 7753 14642 7785 14643 7784 14643 7763 14643 7786 14644 7753 14644 7752 14644 7786 14645 7785 14645 7753 14645 7754 14646 7780 14646 7787 14646 7754 14647 7787 14647 7755 14647 7750 14648 7788 14648 7773 14648 7789 14649 7788 14649 7750 14649 7749 14650 7789 14650 7750 14650 7790 14651 7789 14651 7749 14651 7757 14652 7790 14652 7749 14652 7791 14653 7790 14653 7757 14653 7761 14654 7791 14654 7757 14654 7792 14655 7791 14655 7761 14655 7793 14656 7761 14656 7771 14656 7793 14657 7792 14657 7761 14657 7774 14658 7793 14658 7771 14658 7794 14659 7793 14659 7774 14659 7795 14660 7774 14660 7756 14660 7795 14661 7794 14661 7774 14661 7755 14662 7795 14662 7756 14662 7787 14663 7795 14663 7755 14663 7796 14664 7797 14664 7775 14664 7796 14665 7775 14665 7770 14665 7765 14666 7796 14666 7770 14666 7798 14667 7796 14667 7765 14667 7799 14668 7765 14668 7760 14668 7799 14669 7798 14669 7765 14669 7800 14670 7760 14670 7762 14670 7800 14671 7799 14671 7760 14671 7801 14672 7762 14672 7767 14672 7801 14673 7800 14673 7762 14673 7802 14674 7767 14674 7772 14674 7802 14675 7801 14675 7767 14675 7773 14676 7802 14676 7772 14676 7788 14677 7802 14677 7773 14677 7803 14678 7786 14678 7752 14678 7803 14679 7752 14679 7778 14679 7804 14680 7778 14680 7776 14680 7804 14681 7803 14681 7778 14681 7769 14682 7804 14682 7776 14682 7805 14683 7804 14683 7769 14683 7806 14684 7769 14684 7759 14684 7806 14685 7805 14685 7769 14685 7751 14686 7806 14686 7759 14686 7807 14687 7806 14687 7751 14687 7777 14688 7807 14688 7751 14688 7808 14689 7807 14689 7777 14689 7775 14690 7808 14690 7777 14690 7797 14691 7808 14691 7775 14691 7802 14692 7799 14692 7800 14692 7802 14693 7800 14693 7801 14693 7788 14694 7799 14694 7802 14694 7791 14695 7789 14695 7790 14695 7792 14696 7789 14696 7791 14696 7793 14697 7788 14697 7789 14697 7793 14698 7789 14698 7792 14698 7794 14699 7796 14699 7798 14699 7794 14700 7798 14700 7799 14700 7794 14701 7799 14701 7788 14701 7794 14702 7788 14702 7793 14702 7803 14703 7804 14703 7805 14703 7803 14704 7805 14704 7806 14704 7795 14705 7797 14705 7796 14705 7795 14706 7796 14706 7794 14706 7787 14707 7797 14707 7795 14707 7780 14708 7808 14708 7797 14708 7780 14709 7797 14709 7787 14709 7786 14710 7803 14710 7806 14710 7779 14711 7807 14711 7808 14711 7779 14712 7808 14712 7780 14712 7781 14713 7806 14713 7807 14713 7781 14714 7786 14714 7806 14714 7781 14715 7807 14715 7779 14715 7783 14716 7784 14716 7785 14716 7782 14717 7785 14717 7786 14717 7782 14718 7786 14718 7781 14718 7782 14719 7783 14719 7785 14719 7809 14720 7810 14720 7811 14720 7812 14721 7809 14721 7811 14721 7813 14722 7812 14722 7814 14722 7812 14723 7811 14723 7814 14723 7815 14724 7813 14724 7816 14724 7813 14725 7814 14725 7816 14725 7817 14726 7815 14726 7818 14726 7815 14727 7816 14727 7818 14727 7819 14728 7817 14728 7820 14728 7817 14729 7818 14729 7820 14729 7821 14730 7819 14730 7822 14730 7819 14731 7820 14731 7822 14731 7823 14732 7821 14732 7824 14732 7821 14733 7822 14733 7824 14733 7823 14734 7824 14734 7825 14734 7825 14735 7824 14735 7826 14735 7827 14736 7828 14736 7810 14736 7809 14737 7827 14737 7810 14737 7829 14738 7830 14738 7831 14738 7832 14739 7829 14739 7831 14739 7832 14740 7831 14740 7833 14740 7833 14741 7831 14741 7834 14741 7835 14742 7833 14742 7836 14742 7833 14743 7834 14743 7836 14743 7837 14744 7835 14744 7838 14744 7835 14745 7836 14745 7838 14745 7839 14746 7837 14746 7840 14746 7837 14747 7838 14747 7840 14747 7827 14748 7839 14748 7828 14748 7839 14749 7840 14749 7828 14749 7841 14750 7842 14750 7830 14750 7829 14751 7841 14751 7830 14751 7843 14752 7844 14752 7845 14752 7846 14753 7843 14753 7845 14753 7847 14754 7846 14754 7848 14754 7846 14755 7845 14755 7848 14755 7849 14756 7847 14756 7850 14756 7847 14757 7848 14757 7850 14757 7851 14758 7849 14758 7852 14758 7849 14759 7850 14759 7852 14759 7851 14760 7852 14760 7853 14760 7853 14761 7852 14761 7854 14761 7855 14762 7853 14762 7856 14762 7853 14763 7854 14763 7856 14763 7855 14764 7856 14764 7857 14764 7857 14765 7856 14765 7858 14765 7857 14766 7858 14766 7859 14766 7859 14767 7858 14767 7860 14767 7841 14768 7859 14768 7842 14768 7859 14769 7860 14769 7842 14769 7861 14770 7862 14770 7844 14770 7843 14771 7861 14771 7844 14771 7863 14772 7864 14772 7865 14772 7866 14773 7863 14773 7865 14773 7867 14774 7866 14774 7868 14774 7866 14775 7865 14775 7868 14775 7869 14776 7867 14776 7870 14776 7867 14777 7868 14777 7870 14777 7869 14778 7870 14778 7871 14778 7871 14779 7870 14779 7872 14779 7873 14780 7871 14780 7874 14780 7871 14781 7872 14781 7874 14781 7875 14782 7873 14782 7876 14782 7873 14783 7874 14783 7876 14783 7877 14784 7875 14784 7878 14784 7875 14785 7876 14785 7878 14785 7879 14786 7877 14786 7880 14786 7877 14787 7878 14787 7880 14787 7879 14788 7880 14788 7861 14788 7861 14789 7880 14789 7862 14789 7825 14790 7826 14790 7864 14790 7863 14791 7825 14791 7864 14791 7867 14792 7869 14792 7871 14792 7867 14793 7871 14793 7873 14793 7867 14794 7873 14794 7875 14794 7866 14795 7875 14795 7877 14795 7866 14796 7867 14796 7875 14796 7863 14797 7877 14797 7879 14797 7863 14798 7866 14798 7877 14798 7861 14799 7863 14799 7879 14799 7825 14800 7863 14800 7861 14800 7813 14801 7815 14801 7817 14801 7813 14802 7817 14802 7819 14802 7812 14803 7819 14803 7821 14803 7812 14804 7821 14804 7823 14804 7812 14805 7813 14805 7819 14805 7809 14806 7823 14806 7825 14806 7809 14807 7825 14807 7861 14807 7809 14808 7812 14808 7823 14808 7851 14809 7847 14809 7849 14809 7853 14810 7847 14810 7851 14810 7855 14811 7846 14811 7847 14811 7855 14812 7847 14812 7853 14812 7857 14813 7843 14813 7846 14813 7857 14814 7846 14814 7855 14814 7859 14815 7843 14815 7857 14815 7841 14816 7843 14816 7859 14816 7827 14817 7861 14817 7843 14817 7827 14818 7809 14818 7861 14818 7829 14819 7839 14819 7827 14819 7829 14820 7827 14820 7843 14820 7829 14821 7843 14821 7841 14821 7837 14822 7839 14822 7829 14822 7835 14823 7837 14823 7829 14823 7833 14824 7835 14824 7829 14824 7833 14825 7829 14825 7832 14825 7881 14826 7882 14826 7883 14826 7883 14827 7882 14827 7884 14827 7885 14828 7883 14828 7886 14828 7883 14829 7884 14829 7886 14829 7885 14830 7886 14830 7887 14830 7887 14831 7886 14831 7888 14831 7889 14832 7887 14832 7890 14832 7887 14833 7888 14833 7890 14833 7891 14834 7889 14834 7892 14834 7889 14835 7890 14835 7892 14835 7891 14836 7892 14836 7893 14836 7893 14837 7892 14837 7894 14837 7895 14838 7893 14838 7896 14838 7893 14839 7894 14839 7896 14839 7897 14840 7895 14840 7898 14840 7895 14841 7896 14841 7898 14841 7899 14842 7900 14842 7881 14842 7881 14843 7900 14843 7882 14843 7901 14844 7902 14844 7903 14844 7904 14845 7901 14845 7903 14845 7904 14846 7903 14846 7905 14846 7905 14847 7903 14847 7906 14847 7907 14848 7905 14848 7908 14848 7905 14849 7906 14849 7908 14849 7907 14850 7908 14850 7909 14850 7909 14851 7908 14851 7910 14851 7911 14852 7909 14852 7912 14852 7909 14853 7910 14853 7912 14853 7913 14854 7911 14854 7914 14854 7911 14855 7912 14855 7914 14855 7915 14856 7913 14856 7916 14856 7913 14857 7914 14857 7916 14857 7917 14858 7915 14858 7918 14858 7915 14859 7916 14859 7918 14859 7899 14860 7917 14860 7900 14860 7917 14861 7918 14861 7900 14861 7919 14862 7920 14862 7902 14862 7901 14863 7919 14863 7902 14863 7921 14864 7922 14864 7923 14864 7924 14865 7921 14865 7923 14865 7925 14866 7924 14866 7926 14866 7924 14867 7923 14867 7926 14867 7925 14868 7926 14868 7927 14868 7927 14869 7926 14869 7928 14869 7929 14870 7927 14870 7930 14870 7927 14871 7928 14871 7930 14871 7931 14872 7929 14872 7932 14872 7929 14873 7930 14873 7932 14873 7931 14874 7932 14874 7933 14874 7933 14875 7932 14875 7934 14875 7935 14876 7933 14876 7936 14876 7933 14877 7934 14877 7936 14877 7935 14878 7936 14878 7937 14878 7937 14879 7936 14879 7938 14879 7919 14880 7937 14880 7920 14880 7937 14881 7938 14881 7920 14881 7939 14882 7940 14882 7922 14882 7921 14883 7939 14883 7922 14883 7941 14884 7942 14884 7943 14884 7944 14885 7941 14885 7943 14885 7945 14886 7944 14886 7946 14886 7944 14887 7943 14887 7946 14887 7945 14888 7946 14888 7947 14888 7947 14889 7946 14889 7948 14889 7947 14890 7948 14890 7949 14890 7949 14891 7948 14891 7950 14891 7951 14892 7949 14892 7952 14892 7949 14893 7950 14893 7952 14893 7951 14894 7952 14894 7939 14894 7939 14895 7952 14895 7940 14895 7897 14896 7898 14896 7942 14896 7941 14897 7897 14897 7942 14897 7907 14898 7909 14898 7913 14898 7909 14899 7911 14899 7913 14899 7907 14900 7913 14900 7915 14900 7905 14901 7907 14901 7917 14901 7907 14902 7915 14902 7917 14902 7901 14903 7904 14903 7899 14903 7904 14904 7905 14904 7899 14904 7905 14905 7917 14905 7899 14905 7901 14906 7899 14906 7881 14906 7883 14907 7885 14907 7889 14907 7885 14908 7887 14908 7889 14908 7881 14909 7883 14909 7891 14909 7883 14910 7889 14910 7891 14910 7881 14911 7891 14911 7893 14911 7881 14912 7893 14912 7895 14912 7901 14913 7881 14913 7897 14913 7881 14914 7895 14914 7897 14914 7929 14915 7931 14915 7927 14915 7931 14916 7933 14916 7925 14916 7927 14917 7931 14917 7925 14917 7933 14918 7935 14918 7924 14918 7935 14919 7937 14919 7924 14919 7925 14920 7933 14920 7924 14920 7937 14921 7919 14921 7921 14921 7924 14922 7937 14922 7921 14922 7919 14923 7901 14923 7941 14923 7901 14924 7897 14924 7941 14924 7921 14925 7919 14925 7939 14925 7919 14926 7941 14926 7939 14926 7939 14927 7941 14927 7944 14927 7939 14928 7944 14928 7951 14928 7944 14929 7945 14929 7949 14929 7951 14930 7944 14930 7949 14930 7949 14931 7945 14931 7947 14931 7953 14932 7954 14932 7955 14932 7956 14933 7953 14933 7955 14933 7957 14934 7956 14934 7958 14934 7956 14935 7955 14935 7958 14935 7959 14936 7957 14936 7960 14936 7957 14937 7958 14937 7960 14937 7961 14938 7959 14938 7962 14938 7959 14939 7960 14939 7962 14939 7963 14940 7961 14940 7964 14940 7961 14941 7962 14941 7964 14941 7965 14942 7963 14942 7966 14942 7963 14943 7964 14943 7966 14943 7967 14944 7965 14944 7968 14944 7965 14945 7966 14945 7968 14945 7969 14946 7967 14946 7970 14946 7967 14947 7968 14947 7970 14947 7971 14948 7972 14948 7954 14948 7953 14949 7971 14949 7954 14949 7973 14950 7974 14950 7975 14950 7976 14951 7973 14951 7975 14951 7976 14952 7975 14952 7977 14952 7977 14953 7975 14953 7978 14953 7979 14954 7977 14954 7980 14954 7977 14955 7978 14955 7980 14955 7981 14956 7979 14956 7982 14956 7979 14957 7980 14957 7982 14957 7983 14958 7981 14958 7984 14958 7981 14959 7982 14959 7984 14959 7971 14960 7983 14960 7972 14960 7983 14961 7984 14961 7972 14961 7985 14962 7986 14962 7974 14962 7973 14963 7985 14963 7974 14963 7987 14964 7988 14964 7989 14964 7990 14965 7987 14965 7989 14965 7990 14966 7989 14966 7991 14966 7991 14967 7989 14967 7992 14967 7991 14968 7992 14968 7993 14968 7993 14969 7992 14969 7994 14969 7995 14970 7993 14970 7996 14970 7993 14971 7994 14971 7996 14971 7995 14972 7996 14972 7997 14972 7997 14973 7996 14973 7998 14973 7999 14974 7997 14974 8000 14974 7997 14975 7998 14975 8000 14975 8001 14976 7999 14976 8002 14976 7999 14977 8000 14977 8002 14977 8003 14978 8001 14978 8004 14978 8001 14979 8002 14979 8004 14979 8003 14980 8004 14980 7985 14980 7985 14981 8004 14981 7986 14981 8005 14982 8006 14982 7987 14982 7987 14983 8006 14983 7988 14983 8007 14984 8008 14984 8009 14984 8010 14985 8007 14985 8009 14985 8011 14986 8010 14986 8012 14986 8010 14987 8009 14987 8012 14987 8011 14988 8012 14988 8013 14988 8013 14989 8012 14989 8014 14989 8015 14990 8013 14990 8016 14990 8013 14991 8014 14991 8016 14991 8017 14992 8015 14992 8018 14992 8015 14993 8016 14993 8018 14993 8019 14994 8017 14994 8020 14994 8017 14995 8018 14995 8020 14995 8021 14996 8019 14996 8022 14996 8019 14997 8020 14997 8022 14997 8021 14998 8022 14998 8023 14998 8023 14999 8022 14999 8024 14999 8025 15000 8023 15000 8026 15000 8023 15001 8024 15001 8026 15001 8025 15002 8026 15002 8005 15002 8005 15003 8026 15003 8006 15003 7969 15004 7970 15004 8008 15004 8007 15005 7969 15005 8008 15005 7977 15006 7979 15006 7973 15006 7977 15007 7973 15007 7976 15007 8013 15008 8015 15008 8017 15008 8011 15009 8017 15009 8019 15009 8011 15010 8013 15010 8017 15010 8010 15011 8019 15011 8021 15011 8010 15012 8011 15012 8019 15012 8007 15013 8021 15013 8023 15013 8007 15014 8023 15014 8025 15014 8007 15015 8010 15015 8021 15015 8005 15016 8007 15016 8025 15016 7969 15017 8007 15017 8005 15017 7957 15018 7959 15018 7961 15018 7957 15019 7961 15019 7963 15019 7956 15020 7963 15020 7965 15020 7956 15021 7965 15021 7967 15021 7956 15022 7957 15022 7963 15022 7953 15023 7967 15023 7969 15023 7953 15024 7969 15024 8005 15024 7953 15025 7956 15025 7967 15025 7995 15026 7991 15026 7993 15026 7997 15027 7990 15027 7991 15027 7997 15028 7991 15028 7995 15028 7999 15029 7987 15029 7990 15029 7999 15030 7990 15030 7997 15030 8001 15031 7987 15031 7999 15031 8003 15032 7987 15032 8001 15032 7985 15033 7987 15033 8003 15033 7971 15034 8005 15034 7987 15034 7971 15035 7953 15035 8005 15035 7973 15036 7987 15036 7985 15036 7973 15037 7983 15037 7971 15037 7973 15038 7971 15038 7987 15038 7981 15039 7983 15039 7973 15039 7979 15040 7981 15040 7973 15040 774 15041 750 15041 749 15041 774 15042 753 15042 750 15042 774 15043 755 15043 753 15043 774 15044 757 15044 755 15044 774 15045 749 15045 8027 15045 775 15046 8028 15046 8029 15046 775 15047 8030 15047 8028 15047 775 15048 8031 15048 8030 15048 775 15049 8027 15049 8031 15049 775 15050 774 15050 8027 15050 776 15051 8029 15051 747 15051 776 15052 747 15052 746 15052 776 15053 775 15053 8029 15053 744 15054 776 15054 746 15054 742 15055 776 15055 744 15055 740 15056 776 15056 742 15056 774 15057 759 15057 757 15057 738 15058 776 15058 740 15058 805 15059 8032 15059 8033 15059 805 15060 8034 15060 8032 15060 805 15061 8035 15061 8034 15061 8036 15062 805 15062 8033 15062 8037 15063 805 15063 8036 15063 808 15064 8037 15064 8038 15064 808 15065 805 15065 8037 15065 8039 15066 808 15066 8038 15066 8040 15067 808 15067 8039 15067 8041 15068 808 15068 8040 15068 840 15069 808 15069 8041 15069 769 15070 840 15070 8041 15070 767 15071 840 15071 769 15071 765 15072 840 15072 767 15072 763 15073 840 15073 765 15073 761 15074 840 15074 763 15074 805 15075 826 15075 8035 15075 759 15076 840 15076 761 15076 784 15077 8042 15077 8043 15077 784 15078 8044 15078 8045 15078 784 15079 8046 15079 8044 15079 784 15080 8047 15080 8046 15080 784 15081 8043 15081 8047 15081 772 15082 8048 15082 8042 15082 772 15083 8049 15083 8048 15083 772 15084 8050 15084 8049 15084 772 15085 8051 15085 8050 15085 772 15086 8042 15086 784 15086 771 15087 730 15087 728 15087 771 15088 732 15088 730 15088 771 15089 734 15089 732 15089 771 15090 736 15090 734 15090 771 15091 728 15091 8051 15091 771 15092 8051 15092 772 15092 771 15093 738 15093 736 15093 841 15094 784 15094 8045 15094 8052 15095 823 15095 8053 15095 8054 15096 823 15096 8052 15096 8055 15097 823 15097 8054 15097 8056 15098 823 15098 8055 15098 8057 15099 798 15099 823 15099 8057 15100 823 15100 8056 15100 8058 15101 800 15101 8059 15101 8060 15102 8059 15102 800 15102 8061 15103 800 15103 8058 15103 8062 15104 8060 15104 800 15104 8063 15105 798 15105 8057 15105 8064 15106 800 15106 798 15106 8064 15107 8062 15107 800 15107 8065 15108 798 15108 8063 15108 8066 15109 8064 15109 798 15109 8066 15110 798 15110 8065 15110 823 15111 818 15111 8053 15111 826 15112 800 15112 8061 15112 832 15113 8067 15113 8068 15113 832 15114 8069 15114 8067 15114 832 15115 8070 15115 8069 15115 832 15116 8071 15116 8070 15116 8072 15117 8071 15117 832 15117 831 15118 8073 15118 8072 15118 831 15119 8074 15119 8073 15119 831 15120 8072 15120 832 15120 8075 15121 8074 15121 831 15121 8076 15122 8075 15122 831 15122 838 15123 8077 15123 8076 15123 838 15124 8076 15124 831 15124 8078 15125 8077 15125 838 15125 8079 15126 8078 15126 838 15126 8080 15127 8079 15127 838 15127 8081 15128 8080 15128 838 15128 838 15129 841 15129 8081 15129 825 15130 832 15130 8068 15130 817 15131 8082 15131 8083 15131 817 15132 8084 15132 8082 15132 8085 15133 8084 15133 817 15133 725 15134 8085 15134 817 15134 723 15135 817 15135 821 15135 723 15136 725 15136 817 15136 721 15137 723 15137 821 15137 719 15138 721 15138 821 15138 717 15139 719 15139 821 15139 715 15140 821 15140 820 15140 715 15141 717 15141 821 15141 712 15142 715 15142 820 15142 8086 15143 712 15143 820 15143 8087 15144 8086 15144 820 15144 8088 15145 8087 15145 820 15145 8089 15146 8088 15146 820 15146 820 15147 825 15147 8089 15147 818 15148 817 15148 8083 15148 8057 15149 8056 15149 8090 15149 8057 15150 8090 15150 8091 15150 8063 15151 8091 15151 8092 15151 8063 15152 8057 15152 8091 15152 8065 15153 8092 15153 8093 15153 8065 15154 8063 15154 8092 15154 8066 15155 8093 15155 8094 15155 8066 15156 8065 15156 8093 15156 8064 15157 8094 15157 8095 15157 8064 15158 8066 15158 8094 15158 8062 15159 8095 15159 8096 15159 8062 15160 8064 15160 8095 15160 8097 15161 8098 15161 8036 15161 8097 15162 8036 15162 8033 15162 8099 15163 8097 15163 8032 15163 8100 15164 8099 15164 8032 15164 8097 15165 8033 15165 8032 15165 8101 15166 8100 15166 8034 15166 8100 15167 8032 15167 8034 15167 8101 15168 8034 15168 8035 15168 8102 15169 8101 15169 826 15169 8101 15170 8035 15170 826 15170 8103 15171 8102 15171 8061 15171 8102 15172 826 15172 8061 15172 8104 15173 8103 15173 8058 15173 8103 15174 8061 15174 8058 15174 8105 15175 8104 15175 8059 15175 8104 15176 8058 15176 8059 15176 8106 15177 8105 15177 8060 15177 8105 15178 8059 15178 8060 15178 8096 15179 8106 15179 8062 15179 8106 15180 8060 15180 8062 15180 8037 15181 8036 15181 8098 15181 8037 15182 8098 15182 8107 15182 8038 15183 8108 15183 8109 15183 8038 15184 8107 15184 8108 15184 8038 15185 8037 15185 8107 15185 8039 15186 8038 15186 8109 15186 8040 15187 8109 15187 8110 15187 8040 15188 8039 15188 8109 15188 8041 15189 8110 15189 8111 15189 8041 15190 8040 15190 8110 15190 769 15191 8111 15191 768 15191 769 15192 8041 15192 8111 15192 8027 15193 749 15193 748 15193 8027 15194 8112 15194 8113 15194 8027 15195 748 15195 8112 15195 8031 15196 8113 15196 8114 15196 8031 15197 8027 15197 8113 15197 8030 15198 8114 15198 8115 15198 8030 15199 8031 15199 8114 15199 8028 15200 8115 15200 8116 15200 8028 15201 8030 15201 8115 15201 8029 15202 8116 15202 745 15202 8029 15203 8028 15203 8116 15203 747 15204 8029 15204 745 15204 8051 15205 728 15205 727 15205 8051 15206 8117 15206 8118 15206 8051 15207 727 15207 8117 15207 8050 15208 8118 15208 8119 15208 8050 15209 8051 15209 8118 15209 8049 15210 8119 15210 8120 15210 8049 15211 8050 15211 8119 15211 8048 15212 8120 15212 8121 15212 8048 15213 8049 15213 8120 15213 8042 15214 8121 15214 8122 15214 8042 15215 8048 15215 8121 15215 8043 15216 8042 15216 8122 15216 8123 15217 8124 15217 8077 15217 8125 15218 8123 15218 8078 15218 8123 15219 8077 15219 8078 15219 8126 15220 8125 15220 8079 15220 8125 15221 8078 15221 8079 15221 8127 15222 8126 15222 8080 15222 8126 15223 8079 15223 8080 15223 8128 15224 8127 15224 8081 15224 8127 15225 8080 15225 8081 15225 8129 15226 8128 15226 841 15226 8128 15227 8081 15227 841 15227 8130 15228 8129 15228 8045 15228 8129 15229 841 15229 8045 15229 8131 15230 8130 15230 8044 15230 8130 15231 8045 15231 8044 15231 8132 15232 8131 15232 8046 15232 8131 15233 8044 15233 8046 15233 8122 15234 8132 15234 8047 15234 8132 15235 8046 15235 8047 15235 8122 15236 8047 15236 8043 15236 8077 15237 8124 15237 8133 15237 8076 15238 8133 15238 8134 15238 8076 15239 8077 15239 8133 15239 8075 15240 8076 15240 8134 15240 8074 15241 8134 15241 8135 15241 8074 15242 8075 15242 8134 15242 8073 15243 8135 15243 8136 15243 8073 15244 8074 15244 8135 15244 8072 15245 8136 15245 8137 15245 8072 15246 8073 15246 8136 15246 8071 15247 8137 15247 8138 15247 8071 15248 8072 15248 8137 15248 713 15249 712 15249 8086 15249 8139 15250 713 15250 8086 15250 8140 15251 8139 15251 8087 15251 8139 15252 8086 15252 8087 15252 8141 15253 8140 15253 8088 15253 8140 15254 8087 15254 8088 15254 8142 15255 8141 15255 8089 15255 8141 15256 8088 15256 8089 15256 8143 15257 8142 15257 825 15257 8142 15258 8089 15258 825 15258 8144 15259 8143 15259 8068 15259 8143 15260 825 15260 8068 15260 8145 15261 8144 15261 8067 15261 8144 15262 8068 15262 8067 15262 8146 15263 8145 15263 8069 15263 8145 15264 8067 15264 8069 15264 8147 15265 8146 15265 8070 15265 8146 15266 8069 15266 8070 15266 8138 15267 8147 15267 8071 15267 8147 15268 8070 15268 8071 15268 8090 15269 8056 15269 8055 15269 8148 15270 8090 15270 8055 15270 8149 15271 8148 15271 8055 15271 8150 15272 8149 15272 8054 15272 8149 15273 8055 15273 8054 15273 8150 15274 8054 15274 8052 15274 8151 15275 8150 15275 8053 15275 8150 15276 8052 15276 8053 15276 8152 15277 8151 15277 818 15277 8151 15278 8053 15278 818 15278 8153 15279 8152 15279 8083 15279 8152 15280 818 15280 8083 15280 8154 15281 8153 15281 8082 15281 8153 15282 8083 15282 8082 15282 8155 15283 8154 15283 8084 15283 8154 15284 8082 15284 8084 15284 8156 15285 8155 15285 8085 15285 8155 15286 8084 15286 8085 15286 724 15287 8156 15287 725 15287 8156 15288 8085 15288 725 15288 8093 15289 718 15289 8135 15289 8099 15290 8100 15290 8106 15290 8093 15291 8135 15291 8119 15291 8099 15292 8106 15292 8097 15292 8093 15293 8092 15293 720 15293 8121 15294 8133 15294 8122 15294 733 15295 727 15295 731 15295 735 15296 727 15296 733 15296 8111 15297 8110 15297 8113 15297 8111 15298 8113 15298 8112 15298 737 15299 727 15299 735 15299 739 15300 727 15300 737 15300 768 15301 8111 15301 8112 15301 768 15302 8112 15302 748 15302 768 15303 748 15303 751 15303 752 15304 768 15304 751 15304 741 15305 727 15305 739 15305 8138 15306 8140 15306 8141 15306 8154 15307 8155 15307 8156 15307 8138 15308 8141 15308 8142 15308 8138 15309 8142 15309 8143 15309 8138 15310 8143 15310 8144 15310 743 15311 727 15311 741 15311 8138 15312 8144 15312 8145 15312 8138 15313 8145 15313 8146 15313 8138 15314 8146 15314 8147 15314 8139 15315 8140 15315 8138 15315 745 15316 727 15316 743 15316 754 15317 768 15317 752 15317 8120 15318 8134 15318 8133 15318 713 15319 8139 15319 8138 15319 713 15320 8138 15320 8137 15320 764 15321 766 15321 768 15321 8120 15322 8133 15322 8121 15322 756 15323 768 15323 754 15323 8116 15324 727 15324 745 15324 762 15325 764 15325 768 15325 8116 15326 8117 15326 727 15326 8151 15327 8152 15327 8153 15327 758 15328 768 15328 756 15328 8151 15329 8153 15329 8154 15329 8115 15330 8117 15330 8116 15330 8115 15331 8118 15331 8117 15331 760 15332 762 15332 768 15332 8151 15333 8154 15333 8156 15333 760 15334 768 15334 758 15334 8119 15335 8135 15335 8134 15335 8119 15336 8134 15336 8120 15336 8114 15337 8118 15337 8115 15337 8114 15338 8119 15338 8118 15338 8149 15339 8150 15339 8151 15339 8149 15340 8151 15340 8156 15340 714 15341 713 15341 8137 15341 8148 15342 8156 15342 724 15342 8148 15343 8149 15343 8156 15343 8090 15344 724 15344 722 15344 8090 15345 8148 15345 724 15345 8104 15346 8105 15346 8106 15346 8108 15347 8094 15347 8093 15347 716 15348 8137 15348 8136 15348 8091 15349 8090 15349 722 15349 716 15350 714 15350 8137 15350 8109 15351 8108 15351 8093 15351 8109 15352 8119 15352 8114 15352 8109 15353 8093 15353 8119 15353 8107 15354 8095 15354 8094 15354 8107 15355 8094 15355 8108 15355 8092 15356 722 15356 720 15356 718 15357 716 15357 8136 15357 8102 15358 8103 15358 8104 15358 718 15359 8136 15359 8135 15359 8110 15360 8109 15360 8114 15360 8110 15361 8114 15361 8113 15361 8092 15362 8091 15362 722 15362 8122 15363 8133 15363 8124 15363 8122 15364 8124 15364 8123 15364 8098 15365 8096 15365 8095 15365 8122 15366 8123 15366 8125 15366 8122 15367 8125 15367 8126 15367 8122 15368 8126 15368 8127 15368 8122 15369 8127 15369 8128 15369 8098 15370 8095 15370 8107 15370 729 15371 727 15371 726 15371 8122 15372 8128 15372 8129 15372 8122 15373 8129 15373 8130 15373 8122 15374 8130 15374 8131 15374 8122 15375 8131 15375 8132 15375 8098 15376 8106 15376 8096 15376 8101 15377 8102 15377 8104 15377 731 15378 727 15378 729 15378 8101 15379 8104 15379 8106 15379 8097 15380 8106 15380 8098 15380 8100 15381 8101 15381 8106 15381 8093 15382 720 15382 718 15382 641 15383 617 15383 616 15383 641 15384 620 15384 617 15384 641 15385 622 15385 620 15385 641 15386 624 15386 622 15386 641 15387 616 15387 8157 15387 642 15388 8158 15388 8159 15388 642 15389 8160 15389 8158 15389 642 15390 8161 15390 8160 15390 642 15391 8157 15391 8161 15391 642 15392 641 15392 8157 15392 643 15393 8159 15393 614 15393 643 15394 614 15394 613 15394 643 15395 642 15395 8159 15395 611 15396 643 15396 613 15396 609 15397 643 15397 611 15397 607 15398 643 15398 609 15398 641 15399 626 15399 624 15399 605 15400 643 15400 607 15400 672 15401 8162 15401 8163 15401 672 15402 8164 15402 8162 15402 672 15403 8165 15403 8164 15403 8166 15404 672 15404 8163 15404 8167 15405 672 15405 8166 15405 675 15406 8167 15406 8168 15406 675 15407 672 15407 8167 15407 8169 15408 675 15408 8168 15408 8170 15409 675 15409 8169 15409 8171 15410 675 15410 8170 15410 707 15411 675 15411 8171 15411 636 15412 707 15412 8171 15412 634 15413 707 15413 636 15413 632 15414 707 15414 634 15414 630 15415 707 15415 632 15415 628 15416 707 15416 630 15416 672 15417 693 15417 8165 15417 626 15418 707 15418 628 15418 651 15419 8172 15419 8173 15419 651 15420 8174 15420 8175 15420 651 15421 8176 15421 8174 15421 651 15422 8177 15422 8176 15422 651 15423 8173 15423 8177 15423 639 15424 8178 15424 8172 15424 639 15425 8179 15425 8178 15425 639 15426 8180 15426 8179 15426 639 15427 8181 15427 8180 15427 639 15428 8172 15428 651 15428 638 15429 597 15429 595 15429 638 15430 599 15430 597 15430 638 15431 601 15431 599 15431 638 15432 603 15432 601 15432 638 15433 595 15433 8181 15433 638 15434 8181 15434 639 15434 638 15435 605 15435 603 15435 708 15436 651 15436 8175 15436 8182 15437 690 15437 8183 15437 8184 15438 690 15438 8182 15438 8185 15439 690 15439 8184 15439 8186 15440 690 15440 8185 15440 8187 15441 665 15441 690 15441 8187 15442 690 15442 8186 15442 8188 15443 667 15443 8189 15443 8190 15444 8189 15444 667 15444 8191 15445 667 15445 8188 15445 8192 15446 8190 15446 667 15446 8193 15447 665 15447 8187 15447 8194 15448 667 15448 665 15448 8194 15449 8192 15449 667 15449 8195 15450 665 15450 8193 15450 8196 15451 8194 15451 665 15451 8196 15452 665 15452 8195 15452 690 15453 685 15453 8183 15453 693 15454 667 15454 8191 15454 699 15455 8197 15455 8198 15455 699 15456 8199 15456 8197 15456 699 15457 8200 15457 8199 15457 699 15458 8201 15458 8200 15458 8202 15459 8201 15459 699 15459 698 15460 8203 15460 8202 15460 698 15461 8204 15461 8203 15461 698 15462 8202 15462 699 15462 8205 15463 8204 15463 698 15463 8206 15464 8205 15464 698 15464 705 15465 8207 15465 8206 15465 705 15466 8206 15466 698 15466 8208 15467 8207 15467 705 15467 8209 15468 8208 15468 705 15468 8210 15469 8209 15469 705 15469 8211 15470 8210 15470 705 15470 705 15471 708 15471 8211 15471 692 15472 699 15472 8198 15472 684 15473 8212 15473 8213 15473 684 15474 8214 15474 8212 15474 8215 15475 8214 15475 684 15475 591 15476 8215 15476 684 15476 589 15477 684 15477 688 15477 589 15478 591 15478 684 15478 587 15479 589 15479 688 15479 585 15480 587 15480 688 15480 583 15481 585 15481 688 15481 579 15482 688 15482 687 15482 579 15483 583 15483 688 15483 582 15484 579 15484 687 15484 8216 15485 582 15485 687 15485 8217 15486 8216 15486 687 15486 8218 15487 8217 15487 687 15487 8219 15488 8218 15488 687 15488 687 15489 692 15489 8219 15489 685 15490 684 15490 8213 15490 8187 15491 8186 15491 8220 15491 8187 15492 8220 15492 8221 15492 8193 15493 8221 15493 8222 15493 8193 15494 8187 15494 8221 15494 8195 15495 8222 15495 8223 15495 8195 15496 8193 15496 8222 15496 8196 15497 8223 15497 8224 15497 8196 15498 8195 15498 8223 15498 8194 15499 8224 15499 8225 15499 8194 15500 8196 15500 8224 15500 8192 15501 8225 15501 8226 15501 8192 15502 8194 15502 8225 15502 8227 15503 8228 15503 8166 15503 8229 15504 8227 15504 8163 15504 8227 15505 8166 15505 8163 15505 8230 15506 8229 15506 8162 15506 8229 15507 8163 15507 8162 15507 8231 15508 8230 15508 8164 15508 8230 15509 8162 15509 8164 15509 8232 15510 8231 15510 8165 15510 8231 15511 8164 15511 8165 15511 8233 15512 8232 15512 693 15512 8232 15513 8165 15513 693 15513 8234 15514 8233 15514 8191 15514 8233 15515 693 15515 8191 15515 8235 15516 8234 15516 8188 15516 8234 15517 8191 15517 8188 15517 8236 15518 8235 15518 8189 15518 8235 15519 8188 15519 8189 15519 8236 15520 8189 15520 8190 15520 8226 15521 8236 15521 8192 15521 8236 15522 8190 15522 8192 15522 8166 15523 8228 15523 8237 15523 8167 15524 8166 15524 8237 15524 8168 15525 8237 15525 8238 15525 8168 15526 8167 15526 8237 15526 8169 15527 8239 15527 8240 15527 8169 15528 8238 15528 8239 15528 8169 15529 8168 15529 8238 15529 8170 15530 8169 15530 8240 15530 8171 15531 8241 15531 635 15531 8171 15532 8240 15532 8241 15532 8171 15533 8170 15533 8240 15533 636 15534 8171 15534 635 15534 8157 15535 616 15535 615 15535 8157 15536 8242 15536 8243 15536 8157 15537 615 15537 8242 15537 8161 15538 8243 15538 8244 15538 8161 15539 8157 15539 8243 15539 8160 15540 8244 15540 8245 15540 8160 15541 8161 15541 8244 15541 8158 15542 8245 15542 8246 15542 8158 15543 8160 15543 8245 15543 8159 15544 8246 15544 612 15544 8159 15545 8158 15545 8246 15545 614 15546 8159 15546 612 15546 595 15547 594 15547 8247 15547 8181 15548 8247 15548 8248 15548 8181 15549 595 15549 8247 15549 8180 15550 8248 15550 8249 15550 8180 15551 8181 15551 8248 15551 8179 15552 8249 15552 8250 15552 8179 15553 8180 15553 8249 15553 8178 15554 8250 15554 8251 15554 8178 15555 8179 15555 8250 15555 8172 15556 8251 15556 8252 15556 8172 15557 8178 15557 8251 15557 8173 15558 8172 15558 8252 15558 8253 15559 8207 15559 8208 15559 8254 15560 8253 15560 8208 15560 8255 15561 8254 15561 8209 15561 8254 15562 8208 15562 8209 15562 8256 15563 8255 15563 8210 15563 8255 15564 8209 15564 8210 15564 8257 15565 8256 15565 8211 15565 8256 15566 8210 15566 8211 15566 8258 15567 8257 15567 708 15567 8257 15568 8211 15568 708 15568 8259 15569 8258 15569 8175 15569 8258 15570 708 15570 8175 15570 8260 15571 8259 15571 8174 15571 8259 15572 8175 15572 8174 15572 8261 15573 8260 15573 8176 15573 8260 15574 8174 15574 8176 15574 8262 15575 8261 15575 8177 15575 8261 15576 8176 15576 8177 15576 8252 15577 8262 15577 8173 15577 8262 15578 8177 15578 8173 15578 8207 15579 8253 15579 8263 15579 8206 15580 8207 15580 8263 15580 8205 15581 8264 15581 8265 15581 8205 15582 8263 15582 8264 15582 8205 15583 8206 15583 8263 15583 8204 15584 8265 15584 8266 15584 8204 15585 8205 15585 8265 15585 8203 15586 8204 15586 8266 15586 8202 15587 8267 15587 8268 15587 8202 15588 8266 15588 8267 15588 8202 15589 8203 15589 8266 15589 8201 15590 8202 15590 8268 15590 580 15591 582 15591 8216 15591 8269 15592 580 15592 8216 15592 8270 15593 8269 15593 8217 15593 8269 15594 8216 15594 8217 15594 8271 15595 8270 15595 8218 15595 8270 15596 8217 15596 8218 15596 8272 15597 8271 15597 8219 15597 8271 15598 8218 15598 8219 15598 8273 15599 8272 15599 692 15599 8272 15600 8219 15600 692 15600 8274 15601 8273 15601 8198 15601 8273 15602 692 15602 8198 15602 8275 15603 8274 15603 8197 15603 8274 15604 8198 15604 8197 15604 8276 15605 8275 15605 8199 15605 8275 15606 8197 15606 8199 15606 8277 15607 8276 15607 8200 15607 8268 15608 8277 15608 8200 15608 8276 15609 8199 15609 8200 15609 8268 15610 8200 15610 8201 15610 8278 15611 8220 15611 8186 15611 8279 15612 8278 15612 8185 15612 8278 15613 8186 15613 8185 15613 8280 15614 8279 15614 8184 15614 8279 15615 8185 15615 8184 15615 8281 15616 8280 15616 8182 15616 8280 15617 8184 15617 8182 15617 8282 15618 8281 15618 8183 15618 8281 15619 8182 15619 8183 15619 8283 15620 8282 15620 685 15620 8282 15621 8183 15621 685 15621 8284 15622 8283 15622 8213 15622 8283 15623 685 15623 8213 15623 8285 15624 8284 15624 8212 15624 8284 15625 8213 15625 8212 15625 8286 15626 8285 15626 8214 15626 8285 15627 8212 15627 8214 15627 592 15628 8286 15628 8215 15628 8286 15629 8214 15629 8215 15629 592 15630 8215 15630 591 15630 635 15631 8241 15631 8242 15631 635 15632 8242 15632 615 15632 635 15633 615 15633 618 15633 604 15634 594 15634 602 15634 606 15635 594 15635 604 15635 619 15636 635 15636 618 15636 608 15637 594 15637 606 15637 621 15638 635 15638 619 15638 610 15639 594 15639 608 15639 631 15640 633 15640 635 15640 612 15641 594 15641 610 15641 623 15642 635 15642 621 15642 8250 15643 8265 15643 8264 15643 629 15644 631 15644 635 15644 8250 15645 8264 15645 8251 15645 625 15646 635 15646 623 15646 8268 15647 8270 15647 8271 15647 8268 15648 8271 15648 8272 15648 8268 15649 8272 15649 8273 15649 8246 15650 594 15650 612 15650 8268 15651 8273 15651 8274 15651 8268 15652 8274 15652 8275 15652 627 15653 629 15653 635 15653 8268 15654 8275 15654 8276 15654 627 15655 635 15655 625 15655 8268 15656 8276 15656 8277 15656 8246 15657 8247 15657 594 15657 8269 15658 8270 15658 8268 15658 8245 15659 8247 15659 8246 15659 8245 15660 8248 15660 8247 15660 580 15661 8269 15661 8268 15661 8249 15662 8265 15662 8250 15662 8244 15663 8248 15663 8245 15663 8244 15664 8249 15664 8248 15664 8235 15665 8236 15665 8226 15665 8253 15666 8254 15666 8255 15666 8253 15667 8255 15667 8256 15667 8253 15668 8256 15668 8257 15668 8220 15669 8278 15669 8279 15669 8258 15670 8253 15670 8257 15670 8220 15671 8279 15671 8280 15671 8220 15672 8280 15672 8281 15672 8234 15673 8235 15673 8226 15673 8220 15674 8281 15674 8282 15674 8220 15675 8282 15675 8283 15675 8220 15676 8283 15676 8284 15676 8220 15677 8284 15677 8285 15677 8233 15678 8234 15678 8226 15678 8220 15679 8285 15679 8286 15679 8220 15680 8286 15680 592 15680 8220 15681 592 15681 590 15681 8238 15682 8224 15682 8223 15682 581 15683 580 15683 8268 15683 581 15684 8268 15684 8267 15684 8221 15685 590 15685 588 15685 8239 15686 8223 15686 8265 15686 8259 15687 8253 15687 8258 15687 8239 15688 8238 15688 8223 15688 8221 15689 8220 15689 590 15689 8239 15690 8249 15690 8244 15690 8239 15691 8265 15691 8249 15691 8260 15692 8253 15692 8259 15692 8237 15693 8226 15693 8225 15693 8237 15694 8225 15694 8224 15694 8237 15695 8224 15695 8238 15695 8232 15696 8233 15696 8226 15696 584 15697 8267 15697 8266 15697 8240 15698 8239 15698 8244 15698 584 15699 581 15699 8267 15699 8240 15700 8244 15700 8243 15700 8222 15701 588 15701 586 15701 8261 15702 8253 15702 8260 15702 8228 15703 8226 15703 8237 15703 8222 15704 8221 15704 588 15704 8262 15705 8253 15705 8261 15705 8231 15706 8232 15706 8226 15706 596 15707 594 15707 593 15707 586 15708 584 15708 8266 15708 8227 15709 8226 15709 8228 15709 586 15710 8266 15710 8265 15710 598 15711 594 15711 596 15711 8230 15712 8231 15712 8226 15712 8252 15713 8253 15713 8262 15713 8229 15714 8226 15714 8227 15714 8229 15715 8230 15715 8226 15715 8223 15716 586 15716 8265 15716 8223 15717 8222 15717 586 15717 600 15718 594 15718 598 15718 8241 15719 8240 15719 8243 15719 8241 15720 8243 15720 8242 15720 602 15721 594 15721 600 15721 8251 15722 8253 15722 8252 15722 8251 15723 8264 15723 8263 15723 8251 15724 8263 15724 8253 15724 8287 15725 8288 15725 8289 15725 8288 15726 8290 15726 8289 15726 8291 15727 8287 15727 8292 15727 8287 15728 8289 15728 8292 15728 8293 15729 8291 15729 8294 15729 8291 15730 8292 15730 8294 15730 8295 15731 8293 15731 8296 15731 8293 15732 8294 15732 8296 15732 8297 15733 8295 15733 8298 15733 8295 15734 8296 15734 8298 15734 8299 15735 8297 15735 8300 15735 8297 15736 8298 15736 8300 15736 8301 15737 8299 15737 8302 15737 8299 15738 8300 15738 8302 15738 8303 15739 8301 15739 8304 15739 8301 15740 8302 15740 8304 15740 8305 15741 8303 15741 8306 15741 8303 15742 8304 15742 8306 15742 8305 15743 8306 15743 8307 15743 8307 15744 8306 15744 8308 15744 8307 15745 8308 15745 8309 15745 8309 15746 8308 15746 8310 15746 8311 15747 8309 15747 8312 15747 8309 15748 8310 15748 8312 15748 8313 15749 8311 15749 8314 15749 8311 15750 8312 15750 8314 15750 8313 15751 8314 15751 8315 15751 8315 15752 8314 15752 8316 15752 8315 15753 8316 15753 8317 15753 8317 15754 8316 15754 8318 15754 8317 15755 8318 15755 8319 15755 8319 15756 8318 15756 8320 15756 8319 15757 8320 15757 8321 15757 8321 15758 8320 15758 8322 15758 8321 15759 8322 15759 8323 15759 8323 15760 8322 15760 8324 15760 8323 15761 8324 15761 8325 15761 8325 15762 8324 15762 8326 15762 8327 15763 8325 15763 8328 15763 8325 15764 8326 15764 8328 15764 8329 15765 8327 15765 8330 15765 8327 15766 8328 15766 8330 15766 8331 15767 8329 15767 8332 15767 8329 15768 8330 15768 8332 15768 8333 15769 8331 15769 8334 15769 8331 15770 8332 15770 8334 15770 8335 15771 8333 15771 8334 15771 8335 15772 8334 15772 8336 15772 8337 15773 8335 15773 8338 15773 8335 15774 8336 15774 8338 15774 8339 15775 8337 15775 8340 15775 8337 15776 8338 15776 8340 15776 8341 15777 8339 15777 8342 15777 8339 15778 8340 15778 8342 15778 8343 15779 8341 15779 8344 15779 8341 15780 8342 15780 8344 15780 8343 15781 8344 15781 8345 15781 8345 15782 8344 15782 8346 15782 8345 15783 8346 15783 8347 15783 8347 15784 8346 15784 8348 15784 8347 15785 8348 15785 8349 15785 8349 15786 8348 15786 8350 15786 8351 15787 8349 15787 8352 15787 8349 15788 8350 15788 8352 15788 8353 15789 8351 15789 8354 15789 8351 15790 8352 15790 8354 15790 8355 15791 8353 15791 8356 15791 8353 15792 8354 15792 8356 15792 8357 15793 8355 15793 8358 15793 8355 15794 8356 15794 8358 15794 8359 15795 8357 15795 8360 15795 8357 15796 8358 15796 8360 15796 8359 15797 8360 15797 8361 15797 8361 15798 8360 15798 8362 15798 8361 15799 8362 15799 8363 15799 8363 15800 8362 15800 8364 15800 8363 15801 8364 15801 8365 15801 8365 15802 8364 15802 8366 15802 8367 15803 8365 15803 8368 15803 8365 15804 8366 15804 8368 15804 8369 15805 8367 15805 8370 15805 8367 15806 8368 15806 8370 15806 8369 15807 8370 15807 8371 15807 8371 15808 8370 15808 8372 15808 8371 15809 8372 15809 8373 15809 8373 15810 8372 15810 8374 15810 8375 15811 8373 15811 8376 15811 8373 15812 8374 15812 8376 15812 8375 15813 8376 15813 8377 15813 8377 15814 8376 15814 8378 15814 8379 15815 8377 15815 8380 15815 8377 15816 8378 15816 8380 15816 8379 15817 8380 15817 8381 15817 8381 15818 8380 15818 8382 15818 8383 15819 8381 15819 8384 15819 8381 15820 8382 15820 8384 15820 8385 15821 8383 15821 8386 15821 8383 15822 8384 15822 8386 15822 8385 15823 8386 15823 8387 15823 8387 15824 8386 15824 8388 15824 8387 15825 8388 15825 8389 15825 8389 15826 8388 15826 8390 15826 8391 15827 8389 15827 8392 15827 8389 15828 8390 15828 8392 15828 8393 15829 8391 15829 8394 15829 8391 15830 8392 15830 8394 15830 8393 15831 8394 15831 8395 15831 8395 15832 8394 15832 8396 15832 8397 15833 8395 15833 8398 15833 8395 15834 8396 15834 8398 15834 8399 15835 8397 15835 8400 15835 8397 15836 8398 15836 8400 15836 8399 15837 8400 15837 8401 15837 8401 15838 8400 15838 8402 15838 8403 15839 8401 15839 8404 15839 8401 15840 8402 15840 8404 15840 8403 15841 8404 15841 8405 15841 8405 15842 8404 15842 8406 15842 8407 15843 8405 15843 8408 15843 8405 15844 8406 15844 8408 15844 8409 15845 8407 15845 8410 15845 8407 15846 8408 15846 8410 15846 8411 15847 8409 15847 8412 15847 8409 15848 8410 15848 8412 15848 8411 15849 8412 15849 8413 15849 8413 15850 8412 15850 8414 15850 8415 15851 8413 15851 8416 15851 8413 15852 8414 15852 8416 15852 8415 15853 8416 15853 8417 15853 8417 15854 8416 15854 8418 15854 8419 15855 8417 15855 8420 15855 8417 15856 8418 15856 8420 15856 8419 15857 8420 15857 8421 15857 8421 15858 8420 15858 8422 15858 8423 15859 8421 15859 8424 15859 8421 15860 8422 15860 8424 15860 8425 15861 8423 15861 8424 15861 8425 15862 8424 15862 8426 15862 8427 15863 8425 15863 8428 15863 8425 15864 8426 15864 8428 15864 8429 15865 8427 15865 8430 15865 8427 15866 8428 15866 8430 15866 8429 15867 8430 15867 8431 15867 8431 15868 8430 15868 8432 15868 8433 15869 8431 15869 8434 15869 8431 15870 8432 15870 8434 15870 8435 15871 8433 15871 8436 15871 8433 15872 8434 15872 8436 15872 8437 15873 8435 15873 8438 15873 8435 15874 8436 15874 8438 15874 8437 15875 8438 15875 8439 15875 8439 15876 8438 15876 8440 15876 8439 15877 8440 15877 8441 15877 8441 15878 8440 15878 8442 15878 8443 15879 8441 15879 8442 15879 8443 15880 8442 15880 8444 15880 8443 15881 8444 15881 8445 15881 8445 15882 8444 15882 8446 15882 8447 15883 8445 15883 8446 15883 8447 15884 8446 15884 8448 15884 8447 15885 8448 15885 8449 15885 8449 15886 8448 15886 8450 15886 8449 15887 8450 15887 8451 15887 8451 15888 8450 15888 8452 15888 8451 15889 8452 15889 8453 15889 8453 15890 8452 15890 8454 15890 8455 15891 8453 15891 8456 15891 8453 15892 8454 15892 8456 15892 8455 15893 8456 15893 8457 15893 8457 15894 8456 15894 8458 15894 8457 15895 8458 15895 8459 15895 8459 15896 8458 15896 8460 15896 8459 15897 8460 15897 8461 15897 8461 15898 8460 15898 8462 15898 8461 15899 8462 15899 8463 15899 8463 15900 8462 15900 8464 15900 8463 15901 8464 15901 8465 15901 8465 15902 8464 15902 8466 15902 8467 15903 8465 15903 8468 15903 8465 15904 8466 15904 8468 15904 8469 15905 8467 15905 8470 15905 8467 15906 8468 15906 8470 15906 8469 15907 8470 15907 8471 15907 8471 15908 8470 15908 8472 15908 8471 15909 8472 15909 8473 15909 8473 15910 8472 15910 8474 15910 8475 15911 8473 15911 8476 15911 8473 15912 8474 15912 8476 15912 8477 15913 8475 15913 8478 15913 8475 15914 8476 15914 8478 15914 8477 15915 8478 15915 8479 15915 8479 15916 8478 15916 8480 15916 8481 15917 8479 15917 8482 15917 8479 15918 8480 15918 8482 15918 8481 15919 8482 15919 8483 15919 8483 15920 8482 15920 8484 15920 8485 15921 8483 15921 8486 15921 8483 15922 8484 15922 8486 15922 8487 15923 8485 15923 8488 15923 8485 15924 8486 15924 8488 15924 8489 15925 8487 15925 8490 15925 8487 15926 8488 15926 8490 15926 8491 15927 8489 15927 8492 15927 8489 15928 8490 15928 8492 15928 8493 15929 8491 15929 8494 15929 8491 15930 8492 15930 8494 15930 8493 15931 8494 15931 8495 15931 8495 15932 8494 15932 8496 15932 8497 15933 8495 15933 8498 15933 8495 15934 8496 15934 8498 15934 8497 15935 8498 15935 8499 15935 8499 15936 8498 15936 8500 15936 8499 15937 8500 15937 8501 15937 8501 15938 8500 15938 8502 15938 8501 15939 8502 15939 8503 15939 8503 15940 8502 15940 8504 15940 8503 15941 8504 15941 8505 15941 8505 15942 8504 15942 8506 15942 8505 15943 8506 15943 8507 15943 8507 15944 8506 15944 8508 15944 8507 15945 8508 15945 8509 15945 8509 15946 8508 15946 8510 15946 8509 15947 8510 15947 8511 15947 8511 15948 8510 15948 8512 15948 8511 15949 8512 15949 8513 15949 8513 15950 8512 15950 8514 15950 8515 15951 8513 15951 8516 15951 8513 15952 8514 15952 8516 15952 8517 15953 8515 15953 8518 15953 8515 15954 8516 15954 8518 15954 8517 15955 8518 15955 8519 15955 8519 15956 8518 15956 8520 15956 8521 15957 8519 15957 8522 15957 8519 15958 8520 15958 8522 15958 8521 15959 8522 15959 8523 15959 8523 15960 8522 15960 8524 15960 8523 15961 8524 15961 8525 15961 8525 15962 8524 15962 8526 15962 8525 15963 8526 15963 8527 15963 8527 15964 8526 15964 8528 15964 8527 15965 8528 15965 8529 15965 8529 15966 8528 15966 8530 15966 8531 15967 8529 15967 8532 15967 8529 15968 8530 15968 8532 15968 8533 15969 8531 15969 8534 15969 8531 15970 8532 15970 8534 15970 8535 15971 8533 15971 8536 15971 8533 15972 8534 15972 8536 15972 8537 15973 8535 15973 8538 15973 8535 15974 8536 15974 8538 15974 8539 15975 8537 15975 8540 15975 8537 15976 8538 15976 8540 15976 8539 15977 8540 15977 8541 15977 8541 15978 8540 15978 8542 15978 8541 15979 8542 15979 8543 15979 8543 15980 8542 15980 8544 15980 8545 15981 8543 15981 8546 15981 8543 15982 8544 15982 8546 15982 8547 15983 8545 15983 8548 15983 8545 15984 8546 15984 8548 15984 8547 15985 8548 15985 8549 15985 8549 15986 8548 15986 8550 15986 8549 15987 8550 15987 8551 15987 8551 15988 8550 15988 8552 15988 8553 15989 8551 15989 8554 15989 8551 15990 8552 15990 8554 15990 8555 15991 8553 15991 8556 15991 8553 15992 8554 15992 8556 15992 8555 15993 8556 15993 8557 15993 8557 15994 8556 15994 8558 15994 8557 15995 8558 15995 8559 15995 8559 15996 8558 15996 8560 15996 8561 15997 8559 15997 8562 15997 8559 15998 8560 15998 8562 15998 8561 15999 8562 15999 8563 15999 8563 16000 8562 16000 8564 16000 8565 16001 8563 16001 8566 16001 8563 16002 8564 16002 8566 16002 8565 16003 8566 16003 8567 16003 8567 16004 8566 16004 8568 16004 8567 16005 8568 16005 8569 16005 8569 16006 8568 16006 8570 16006 8571 16007 8569 16007 8572 16007 8569 16008 8570 16008 8572 16008 8571 16009 8572 16009 8573 16009 8573 16010 8572 16010 8574 16010 8573 16011 8574 16011 8575 16011 8575 16012 8574 16012 8576 16012 8577 16013 8575 16013 8578 16013 8575 16014 8576 16014 8578 16014 8579 16015 8577 16015 8580 16015 8577 16016 8578 16016 8580 16016 8579 16017 8580 16017 8581 16017 8581 16018 8580 16018 8582 16018 8581 16019 8582 16019 8583 16019 8583 16020 8582 16020 8584 16020 8583 16021 8584 16021 8585 16021 8585 16022 8584 16022 8586 16022 8587 16023 8585 16023 8588 16023 8585 16024 8586 16024 8588 16024 8587 16025 8588 16025 8589 16025 8589 16026 8588 16026 8590 16026 8589 16027 8590 16027 8591 16027 8591 16028 8590 16028 8592 16028 8591 16029 8592 16029 8593 16029 8593 16030 8592 16030 8594 16030 8593 16031 8594 16031 8595 16031 8595 16032 8594 16032 8596 16032 8595 16033 8596 16033 8597 16033 8597 16034 8596 16034 8598 16034 8597 16035 8598 16035 8599 16035 8599 16036 8598 16036 8600 16036 8601 16037 8599 16037 8602 16037 8599 16038 8600 16038 8602 16038 8603 16039 8601 16039 8604 16039 8601 16040 8602 16040 8604 16040 8605 16041 8603 16041 8606 16041 8603 16042 8604 16042 8606 16042 8607 16043 8605 16043 8608 16043 8605 16044 8606 16044 8608 16044 8607 16045 8608 16045 8609 16045 8609 16046 8608 16046 8610 16046 8609 16047 8610 16047 8611 16047 8611 16048 8610 16048 8612 16048 8611 16049 8612 16049 8613 16049 8613 16050 8612 16050 8614 16050 8615 16051 8613 16051 8616 16051 8613 16052 8614 16052 8616 16052 8617 16053 8615 16053 8618 16053 8615 16054 8616 16054 8618 16054 8619 16055 8617 16055 8620 16055 8617 16056 8618 16056 8620 16056 8621 16057 8619 16057 8620 16057 8621 16058 8620 16058 8622 16058 8623 16059 8621 16059 8624 16059 8621 16060 8622 16060 8624 16060 8623 16061 8624 16061 8625 16061 8625 16062 8624 16062 8626 16062 8627 16063 8625 16063 8628 16063 8625 16064 8626 16064 8628 16064 8629 16065 8627 16065 8630 16065 8627 16066 8628 16066 8630 16066 8629 16067 8630 16067 8631 16067 8631 16068 8630 16068 8632 16068 8633 16069 8631 16069 8634 16069 8631 16070 8632 16070 8634 16070 8633 16071 8634 16071 8635 16071 8635 16072 8634 16072 8636 16072 8635 16073 8636 16073 8637 16073 8637 16074 8636 16074 8638 16074 8637 16075 8638 16075 8639 16075 8639 16076 8638 16076 8640 16076 8641 16077 8639 16077 8642 16077 8639 16078 8640 16078 8642 16078 8643 16079 8641 16079 8644 16079 8641 16080 8642 16080 8644 16080 8645 16081 8643 16081 8646 16081 8643 16082 8644 16082 8646 16082 8645 16083 8646 16083 8647 16083 8647 16084 8646 16084 8648 16084 8649 16085 8647 16085 8650 16085 8647 16086 8648 16086 8650 16086 8651 16087 8649 16087 8652 16087 8649 16088 8650 16088 8652 16088 8651 16089 8652 16089 8653 16089 8653 16090 8652 16090 8654 16090 8653 16091 8654 16091 8655 16091 8655 16092 8654 16092 8656 16092 8655 16093 8656 16093 8657 16093 8657 16094 8656 16094 8658 16094 8659 16095 8657 16095 8660 16095 8657 16096 8658 16096 8660 16096 8661 16097 8659 16097 8662 16097 8659 16098 8660 16098 8662 16098 8661 16099 8662 16099 8288 16099 8288 16100 8662 16100 8290 16100 8554 16101 8558 16101 8556 16101 8552 16102 8558 16102 8554 16102 8302 16103 8310 16103 8308 16103 8302 16104 8308 16104 8306 16104 8302 16105 8306 16105 8304 16105 8550 16106 8560 16106 8558 16106 8550 16107 8558 16107 8552 16107 8368 16108 8366 16108 8356 16108 8368 16109 8356 16109 8354 16109 8368 16110 8354 16110 8352 16110 8368 16111 8352 16111 8350 16111 8368 16112 8350 16112 8348 16112 8368 16113 8348 16113 8346 16113 8368 16114 8346 16114 8344 16114 8368 16115 8344 16115 8342 16115 8370 16116 8368 16116 8342 16116 8370 16117 8330 16117 8298 16117 8642 16118 8640 16118 8638 16118 8636 16119 8642 16119 8638 16119 8370 16120 8342 16120 8340 16120 8370 16121 8340 16121 8338 16121 8370 16122 8334 16122 8332 16122 8370 16123 8332 16123 8330 16123 8370 16124 8298 16124 8296 16124 8370 16125 8338 16125 8334 16125 8372 16126 8296 16126 8294 16126 8372 16127 8294 16127 8292 16127 8372 16128 8370 16128 8296 16128 8648 16129 8646 16129 8644 16129 8648 16130 8644 16130 8642 16130 8548 16131 8560 16131 8550 16131 8648 16132 8636 16132 8634 16132 8374 16133 8289 16133 8572 16133 8648 16134 8642 16134 8636 16134 8632 16135 8648 16135 8634 16135 8374 16136 8372 16136 8292 16136 8374 16137 8292 16137 8289 16137 8300 16138 8310 16138 8302 16138 8300 16139 8324 16139 8322 16139 8300 16140 8322 16140 8320 16140 8300 16141 8320 16141 8318 16141 8300 16142 8318 16142 8316 16142 8300 16143 8316 16143 8314 16143 8300 16144 8314 16144 8312 16144 8300 16145 8312 16145 8310 16145 8298 16146 8324 16146 8300 16146 8298 16147 8326 16147 8324 16147 8546 16148 8560 16148 8548 16148 8328 16149 8326 16149 8298 16149 8544 16150 8560 16150 8546 16150 8330 16151 8328 16151 8298 16151 8542 16152 8560 16152 8544 16152 8540 16153 8560 16153 8542 16153 1432 16154 8630 16154 8628 16154 1432 16155 8628 16155 1431 16155 1430 16156 8628 16156 8626 16156 1430 16157 1431 16157 8628 16157 8538 16158 8560 16158 8540 16158 8398 16159 8396 16159 8394 16159 1433 16160 8630 16160 1432 16160 1429 16161 1430 16161 8626 16161 8400 16162 8398 16162 8394 16162 1434 16163 8632 16163 8630 16163 1434 16164 8630 16164 1433 16164 8536 16165 8560 16165 8538 16165 8404 16166 8402 16166 8400 16166 1428 16167 1429 16167 8626 16167 8406 16168 8400 16168 8394 16168 8406 16169 8404 16169 8400 16169 1435 16170 8632 16170 1434 16170 1435 16171 8648 16171 8632 16171 8408 16172 8406 16172 8394 16172 1427 16173 1428 16173 8626 16173 8534 16174 8560 16174 8536 16174 1427 16175 8626 16175 8624 16175 8534 16176 8562 16176 8560 16176 8412 16177 8408 16177 8394 16177 1436 16178 8650 16178 8648 16178 1436 16179 8648 16179 1435 16179 8412 16180 8410 16180 8408 16180 8412 16181 8394 16181 8392 16181 8414 16182 8412 16182 8392 16182 1426 16183 1427 16183 8624 16183 8532 16184 8562 16184 8534 16184 1437 16185 8652 16185 8650 16185 8532 16186 8564 16186 8562 16186 1437 16187 8650 16187 1436 16187 8416 16188 8414 16188 8392 16188 8418 16189 8392 16189 8390 16189 8418 16190 8416 16190 8392 16190 8530 16191 8564 16191 8532 16191 8420 16192 8418 16192 8390 16192 1424 16193 1426 16193 8624 16193 8528 16194 8564 16194 8530 16194 1438 16195 8656 16195 8654 16195 1438 16196 8654 16196 8652 16196 8422 16197 8420 16197 8390 16197 1438 16198 8652 16198 1437 16198 8422 16199 8390 16199 8388 16199 8338 16200 8336 16200 8334 16200 8622 16201 1424 16201 8624 16201 1422 16202 1424 16202 8622 16202 8474 16203 8382 16203 8380 16203 1439 16204 8658 16204 8656 16204 1439 16205 8656 16205 1438 16205 8472 16206 8384 16206 8382 16206 8472 16207 8382 16207 8474 16207 1419 16208 8622 16208 8620 16208 1419 16209 1422 16209 8622 16209 1416 16210 8660 16210 8658 16210 8470 16211 8386 16211 8384 16211 8470 16212 8384 16212 8472 16212 1416 16213 8658 16213 1439 16213 8476 16214 8380 16214 8378 16214 8476 16215 8474 16215 8380 16215 1415 16216 8660 16216 1416 16216 8478 16217 8476 16217 8378 16217 8478 16218 8378 16218 8376 16218 8468 16219 8388 16219 8386 16219 8468 16220 8386 16220 8470 16220 8480 16221 8478 16221 8376 16221 8466 16222 8422 16222 8388 16222 8466 16223 8388 16223 8468 16223 8464 16224 8424 16224 8422 16224 8618 16225 1425 16225 1420 16225 8618 16226 1419 16226 8620 16226 8464 16227 8422 16227 8466 16227 8618 16228 1420 16228 1419 16228 8482 16229 8480 16229 8376 16229 8482 16230 8376 16230 8374 16230 8482 16231 8572 16231 8570 16231 8482 16232 8374 16232 8572 16232 8484 16233 8482 16233 8570 16233 8484 16234 8570 16234 8568 16234 8462 16235 8426 16235 8424 16235 8462 16236 8424 16236 8464 16236 8486 16237 8484 16237 8568 16237 8486 16238 8568 16238 8566 16238 8428 16239 8462 16239 8460 16239 8428 16240 8426 16240 8462 16240 8488 16241 8564 16241 8528 16241 8488 16242 8566 16242 8564 16242 8488 16243 8486 16243 8566 16243 8488 16244 8528 16244 8526 16244 8488 16245 8526 16245 8524 16245 8458 16246 8428 16246 8460 16246 8430 16247 8428 16247 8458 16247 8522 16248 8488 16248 8524 16248 8604 16249 8612 16249 8610 16249 8604 16250 8610 16250 8608 16250 8604 16251 8608 16251 8606 16251 8432 16252 8430 16252 8458 16252 8434 16253 8432 16253 8458 16253 8456 16254 8434 16254 8458 16254 8520 16255 8488 16255 8522 16255 8520 16256 8490 16256 8488 16256 8600 16257 8604 16257 8602 16257 8438 16258 8436 16258 8434 16258 8438 16259 8434 16259 8456 16259 8452 16260 8456 16260 8454 16260 8440 16261 8438 16261 8456 16261 8450 16262 8456 16262 8452 16262 8448 16263 8440 16263 8456 16263 8448 16264 8456 16264 8450 16264 8448 16265 8442 16265 8440 16265 8446 16266 8442 16266 8448 16266 8596 16267 8600 16267 8598 16267 8446 16268 8444 16268 8442 16268 8596 16269 8612 16269 8604 16269 8596 16270 8604 16270 8600 16270 8518 16271 8490 16271 8520 16271 8594 16272 8618 16272 8616 16272 8516 16273 8490 16273 8518 16273 8594 16274 8616 16274 8614 16274 8594 16275 8614 16275 8612 16275 8594 16276 1425 16276 8618 16276 8594 16277 8612 16277 8596 16277 8514 16278 8490 16278 8516 16278 8512 16279 8490 16279 8514 16279 8510 16280 8490 16280 8512 16280 8592 16281 1423 16281 1425 16281 8592 16282 1425 16282 8594 16282 8508 16283 8490 16283 8510 16283 8590 16284 1421 16284 1423 16284 8506 16285 8490 16285 8508 16285 8590 16286 1423 16286 8592 16286 8588 16287 1418 16287 1421 16287 8504 16288 8490 16288 8506 16288 8504 16289 8492 16289 8490 16289 8502 16290 8492 16290 8504 16290 8588 16291 1421 16291 8590 16291 8586 16292 1417 16292 1418 16292 8498 16293 8496 16293 8494 16293 8498 16294 8494 16294 8492 16294 8586 16295 1418 16295 8588 16295 8500 16296 8492 16296 8502 16296 8500 16297 8498 16297 8492 16297 8584 16298 1417 16298 8586 16298 8582 16299 8662 16299 8660 16299 8582 16300 1415 16300 1417 16300 8582 16301 8660 16301 1415 16301 8582 16302 1417 16302 8584 16302 8580 16303 8662 16303 8582 16303 8578 16304 8290 16304 8662 16304 8578 16305 8662 16305 8580 16305 8576 16306 8290 16306 8578 16306 8574 16307 8290 16307 8576 16307 8574 16308 8289 16308 8290 16308 8572 16309 8289 16309 8574 16309 8366 16310 8364 16310 8362 16310 8366 16311 8362 16311 8360 16311 8366 16312 8360 16312 8358 16312 8366 16313 8358 16313 8356 16313 7032 16314 7994 16314 7992 16314 7438 16315 7310 16315 7324 16315 7438 16316 7324 16316 7322 16316 7032 16317 7035 16317 7994 16317 7438 16318 7322 16318 7440 16318 7422 16319 7450 16319 7244 16319 7726 16320 7651 16320 7728 16320 7726 16321 7647 16321 7651 16321 6860 16322 1045 16322 1043 16322 968 16323 1034 16323 1030 16323 968 16324 1038 16324 1034 16324 6572 16325 6551 16325 1490 16325 7464 16326 7310 16326 7438 16326 968 16327 1041 16327 1038 16327 7464 16328 7312 16328 7310 16328 968 16329 1043 16329 1041 16329 7464 16330 7314 16330 7312 16330 7668 16331 7666 16331 7671 16331 968 16332 6860 16332 1043 16332 7668 16333 7671 16333 7674 16333 1524 16334 7811 16334 7810 16334 1524 16335 7814 16335 7811 16335 1524 16336 7816 16336 7814 16336 6525 16337 6526 16337 6524 16337 1524 16338 7818 16338 7816 16338 1524 16339 7820 16339 7818 16339 7724 16340 7647 16340 7726 16340 6493 16341 6525 16341 6524 16341 6494 16342 6493 16342 6524 16342 7724 16343 7645 16343 7647 16343 6983 16344 7882 16344 7060 16344 6983 16345 7884 16345 7882 16345 6454 16346 6494 16346 6524 16346 7670 16347 7674 16347 7676 16347 7462 16348 7314 16348 7464 16348 7038 16349 7040 16349 7041 16349 7670 16350 7668 16350 7674 16350 7462 16351 7292 16351 7290 16351 1440 16352 7557 16352 7643 16352 7462 16353 7290 16353 7314 16353 1523 16354 1524 16354 7810 16354 8014 16355 968 16355 8016 16355 1523 16356 7810 16356 7828 16356 1440 16357 1445 16357 7557 16357 1508 16358 1511 16358 7279 16358 1440 16359 7643 16359 7645 16359 1508 16360 7279 16360 7282 16360 1508 16361 7282 16361 7284 16361 1526 16362 6524 16362 6824 16362 1526 16363 7820 16363 1524 16363 1452 16364 1506 16364 1446 16364 1526 16365 7822 16365 7820 16365 1526 16366 7824 16366 7822 16366 1526 16367 7826 16367 7824 16367 1452 16368 1500 16368 1506 16368 1526 16369 6824 16369 7826 16369 1526 16370 6394 16370 6524 16370 7658 16371 7676 16371 7678 16371 7029 16372 7032 16372 7992 16372 8012 16373 968 16373 8014 16373 7658 16374 7670 16374 7676 16374 7460 16375 7292 16375 7462 16375 6394 16376 6454 16376 6524 16376 7460 16377 7294 16377 7292 16377 7722 16378 7645 16378 7724 16378 8009 16379 968 16379 8012 16379 7660 16380 7678 16380 7680 16380 7660 16381 7658 16381 7678 16381 6563 16382 6572 16382 1490 16382 7458 16383 7296 16383 7294 16383 7458 16384 7298 16384 7296 16384 8008 16385 968 16385 8009 16385 1520 16386 1523 16386 7828 16386 7458 16387 7294 16387 7460 16387 1520 16388 7840 16388 7838 16388 7970 16389 968 16389 8008 16389 1520 16390 7828 16390 7840 16390 7662 16391 7660 16391 7680 16391 7968 16392 968 16392 7970 16392 1444 16393 1440 16393 7645 16393 1444 16394 7722 16394 7719 16394 1444 16395 7645 16395 7722 16395 1529 16396 6394 16396 1526 16396 7966 16397 968 16397 7968 16397 7456 16398 7300 16398 7298 16398 7966 16399 6860 16399 968 16399 7456 16400 7302 16400 7300 16400 7456 16401 7298 16401 7458 16401 7019 16402 7018 16402 7021 16402 7019 16403 7021 16403 7024 16403 6980 16404 7886 16404 7884 16404 6980 16405 7884 16405 6983 16405 7593 16406 7423 16406 7422 16406 846 16407 7664 16407 7662 16407 7593 16408 7426 16408 7423 16408 846 16409 7680 16409 7682 16409 7593 16410 7428 16410 7426 16410 6980 16411 7858 16411 7856 16411 846 16412 7682 16412 7692 16412 7593 16413 7430 16413 7428 16413 6980 16414 7860 16414 7858 16414 6980 16415 7842 16415 7860 16415 846 16416 1018 16416 1015 16416 6980 16417 7856 16417 7886 16417 846 16418 7662 16418 7680 16418 7595 16419 7430 16419 7593 16419 6963 16420 7842 16420 6980 16420 1457 16421 1496 16421 1500 16421 1457 16422 1500 16422 1452 16422 7604 16423 7595 16423 7606 16423 1011 16424 846 16424 1015 16424 6978 16425 6963 16425 6980 16425 6549 16426 6563 16426 1490 16426 7602 16427 7595 16427 7604 16427 6971 16428 6965 16428 6963 16428 6971 16429 6963 16429 6978 16429 6987 16430 7842 16430 6963 16430 7599 16431 7595 16431 7602 16431 7599 16432 7432 16432 7430 16432 7599 16433 7430 16433 7595 16433 6987 16434 7830 16434 7842 16434 7132 16435 7028 16435 7026 16435 7132 16436 7024 16436 7028 16436 7134 16437 7132 16437 7026 16437 7134 16438 7026 16438 7029 16438 6531 16439 6549 16439 1490 16439 6531 16440 1490 16440 1494 16440 6531 16441 1494 16441 1502 16441 7130 16442 7024 16442 7132 16442 6531 16443 1502 16443 1503 16443 7136 16444 7134 16444 7029 16444 1006 16445 846 16445 1011 16445 1489 16446 7719 16446 7718 16446 1489 16447 1444 16447 7719 16447 7930 16448 7954 16448 7932 16448 1489 16449 7748 16449 7746 16449 1489 16450 7718 16450 7748 16450 1518 16451 1520 16451 7838 16451 1518 16452 7831 16452 7830 16452 1518 16453 7834 16453 7831 16453 1518 16454 7836 16454 7834 16454 1518 16455 7838 16455 7836 16455 7934 16456 7932 16456 7954 16456 1460 16457 1496 16457 1457 16457 1518 16458 7830 16458 6987 16458 7128 16459 7024 16459 7130 16459 1460 16460 1507 16460 1496 16460 7128 16461 7011 16461 7010 16461 7128 16462 7010 16462 7019 16462 7128 16463 7019 16463 7024 16463 1001 16464 846 16464 1006 16464 7928 16465 7954 16465 7930 16465 7936 16466 7934 16466 7954 16466 1486 16467 1489 16467 7746 16467 7138 16468 7136 16468 7029 16468 7138 16469 7029 16469 7992 16469 1486 16470 7744 16470 7742 16470 1530 16471 6394 16471 1529 16471 7926 16472 7954 16472 7928 16472 1486 16473 7746 16473 7744 16473 7576 16474 7580 16474 7577 16474 7576 16475 7582 16475 7580 16475 7576 16476 7584 16476 7582 16476 7576 16477 7586 16477 7584 16477 7576 16478 7588 16478 7586 16478 1463 16479 1507 16479 1460 16479 1463 16480 1503 16480 1507 16480 1484 16481 1486 16481 7742 16481 7938 16482 7936 16482 7954 16482 1484 16483 7740 16483 7738 16483 1484 16484 7742 16484 7740 16484 7920 16485 7938 16485 7954 16485 7126 16486 7014 16486 7011 16486 6921 16487 7664 16487 846 16487 7126 16488 7011 16488 7128 16488 6921 16489 846 16489 1001 16489 7590 16490 7588 16490 7576 16490 6921 16491 1001 16491 997 16491 7110 16492 7992 16492 7989 16492 7110 16493 7138 16493 7992 16493 7923 16494 7954 16494 7926 16494 6921 16495 7734 16495 7664 16495 7922 16496 7954 16496 7923 16496 7922 16497 7955 16497 7954 16497 7972 16498 7920 16498 7954 16498 7152 16499 7014 16499 7126 16499 7152 16500 7016 16500 7014 16500 7598 16501 7434 16501 7432 16501 7152 16502 6998 16502 7016 16502 7598 16503 7436 16503 7434 16503 7598 16504 7467 16504 7466 16504 6948 16505 7735 16505 7734 16505 6948 16506 7738 16506 7735 16506 6948 16507 7734 16507 6921 16507 7598 16508 7466 16508 7436 16508 7598 16509 7432 16509 7599 16509 7553 16510 7470 16510 7467 16510 7553 16511 7472 16511 7470 16511 7544 16512 7553 16512 7467 16512 6719 16513 1484 16513 7738 16513 7872 16514 7960 16514 7958 16514 6719 16515 7738 16515 6948 16515 7150 16516 6999 16516 6998 16516 7150 16517 6998 16517 7152 16517 7874 16518 7872 16518 7958 16518 6733 16519 6719 16519 6718 16519 1516 16520 6987 16520 6990 16520 7548 16521 7545 16521 7544 16521 1516 16522 6990 16522 6992 16522 1516 16523 6992 16523 6995 16523 7876 16524 7955 16524 7922 16524 7876 16525 7874 16525 7958 16525 7876 16526 7958 16526 7955 16526 1516 16527 1518 16527 6987 16527 7870 16528 7962 16528 7960 16528 7621 16529 7576 16529 7591 16529 1532 16530 6394 16530 1530 16530 7623 16531 7576 16531 7621 16531 7623 16532 7590 16532 7576 16532 6783 16533 6719 16533 6733 16533 7870 16534 7960 16534 7872 16534 6782 16535 6719 16535 6783 16535 7878 16536 7876 16536 7922 16536 7878 16537 7922 16537 7940 16537 7148 16538 7002 16538 6999 16538 7868 16539 7962 16539 7870 16539 7148 16540 6999 16540 7150 16540 7868 16541 7964 16541 7962 16541 7630 16542 7623 16542 7632 16542 7868 16543 7966 16543 7964 16543 6666 16544 6719 16544 6782 16544 7627 16545 7623 16545 7630 16545 7627 16546 7590 16546 7623 16546 6662 16547 6719 16547 6666 16547 6662 16548 1484 16548 6719 16548 6662 16549 1476 16549 1479 16549 7550 16550 7548 16550 7544 16550 6662 16551 1479 16551 1481 16551 7146 16552 7004 16552 7002 16552 6662 16553 1481 16553 1483 16553 7146 16554 7006 16554 7004 16554 6662 16555 1483 16555 1484 16555 7146 16556 7002 16556 7148 16556 7865 16557 6824 16557 6860 16557 6532 16558 1503 16558 1463 16558 7865 16559 6860 16559 7966 16559 6532 16560 1463 16560 1464 16560 7865 16561 7966 16561 7868 16561 6532 16562 1464 16562 1466 16562 6532 16563 1466 16563 1468 16563 7552 16564 7544 16564 7467 16564 7880 16565 7878 16565 7940 16565 7880 16566 7940 16566 7952 16566 6532 16567 6531 16567 1503 16567 6627 16568 6532 16568 1468 16568 7552 16569 7467 16569 7598 16569 7552 16570 7550 16570 7544 16570 7252 16571 7111 16571 7110 16571 7252 16572 7114 16572 7111 16572 7252 16573 7116 16573 7114 16573 7555 16574 7474 16574 7472 16574 7555 16575 7476 16575 7474 16575 7253 16576 7116 16576 7252 16576 7864 16577 6824 16577 7865 16577 7253 16578 7118 16578 7116 16578 6622 16579 6627 16579 1468 16579 7555 16580 7472 16580 7553 16580 7862 16581 7880 16581 7952 16581 7264 16582 7253 16582 7266 16582 7862 16583 7952 16583 7950 16583 6597 16584 6622 16584 1468 16584 6636 16585 1468 16585 1470 16585 6636 16586 1470 16586 1472 16586 7262 16587 7253 16587 7264 16587 6636 16588 1472 16588 1474 16588 6636 16589 1474 16589 1476 16589 7948 16590 7862 16590 7950 16590 6636 16591 1476 16591 6662 16591 6598 16592 6597 16592 1468 16592 7260 16593 7253 16593 7262 16593 6635 16594 1468 16594 6636 16594 1515 16595 1516 16595 6995 16595 6635 16596 6598 16596 1468 16596 1515 16597 6995 16597 6994 16597 965 16598 968 16598 1030 16598 1515 16599 7008 16599 7006 16599 7946 16600 7862 16600 7948 16600 968 16601 846 16601 8026 16601 1515 16602 6994 16602 7008 16602 968 16603 8026 16603 8024 16603 968 16604 8024 16604 8022 16604 968 16605 8022 16605 8020 16605 968 16606 8020 16606 8018 16606 968 16607 8018 16607 8016 16607 8026 16608 846 16608 8006 16608 7614 16609 7611 16609 7610 16609 8006 16610 846 16610 7988 16610 7988 16611 846 16611 7989 16611 7989 16612 846 16612 7688 16612 7257 16613 7118 16613 7253 16613 7989 16614 7688 16614 7685 16614 7989 16615 7685 16615 7684 16615 7257 16616 7253 16616 7260 16616 7989 16617 7684 16617 7619 16617 7989 16618 7619 16618 7621 16618 7144 16619 7006 16619 7146 16619 7989 16620 7621 16620 7591 16620 7989 16621 7591 16621 7593 16621 7607 16622 7552 16622 7598 16622 7943 16623 7862 16623 7946 16623 7989 16624 7593 16624 7422 16624 7989 16625 7422 16625 7244 16625 7144 16626 1515 16626 7006 16626 7688 16627 846 16627 7690 16627 7690 16628 846 16628 7692 16628 6393 16629 6394 16629 1534 16629 846 16630 845 16630 1018 16630 6393 16631 1534 16631 1537 16631 7902 16632 7920 16632 7972 16632 6393 16633 1537 16633 1538 16633 7902 16634 7972 16634 7984 16634 6393 16635 1538 16635 1493 16635 7902 16636 7984 16636 7982 16636 6393 16637 1493 16637 1490 16637 7844 16638 7862 16638 7942 16638 7250 16639 7110 16639 7989 16639 7555 16640 7557 16640 1445 16640 7555 16641 1445 16641 1449 16641 7034 16642 7038 16642 7041 16642 7034 16643 7041 16643 7052 16643 7942 16644 7862 16644 7943 16644 7250 16645 7252 16645 7110 16645 7616 16646 7614 16646 7610 16646 7902 16647 7975 16647 7974 16647 7902 16648 7978 16648 7975 16648 7902 16649 7980 16649 7978 16649 7902 16650 7982 16650 7980 16650 1534 16651 6394 16651 1532 16651 7902 16652 7974 16652 7986 16652 7902 16653 7986 16653 8004 16653 7120 16654 7118 16654 7257 16654 7626 16655 7590 16655 7627 16655 7626 16656 7573 16656 7590 16656 7903 16657 8002 16657 8000 16657 7903 16658 8004 16658 8002 16658 7633 16659 7573 16659 7626 16659 7244 16660 7250 16660 7989 16660 7903 16661 7902 16661 8004 16661 6556 16662 6393 16662 1490 16662 7564 16663 7573 16663 7633 16663 7906 16664 7903 16664 8000 16664 7564 16665 7571 16665 7573 16665 7710 16666 7610 16666 7619 16666 7708 16667 7616 16667 7610 16667 7708 16668 7610 16668 7710 16668 7712 16669 7710 16669 7619 16669 7706 16670 7616 16670 7708 16670 7256 16671 7154 16671 7124 16671 7256 16672 7120 16672 7257 16672 7256 16673 7122 16673 7120 16673 7256 16674 7124 16674 7122 16674 1512 16675 7142 16675 7140 16675 1512 16676 7144 16676 7142 16676 7826 16677 6824 16677 7864 16677 7561 16678 7564 16678 7633 16678 1512 16679 1515 16679 7144 16679 7561 16680 7565 16680 7564 16680 7561 16681 7568 16681 7565 16681 7561 16682 7570 16682 7568 16682 7559 16683 7561 16683 7633 16683 7714 16684 7712 16684 7619 16684 7703 16685 7618 16685 7616 16685 7703 16686 7616 16686 7706 16686 7055 16687 7998 16687 7996 16687 7055 16688 8000 16688 7998 16688 7055 16689 7906 16689 8000 16689 7055 16690 7908 16690 7906 16690 1454 16691 7476 16691 7555 16691 7055 16692 7910 16692 7908 16692 7268 16693 7155 16693 7154 16693 7055 16694 7912 16694 7910 16694 1454 16695 7478 16695 7476 16695 1454 16696 7480 16696 7478 16696 7268 16697 7154 16697 7256 16697 7057 16698 7912 16698 7055 16698 7057 16699 7914 16699 7912 16699 7057 16700 7916 16700 7914 16700 7716 16701 7714 16701 7619 16701 1459 16702 7480 16702 1454 16702 1459 16703 7453 16703 7452 16703 1459 16704 7452 16704 7480 16704 7066 16705 7057 16705 7068 16705 7702 16706 7650 16706 7618 16706 7064 16707 7057 16707 7066 16707 7702 16708 7618 16708 7703 16708 7062 16709 7916 16709 7057 16709 7062 16710 7918 16710 7916 16710 7062 16711 7900 16711 7918 16711 7062 16712 7057 16712 7064 16712 7278 16713 7158 16713 7155 16713 7642 16714 7559 16714 7633 16714 7278 16715 7160 16715 7158 16715 7642 16716 7557 16716 7559 16716 7278 16717 7155 16717 7268 16717 7732 16718 7650 16718 7702 16718 1449 16719 1454 16719 7555 16719 1451 16720 7453 16720 1459 16720 1451 16721 1508 16721 7284 16721 1451 16722 7456 16722 7453 16722 1451 16723 7302 16723 7456 16723 1451 16724 7287 16724 7286 16724 1451 16725 7284 16725 7287 16725 1451 16726 7286 16726 7302 16726 7730 16727 7650 16727 7732 16727 7053 16728 7996 16728 7994 16728 7053 16729 7055 16729 7996 16729 6551 16730 6556 16730 1490 16730 7640 16731 7557 16731 7642 16731 7270 16732 7162 16732 7160 16732 7636 16733 7557 16733 7640 16733 7270 16734 7160 16734 7278 16734 7637 16735 7636 16735 7640 16735 7270 16736 7276 16736 7274 16736 7270 16737 7278 16737 7276 16737 7271 16738 7270 16738 7274 16738 7643 16739 7557 16739 7636 16739 7694 16740 7696 16740 7698 16740 7044 16741 7048 16741 7045 16741 7694 16742 7698 16742 7700 16742 7694 16743 7700 16743 7716 16743 7279 16744 7164 16744 7162 16744 7279 16745 7166 16745 7164 16745 7050 16746 7048 16746 7044 16746 7279 16747 7162 16747 7270 16747 7728 16748 7650 16748 7730 16748 7844 16749 7898 16749 7896 16749 7306 16750 7304 16750 7315 16750 7844 16751 7942 16751 7898 16751 7306 16752 7315 16752 7328 16752 7444 16753 7236 16753 7233 16753 7444 16754 7238 16754 7236 16754 7845 16755 7896 16755 7894 16755 7845 16756 7844 16756 7896 16756 7848 16757 7894 16757 7892 16757 7446 16758 7233 16758 7232 16758 7848 16759 7845 16759 7894 16759 7684 16760 7694 16760 7716 16760 7446 16761 7444 16761 7233 16761 7052 16762 7050 16762 7044 16762 7684 16763 7716 16763 7619 16763 1511 16764 1512 16764 7140 16764 1511 16765 7168 16765 7166 16765 1511 16766 7140 16766 7168 16766 1511 16767 7166 16767 7279 16767 7850 16768 7892 16768 7890 16768 7442 16769 7238 16769 7444 16769 7442 16770 7240 16770 7238 16770 7442 16771 7242 16771 7240 16771 7850 16772 7848 16772 7892 16772 7852 16773 7850 16773 7890 16773 7442 16774 7318 16774 7242 16774 7852 16775 7890 16775 7888 16775 7308 16776 7306 16776 7328 16776 7308 16777 7328 16777 7326 16777 7854 16778 7888 16778 7886 16778 7448 16779 7248 16779 7246 16779 7448 16780 7232 16780 7248 16780 7448 16781 7446 16781 7232 16781 7854 16782 7852 16782 7888 16782 1446 16783 1506 16783 1508 16783 1446 16784 1508 16784 1451 16784 7856 16785 7854 16785 7886 16785 7651 16786 7650 16786 7728 16786 7440 16787 7318 16787 7442 16787 7440 16788 7320 16788 7318 16788 7440 16789 7322 16789 7320 16789 7060 16790 7882 16790 7900 16790 7060 16791 7900 16791 7062 16791 7647 16792 7654 16792 7651 16792 7647 16793 7656 16793 7654 16793 7310 16794 7308 16794 7326 16794 7034 16795 7052 16795 7044 16795 7310 16796 7326 16796 7324 16796 7450 16797 7448 16797 7246 16797 7450 16798 7246 16798 7244 16798 7034 16799 7044 16799 7053 16799 7035 16800 7034 16800 7053 16800 7035 16801 7053 16801 7994 16801 2853 16802 8659 16802 8661 16802 8509 16803 5512 16803 8507 16803 5481 16804 8551 16804 8553 16804 2853 16805 8661 16805 2740 16805 5570 16806 5481 16806 8553 16806 2740 16807 8661 16807 8288 16807 8507 16808 5512 16808 5514 16808 5570 16809 8553 16809 8555 16809 5481 16810 5484 16810 8549 16810 2740 16811 8288 16811 2738 16811 8551 16812 5481 16812 8549 16812 5570 16813 8555 16813 8557 16813 2738 16814 8288 16814 2734 16814 5569 16815 5570 16815 8557 16815 8379 16816 8381 16816 2854 16816 8381 16817 8383 16817 2854 16817 5484 16818 5485 16818 8547 16818 2854 16819 8383 16819 2856 16819 8549 16820 5484 16820 8547 16820 8383 16821 8385 16821 2856 16821 5569 16822 8557 16822 5517 16822 2735 16823 2734 16823 8287 16823 8379 16824 2854 16824 2743 16824 2734 16825 8288 16825 8287 16825 8547 16826 5485 16826 8545 16826 8375 16827 8377 16827 2743 16827 8377 16828 8379 16828 2743 16828 8507 16829 5514 16829 8505 16829 8545 16830 5485 16830 5487 16830 8419 16831 2816 16831 2818 16831 2735 16832 8287 16832 2860 16832 8545 16833 5487 16833 8543 16833 8375 16834 2743 16834 2742 16834 5487 16835 5489 16835 8541 16835 2860 16836 8287 16836 8291 16836 8543 16837 5487 16837 8541 16837 2860 16838 8291 16838 8293 16838 8541 16839 5489 16839 8539 16839 8331 16840 8333 16840 2773 16840 8539 16841 5489 16841 8537 16841 2775 16842 8331 16842 2773 16842 2860 16843 8293 16843 2862 16843 8375 16844 2742 16844 2746 16844 8537 16845 5489 16845 5491 16845 2862 16846 8293 16846 8295 16846 8373 16847 8375 16847 2746 16847 8537 16848 5491 16848 8535 16848 2862 16849 8295 16849 8297 16849 2773 16850 8333 16850 8335 16850 2856 16851 8385 16851 2858 16851 8505 16852 5514 16852 5479 16852 2862 16853 8297 16853 2753 16853 8385 16854 8387 16854 2858 16854 2858 16855 8387 16855 8389 16855 8373 16856 2746 16856 2748 16856 2753 16857 8297 16857 8299 16857 5526 16858 5528 16858 8607 16858 8505 16859 5479 16859 8503 16859 8535 16860 5491 16860 5493 16860 5526 16861 8607 16861 8609 16861 5525 16862 5526 16862 8609 16862 2773 16863 8335 16863 8337 16863 8503 16864 5479 16864 8501 16864 8607 16865 5528 16865 8605 16865 8373 16866 2748 16866 2866 16866 8371 16867 8373 16867 2866 16867 8605 16868 5528 16868 8603 16868 8419 16869 2818 16869 8417 16869 8501 16870 5479 16870 5478 16870 8501 16871 5478 16871 8499 16871 8603 16872 5528 16872 8601 16872 5528 16873 5530 16873 8601 16873 5525 16874 8609 16874 8611 16874 2837 16875 5525 16875 8611 16875 8371 16876 2866 16876 2864 16876 8369 16877 8371 16877 2864 16877 8499 16878 5478 16878 8497 16878 8601 16879 5530 16879 8599 16879 2858 16880 8389 16880 2799 16880 2837 16881 8611 16881 8613 16881 8389 16882 8391 16882 2799 16882 8497 16883 5478 16883 8495 16883 2837 16884 8613 16884 8615 16884 8599 16885 5530 16885 8597 16885 8369 16886 2864 16886 2794 16886 8535 16887 5493 16887 8533 16887 8367 16888 8369 16888 2794 16888 8597 16889 5530 16889 5522 16889 8495 16890 5478 16890 5565 16890 8417 16891 2818 16891 2819 16891 8493 16892 8495 16892 5565 16892 8493 16893 5565 16893 8491 16893 8415 16894 8417 16894 2819 16894 2773 16895 8337 16895 2771 16895 8597 16896 5522 16896 8595 16896 8337 16897 8339 16897 2771 16897 8595 16898 5522 16898 8593 16898 8415 16899 2819 16899 8413 16899 8491 16900 5565 16900 5566 16900 2837 16901 8615 16901 8617 16901 8413 16902 2819 16902 8411 16902 8533 16903 5493 16903 5495 16903 2837 16904 8617 16904 2835 16904 2799 16905 8391 16905 2798 16905 8533 16906 5495 16906 8531 16906 8391 16907 8393 16907 2798 16907 2771 16908 8339 16908 8341 16908 8491 16909 5566 16909 5477 16909 2753 16910 8299 16910 2752 16910 2798 16911 8393 16911 8395 16911 5517 16912 8557 16912 8559 16912 2752 16913 8299 16913 8301 16913 2870 16914 2752 16914 8301 16914 2870 16915 8301 16915 2869 16915 5518 16916 5517 16916 8559 16916 8411 16917 2819 16917 2800 16917 2869 16918 8301 16918 8303 16918 8407 16919 8409 16919 2800 16919 5518 16920 8559 16920 8561 16920 8409 16921 8411 16921 2800 16921 2798 16922 8395 16922 2808 16922 2869 16923 8303 16923 8305 16923 8395 16924 8397 16924 2808 16924 8593 16925 5522 16925 8591 16925 8305 16926 8307 16926 2754 16926 2869 16927 8305 16927 2754 16927 5522 16928 5521 16928 8591 16928 5518 16929 8561 16929 8563 16929 2771 16930 8341 16930 2769 16930 2754 16931 8307 16931 8309 16931 5560 16932 5518 16932 8563 16932 2835 16933 8617 16933 8619 16933 8403 16934 8405 16934 2803 16934 8405 16935 8407 16935 2803 16935 8407 16936 2800 16936 2803 16936 8491 16937 5477 16937 8489 16937 8397 16938 8399 16938 2806 16938 8399 16939 8401 16939 2806 16939 2808 16940 8397 16940 2806 16940 5560 16941 8563 16941 8565 16941 8403 16942 2803 16942 2804 16942 2806 16943 8401 16943 2804 16943 8401 16944 8403 16944 2804 16944 8489 16945 5477 16945 5475 16945 5560 16946 8565 16946 8567 16946 5562 16947 5560 16947 8567 16947 2769 16948 8341 16948 8343 16948 2769 16949 8343 16949 2767 16949 2754 16950 8309 16950 2755 16950 8591 16951 5521 16951 8589 16951 8589 16952 5521 16952 5554 16952 2767 16953 8343 16953 8345 16953 8531 16954 5495 16954 8529 16954 8489 16955 5475 16955 8487 16955 2767 16956 8345 16956 2765 16956 5562 16957 8567 16957 8569 16957 8345 16958 8347 16958 2765 16958 8487 16959 5475 16959 5558 16959 8529 16960 5495 16960 5497 16960 2765 16961 8347 16961 2763 16961 5562 16962 8569 16962 8571 16962 8347 16963 8349 16963 2763 16963 8487 16964 5558 16964 8485 16964 5470 16965 5472 16965 8571 16965 5472 16966 5562 16966 8571 16966 2763 16967 8349 16967 8351 16967 2835 16968 8619 16968 2833 16968 8619 16969 8621 16969 2833 16969 8367 16970 2794 16970 2795 16970 8483 16971 8485 16971 5556 16971 8485 16972 5558 16972 5556 16972 2763 16973 8351 16973 2761 16973 8351 16974 8353 16974 2761 16974 2755 16975 8309 16975 8311 16975 8589 16976 5554 16976 8587 16976 8367 16977 2795 16977 8365 16977 8483 16978 5556 16978 8481 16978 5470 16979 8571 16979 8573 16979 5469 16980 5470 16980 8573 16980 8365 16981 2795 16981 2873 16981 8481 16982 5556 16982 5458 16982 5469 16983 8573 16983 8575 16983 2761 16984 8353 16984 2760 16984 5466 16985 5469 16985 8575 16985 8481 16986 5458 16986 5461 16986 8353 16987 8355 16987 2760 16987 8355 16988 8357 16988 2760 16988 8587 16989 5554 16989 8585 16989 5554 16990 5552 16990 8585 16990 5466 16991 8575 16991 8577 16991 5550 16992 5466 16992 8577 16992 2755 16993 8311 16993 2790 16993 8585 16994 5552 16994 8583 16994 8365 16995 2873 16995 2874 16995 5552 16996 5550 16996 8583 16996 5461 16997 5462 16997 8479 16997 8361 16998 8363 16998 2874 16998 8363 16999 8365 16999 2874 16999 5550 17000 8577 17000 8579 17000 2760 17001 8357 17001 2757 17001 8361 17002 2874 17002 2757 17002 8357 17003 8359 17003 2757 17003 8583 17004 5550 17004 8581 17004 8359 17005 8361 17005 2757 17005 8481 17006 5461 17006 8479 17006 5550 17007 8579 17007 8581 17007 8479 17008 5462 17008 5464 17008 2833 17009 8621 17009 8623 17009 8529 17010 5497 17010 8527 17010 8479 17011 5464 17011 8477 17011 2790 17012 8311 17012 8313 17012 8527 17013 5497 17013 5499 17013 8477 17014 5464 17014 8475 17014 2833 17015 8623 17015 2831 17015 8475 17016 5464 17016 5548 17016 8475 17017 5548 17017 8473 17017 2831 17018 8623 17018 8625 17018 8473 17019 5548 17019 8471 17019 8469 17020 8471 17020 5546 17020 8471 17021 5548 17021 5546 17021 8527 17022 5499 17022 8525 17022 2831 17023 8625 17023 8627 17023 2790 17024 8313 17024 2788 17024 2831 17025 8627 17025 2829 17025 8525 17026 5499 17026 5501 17026 2788 17027 8313 17027 8315 17027 8469 17028 5546 17028 8467 17028 8465 17029 8467 17029 5544 17029 8525 17030 5501 17030 8523 17030 8467 17031 5546 17031 5544 17031 8465 17032 5544 17032 8463 17032 2829 17033 8627 17033 8629 17033 8463 17034 5544 17034 8461 17034 2829 17035 8629 17035 2826 17035 8461 17036 5544 17036 5533 17036 8461 17037 5533 17037 8459 17037 8523 17038 5501 17038 5503 17038 8459 17039 5533 17039 8457 17039 8523 17040 5503 17040 8521 17040 2788 17041 8315 17041 8317 17041 2826 17042 8629 17042 8631 17042 8521 17043 5503 17043 8519 17043 2788 17044 8317 17044 2785 17044 8457 17045 5533 17045 5535 17045 2826 17046 8631 17046 2827 17046 8457 17047 5535 17047 8455 17047 2785 17048 8317 17048 8319 17048 2827 17049 8631 17049 8633 17049 8519 17050 5503 17050 5505 17050 8455 17051 5535 17051 8453 17051 8453 17052 5535 17052 5537 17052 2827 17053 8633 17053 8635 17053 2827 17054 8635 17054 2846 17054 8453 17055 5537 17055 8451 17055 2846 17056 8635 17056 8637 17056 2846 17057 8637 17057 2844 17057 2785 17058 8319 17058 2783 17058 8451 17059 5537 17059 5538 17059 8519 17060 5505 17060 8517 17060 8451 17061 5538 17061 8449 17061 8449 17062 5538 17062 8447 17062 2844 17063 8637 17063 8639 17063 2783 17064 8319 17064 8321 17064 8445 17065 8447 17065 5540 17065 8639 17066 8641 17066 2842 17066 2844 17067 8639 17067 2842 17067 8447 17068 5538 17068 5540 17068 8445 17069 5540 17069 8443 17069 8517 17070 5505 17070 5507 17070 2842 17071 8641 17071 8643 17071 8441 17072 8443 17072 5542 17072 8443 17073 5540 17073 5542 17073 8441 17074 5542 17074 8439 17074 2842 17075 8643 17075 2841 17075 8439 17076 5542 17076 8437 17076 2841 17077 8643 17077 8645 17077 2783 17078 8321 17078 2781 17078 8517 17079 5507 17079 8515 17079 8435 17080 8437 17080 2811 17080 8437 17081 5542 17081 2811 17081 8645 17082 8647 17082 2825 17082 2841 17083 8645 17083 2825 17083 2781 17084 8321 17084 8323 17084 8515 17085 5507 17085 8513 17085 8435 17086 2811 17086 8433 17086 8513 17087 5507 17087 5509 17087 8513 17088 5509 17088 8511 17088 8323 17089 8325 17089 2779 17089 2781 17090 8323 17090 2779 17090 8431 17091 8433 17091 2810 17091 2825 17092 8647 17092 8649 17092 8433 17093 2811 17093 2810 17093 8431 17094 2810 17094 8429 17094 2825 17095 8649 17095 2823 17095 8429 17096 2810 17096 8427 17096 2823 17097 8649 17097 8651 17097 2779 17098 8325 17098 8327 17098 2779 17099 8327 17099 2777 17099 2823 17100 8651 17100 2849 17100 8427 17101 2810 17101 2813 17101 2849 17102 8651 17102 8653 17102 8427 17103 2813 17103 8425 17103 2849 17104 8653 17104 8655 17104 8425 17105 2813 17105 8423 17105 2777 17106 8327 17106 8329 17106 8509 17107 8511 17107 5512 17107 2777 17108 8329 17108 2775 17108 8511 17109 5509 17109 5512 17109 8423 17110 2813 17110 2816 17110 8421 17111 8423 17111 2816 17111 2849 17112 8655 17112 2851 17112 2851 17113 8655 17113 8657 17113 2775 17114 8329 17114 8331 17114 8421 17115 2816 17115 8419 17115 8657 17116 8659 17116 2853 17116 2851 17117 8657 17117 2853 17117 534 17118 542 17118 536 17118 550 17119 546 17119 542 17119 539 17120 538 17120 550 17120 578 17121 533 17121 531 17121 576 17122 534 17122 533 17122 576 17123 542 17123 534 17123 576 17124 539 17124 550 17124 576 17125 550 17125 542 17125 576 17126 533 17126 578 17126 548 17127 544 17127 539 17127 572 17128 576 17128 574 17128 554 17129 552 17129 548 17129 570 17130 548 17130 539 17130 570 17131 539 17131 576 17131 570 17132 576 17132 572 17132 568 17133 548 17133 570 17133 558 17134 556 17134 554 17134 558 17135 554 17135 548 17135 562 17136 560 17136 558 17136 562 17137 566 17137 564 17137 562 17138 568 17138 566 17138 562 17139 558 17139 548 17139 562 17140 548 17140 568 17140 526 17141 480 17141 528 17141 487 17142 481 17142 480 17142 485 17143 484 17143 487 17143 485 17144 487 17144 480 17144 520 17145 524 17145 522 17145 520 17146 526 17146 524 17146 489 17147 485 17147 480 17147 496 17148 492 17148 489 17148 496 17149 494 17149 492 17149 496 17150 489 17150 480 17150 500 17151 498 17151 496 17151 500 17152 480 17152 526 17152 500 17153 496 17153 480 17153 504 17154 502 17154 500 17154 504 17155 508 17155 506 17155 504 17156 510 17156 508 17156 504 17157 512 17157 510 17157 504 17158 514 17158 512 17158 504 17159 516 17159 514 17159 504 17160 518 17160 516 17160 504 17161 520 17161 518 17161 504 17162 526 17162 520 17162 504 17163 500 17163 526 17163 408 17164 386 17164 384 17164 408 17165 388 17165 386 17165 408 17166 390 17166 388 17166 408 17167 392 17167 390 17167 408 17168 384 17168 8663 17168 409 17169 8664 17169 8665 17169 409 17170 8666 17170 8664 17170 409 17171 8667 17171 8666 17171 409 17172 8663 17172 8667 17172 409 17173 408 17173 8663 17173 410 17174 8665 17174 381 17174 410 17175 381 17175 380 17175 410 17176 409 17176 8665 17176 378 17177 410 17177 380 17177 376 17178 410 17178 378 17178 374 17179 410 17179 376 17179 408 17180 394 17180 392 17180 372 17181 410 17181 374 17181 439 17182 8668 17182 8669 17182 439 17183 8670 17183 8668 17183 439 17184 8671 17184 8670 17184 8672 17185 439 17185 8669 17185 8673 17186 439 17186 8672 17186 441 17187 8673 17187 8674 17187 441 17188 439 17188 8673 17188 8675 17189 441 17189 8674 17189 8676 17190 441 17190 8675 17190 8677 17191 441 17191 8676 17191 474 17192 441 17192 8677 17192 403 17193 474 17193 8677 17193 402 17194 474 17194 403 17194 400 17195 474 17195 402 17195 398 17196 474 17196 400 17196 396 17197 474 17197 398 17197 439 17198 460 17198 8671 17198 394 17199 474 17199 396 17199 418 17200 8678 17200 8679 17200 418 17201 8680 17201 8681 17201 418 17202 8682 17202 8680 17202 418 17203 8683 17203 8682 17203 418 17204 8679 17204 8683 17204 406 17205 8684 17205 8678 17205 406 17206 8685 17206 8684 17206 406 17207 8686 17207 8685 17207 406 17208 8687 17208 8686 17208 406 17209 8678 17209 418 17209 405 17210 364 17210 362 17210 405 17211 366 17211 364 17211 405 17212 368 17212 366 17212 405 17213 370 17213 368 17213 405 17214 362 17214 8687 17214 405 17215 8687 17215 406 17215 405 17216 372 17216 370 17216 475 17217 418 17217 8681 17217 8688 17218 457 17218 8689 17218 8690 17219 457 17219 8688 17219 8691 17220 457 17220 8690 17220 8692 17221 457 17221 8691 17221 8693 17222 432 17222 457 17222 8693 17223 457 17223 8692 17223 8694 17224 434 17224 8695 17224 8696 17225 8695 17225 434 17225 8697 17226 434 17226 8694 17226 8698 17227 8696 17227 434 17227 8699 17228 432 17228 8693 17228 8700 17229 434 17229 432 17229 8700 17230 8698 17230 434 17230 8701 17231 432 17231 8699 17231 8702 17232 8700 17232 432 17232 8702 17233 432 17233 8701 17233 457 17234 452 17234 8689 17234 460 17235 434 17235 8697 17235 466 17236 8703 17236 8704 17236 466 17237 8705 17237 8703 17237 466 17238 8706 17238 8705 17238 466 17239 8707 17239 8706 17239 8708 17240 8707 17240 466 17240 465 17241 8709 17241 8708 17241 465 17242 8710 17242 8709 17242 465 17243 8708 17243 466 17243 8711 17244 8710 17244 465 17244 8712 17245 8711 17245 465 17245 472 17246 8713 17246 8712 17246 472 17247 8712 17247 465 17247 8714 17248 8713 17248 472 17248 8715 17249 8714 17249 472 17249 8716 17250 8715 17250 472 17250 8717 17251 8716 17251 472 17251 472 17252 475 17252 8717 17252 459 17253 466 17253 8704 17253 451 17254 8718 17254 8719 17254 451 17255 8720 17255 8718 17255 8721 17256 8720 17256 451 17256 359 17257 8721 17257 451 17257 357 17258 451 17258 455 17258 357 17259 359 17259 451 17259 355 17260 357 17260 455 17260 353 17261 355 17261 455 17261 351 17262 353 17262 455 17262 349 17263 455 17263 454 17263 349 17264 351 17264 455 17264 346 17265 349 17265 454 17265 8722 17266 346 17266 454 17266 8723 17267 8722 17267 454 17267 8724 17268 8723 17268 454 17268 8725 17269 8724 17269 454 17269 454 17270 459 17270 8725 17270 452 17271 451 17271 8719 17271 8692 17272 8726 17272 8727 17272 8693 17273 8692 17273 8727 17273 8699 17274 8727 17274 8728 17274 8699 17275 8693 17275 8727 17275 8701 17276 8728 17276 8729 17276 8701 17277 8699 17277 8728 17277 8702 17278 8729 17278 8730 17278 8702 17279 8701 17279 8729 17279 8700 17280 8730 17280 8731 17280 8700 17281 8702 17281 8730 17281 8698 17282 8731 17282 8732 17282 8698 17283 8700 17283 8731 17283 8733 17284 8672 17284 8669 17284 8734 17285 8733 17285 8669 17285 8735 17286 8734 17286 8668 17286 8734 17287 8669 17287 8668 17287 8736 17288 8735 17288 8670 17288 8735 17289 8668 17289 8670 17289 8737 17290 8736 17290 8671 17290 8736 17291 8670 17291 8671 17291 8738 17292 8737 17292 460 17292 8737 17293 8671 17293 460 17293 8739 17294 8738 17294 8697 17294 8738 17295 460 17295 8697 17295 8740 17296 8739 17296 8694 17296 8739 17297 8697 17297 8694 17297 8741 17298 8740 17298 8695 17298 8740 17299 8694 17299 8695 17299 8742 17300 8741 17300 8696 17300 8741 17301 8695 17301 8696 17301 8732 17302 8742 17302 8698 17302 8742 17303 8696 17303 8698 17303 8673 17304 8672 17304 8733 17304 8673 17305 8733 17305 8743 17305 8674 17306 8743 17306 8744 17306 8674 17307 8673 17307 8743 17307 8675 17308 8744 17308 8745 17308 8675 17309 8674 17309 8744 17309 8676 17310 8745 17310 8746 17310 8676 17311 8675 17311 8745 17311 8677 17312 8746 17312 8747 17312 8677 17313 8676 17313 8746 17313 403 17314 8747 17314 401 17314 403 17315 8677 17315 8747 17315 8663 17316 384 17316 383 17316 8663 17317 383 17317 8748 17317 8667 17318 8748 17318 8749 17318 8667 17319 8663 17319 8748 17319 8666 17320 8749 17320 8750 17320 8666 17321 8667 17321 8749 17321 8664 17322 8750 17322 8751 17322 8664 17323 8666 17323 8750 17323 8665 17324 8751 17324 8752 17324 8665 17325 8664 17325 8751 17325 381 17326 8752 17326 379 17326 381 17327 8665 17327 8752 17327 362 17328 361 17328 8753 17328 8687 17329 8753 17329 8754 17329 8687 17330 362 17330 8753 17330 8686 17331 8754 17331 8755 17331 8686 17332 8687 17332 8754 17332 8685 17333 8755 17333 8756 17333 8685 17334 8686 17334 8755 17334 8684 17335 8756 17335 8757 17335 8684 17336 8685 17336 8756 17336 8678 17337 8757 17337 8758 17337 8678 17338 8684 17338 8757 17338 8679 17339 8678 17339 8758 17339 8759 17340 8713 17340 8714 17340 8760 17341 8759 17341 8714 17341 8761 17342 8760 17342 8715 17342 8760 17343 8714 17343 8715 17343 8762 17344 8761 17344 8716 17344 8761 17345 8715 17345 8716 17345 8763 17346 8762 17346 8717 17346 8762 17347 8716 17347 8717 17347 8764 17348 8763 17348 475 17348 8763 17349 8717 17349 475 17349 8765 17350 8764 17350 8681 17350 8764 17351 475 17351 8681 17351 8766 17352 8765 17352 8680 17352 8765 17353 8681 17353 8680 17353 8767 17354 8766 17354 8682 17354 8766 17355 8680 17355 8682 17355 8768 17356 8767 17356 8683 17356 8767 17357 8682 17357 8683 17357 8758 17358 8768 17358 8679 17358 8768 17359 8683 17359 8679 17359 8712 17360 8713 17360 8759 17360 8712 17361 8769 17361 8770 17361 8712 17362 8759 17362 8769 17362 8711 17363 8770 17363 8771 17363 8711 17364 8712 17364 8770 17364 8710 17365 8771 17365 8772 17365 8710 17366 8711 17366 8771 17366 8709 17367 8772 17367 8773 17367 8709 17368 8710 17368 8772 17368 8708 17369 8773 17369 8774 17369 8708 17370 8709 17370 8773 17370 8707 17371 8708 17371 8774 17371 8775 17372 347 17372 346 17372 8775 17373 346 17373 8722 17373 8776 17374 8775 17374 8723 17374 8775 17375 8722 17375 8723 17375 8777 17376 8776 17376 8724 17376 8776 17377 8723 17377 8724 17377 8778 17378 8777 17378 8725 17378 8777 17379 8724 17379 8725 17379 8779 17380 8778 17380 459 17380 8778 17381 8725 17381 459 17381 8780 17382 8779 17382 8704 17382 8779 17383 459 17383 8704 17383 8781 17384 8780 17384 8703 17384 8780 17385 8704 17385 8703 17385 8782 17386 8781 17386 8705 17386 8781 17387 8703 17387 8705 17387 8783 17388 8782 17388 8706 17388 8782 17389 8705 17389 8706 17389 8774 17390 8783 17390 8707 17390 8783 17391 8706 17391 8707 17391 8726 17392 8692 17392 8691 17392 8784 17393 8726 17393 8691 17393 8785 17394 8784 17394 8690 17394 8784 17395 8691 17395 8690 17395 8786 17396 8785 17396 8688 17396 8785 17397 8690 17397 8688 17397 8787 17398 8786 17398 8689 17398 8786 17399 8688 17399 8689 17399 8788 17400 8787 17400 452 17400 8787 17401 8689 17401 452 17401 8789 17402 8788 17402 8719 17402 8788 17403 452 17403 8719 17403 8790 17404 8789 17404 8718 17404 8789 17405 8719 17405 8718 17405 8791 17406 8790 17406 8720 17406 8790 17407 8718 17407 8720 17407 8792 17408 8791 17408 8721 17408 8791 17409 8720 17409 8721 17409 358 17410 8792 17410 359 17410 8792 17411 8721 17411 359 17411 8735 17412 8736 17412 8737 17412 369 17413 361 17413 367 17413 8747 17414 8746 17414 8749 17414 8747 17415 8749 17415 8748 17415 8747 17416 8748 17416 383 17416 371 17417 361 17417 369 17417 8757 17418 8770 17418 8769 17418 8757 17419 8769 17419 8758 17419 373 17420 361 17420 371 17420 401 17421 8747 17421 383 17421 375 17422 361 17422 373 17422 8791 17423 8792 17423 358 17423 377 17424 361 17424 375 17424 385 17425 383 17425 382 17425 399 17426 401 17426 383 17426 8774 17427 8776 17427 8777 17427 8774 17428 8777 17428 8778 17428 8774 17429 8778 17429 8779 17429 379 17430 361 17430 377 17430 8774 17431 8779 17431 8780 17431 8790 17432 8791 17432 358 17432 8774 17433 8780 17433 8781 17433 379 17434 8753 17434 361 17434 8774 17435 8781 17435 8782 17435 387 17436 383 17436 385 17436 8774 17437 8782 17437 8783 17437 8789 17438 8790 17438 358 17438 8775 17439 8776 17439 8774 17439 397 17440 399 17440 383 17440 8756 17441 8771 17441 8770 17441 347 17442 8775 17442 8774 17442 389 17443 383 17443 387 17443 8756 17444 8770 17444 8757 17444 8752 17445 8753 17445 379 17445 395 17446 397 17446 383 17446 8788 17447 8789 17447 358 17447 391 17448 383 17448 389 17448 8751 17449 8753 17449 8752 17449 8751 17450 8754 17450 8753 17450 393 17451 395 17451 383 17451 8787 17452 8788 17452 358 17452 393 17453 383 17453 391 17453 8755 17454 352 17454 8771 17454 8755 17455 8771 17455 8756 17455 8786 17456 8787 17456 358 17456 8750 17457 8754 17457 8751 17457 8750 17458 8755 17458 8754 17458 8785 17459 8786 17459 358 17459 8784 17460 8785 17460 358 17460 348 17461 347 17461 8774 17461 8726 17462 8784 17462 358 17462 348 17463 8774 17463 8773 17463 8740 17464 8741 17464 8742 17464 8727 17465 358 17465 356 17465 8739 17466 8740 17466 8742 17466 8744 17467 8731 17467 8730 17467 8727 17468 8726 17468 358 17468 350 17469 348 17469 8773 17469 350 17470 8773 17470 8772 17470 8745 17471 8744 17471 8730 17471 8745 17472 8730 17472 8729 17472 8745 17473 8755 17473 8750 17473 8745 17474 352 17474 8755 17474 8745 17475 8729 17475 352 17475 8743 17476 8732 17476 8731 17476 8728 17477 356 17477 354 17477 8743 17478 8731 17478 8744 17478 8728 17479 8727 17479 356 17479 8746 17480 8745 17480 8750 17480 363 17481 361 17481 360 17481 8746 17482 8750 17482 8749 17482 352 17483 350 17483 8772 17483 352 17484 8772 17484 8771 17484 8733 17485 8732 17485 8743 17485 365 17486 361 17486 363 17486 8733 17487 8742 17487 8732 17487 8758 17488 8769 17488 8759 17488 8758 17489 8759 17489 8760 17489 8758 17490 8760 17490 8761 17490 8758 17491 8761 17491 8762 17491 8758 17492 8762 17492 8763 17492 8737 17493 8738 17493 8739 17493 8729 17494 354 17494 352 17494 8758 17495 8763 17495 8764 17495 8758 17496 8764 17496 8765 17496 8758 17497 8765 17497 8766 17497 8758 17498 8766 17498 8767 17498 8734 17499 8742 17499 8733 17499 8758 17500 8767 17500 8768 17500 8729 17501 8728 17501 354 17501 367 17502 361 17502 365 17502 8735 17503 8739 17503 8742 17503 8735 17504 8737 17504 8739 17504 8735 17505 8742 17505 8734 17505 113 17506 95 17506 103 17506 72 17507 87 17507 95 17507 123 17508 113 17508 120 17508 73 17509 72 17509 95 17509 129 17510 113 17510 123 17510 140 17511 73 17511 95 17511 136 17512 129 17512 132 17512 136 17513 95 17513 113 17513 136 17514 113 17514 129 17514 143 17515 136 17515 139 17515 106 17516 114 17516 122 17516 106 17517 122 17517 130 17517 106 17518 130 17518 140 17518 77 17519 140 17519 95 17519 77 17520 95 17520 136 17520 77 17521 136 17521 143 17521 77 17522 106 17522 140 17522 76 17523 106 17523 77 17523 93 17524 98 17524 106 17524 93 17525 106 17525 76 17525 82 17526 93 17526 76 17526 85 17527 89 17527 93 17527 85 17528 93 17528 82 17528 116 17529 109 17529 121 17529 109 17530 101 17530 92 17530 124 17531 121 17531 127 17531 109 17532 92 17532 84 17532 127 17533 121 17533 131 17533 109 17534 84 17534 80 17534 135 17535 131 17535 138 17535 121 17536 109 17536 138 17536 131 17537 121 17537 138 17537 141 17538 138 17538 145 17538 134 17539 126 17539 118 17539 144 17540 134 17540 118 17540 80 17541 144 17541 118 17541 109 17542 80 17542 78 17542 138 17543 109 17543 78 17543 145 17544 138 17544 78 17544 78 17545 80 17545 83 17545 118 17546 110 17546 102 17546 80 17547 118 17547 102 17547 83 17548 80 17548 102 17548 83 17549 102 17549 86 17549 102 17550 94 17550 90 17550 86 17551 102 17551 90 17551 32 17552 30 17552 34 17552 30 17553 25 17553 23 17553 36 17554 34 17554 38 17554 38 17555 34 17555 41 17555 23 17556 21 17556 16 17556 30 17557 23 17557 16 17557 48 17558 41 17558 55 17558 70 17559 66 17559 65 17559 15 17560 70 17560 65 17560 16 17561 15 17561 65 17561 63 17562 55 17562 28 17562 68 17563 63 17563 28 17563 34 17564 30 17564 28 17564 41 17565 34 17565 28 17565 30 17566 16 17566 28 17566 55 17567 41 17567 28 17567 16 17568 65 17568 28 17568 65 17569 60 17569 52 17569 28 17570 65 17570 52 17570 29 17571 28 17571 0 17571 52 17572 43 17572 40 17572 28 17573 52 17573 40 17573 0 17574 28 17574 40 17574 33 17575 26 17575 31 17575 22 17576 24 17576 26 17576 37 17577 33 17577 35 17577 39 17578 33 17578 37 17578 14 17579 20 17579 22 17579 14 17580 22 17580 26 17580 46 17581 39 17581 44 17581 54 17582 61 17582 69 17582 54 17583 69 17583 71 17583 54 17584 71 17584 14 17584 17 17585 46 17585 50 17585 17 17586 50 17586 57 17586 17 17587 26 17587 33 17587 17 17588 33 17588 39 17588 17 17589 14 17589 26 17589 17 17590 39 17590 46 17590 17 17591 54 17591 14 17591 10 17592 12 17592 54 17592 10 17593 54 17593 17 17593 3 17594 17 17594 19 17594 6 17595 8 17595 10 17595 6 17596 10 17596 17 17596 6 17597 17 17597 3 17597

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae new file mode 100644 index 0000000..e932242 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_finger.dae @@ -0,0 +1,98 @@ + + + 2016-07-17T22:24:25.381218 + 2016-07-17T22:24:25.381230 + Z_UP + + + + + + + + 0.007843 0.007843 0.007843 1 + + + 0.08 0.08 0.08 1 + + + 0.08 0.08 0.08 1 + + + 0.312500 + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.000000 + + + + + + 0 + + + + + + + + + + 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 3.25 1.431608e-13 -1.668798e-15 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 1.7 7.488409e-14 -8.729096e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -1.5 -6.60742e-14 7.702144e-16 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 2.191017e-13 -4.964106 -0.5980366 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -2.128613e-13 4.814562 -1.349073 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 -1.080877e-15 0.0002670802 -6 1.489651e-14 -0.3419783 -0.9397078 1.489651e-14 -0.3419783 -0.9397078 -1.489651e-14 0.3419783 0.9397078 -1.489651e-14 0.3419783 0.9397078 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.083198e-14 0.9284602 0.371432 -4.083198e-14 0.9284602 0.371432 1.801462e-16 -4.451336e-05 1 1.801462e-16 -4.451336e-05 1 4.404944e-14 -1 -4.451336e-05 4.404944e-14 -1 -4.451336e-05 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 -1.44117e-15 0.0003561069 -8 1.801462e-16 -4.451336e-05 1 1.801462e-16 -4.451336e-05 1 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -0.5 -2.202473e-14 2.567381e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 1 4.415709e-14 -1.652176e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -1 -4.415385e-14 2.074388e-16 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -4.404944e-14 1 4.451336e-05 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -2.12132 -9.442709e-05 2.12132 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 -5.404387e-16 0.0001335401 -3 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 2.474874 0.0001101649 -2.474874 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 1 4.404945e-14 -1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 -1 -4.404945e-14 1.781855e-16 + + + + + + + + + + -2.847997 -13.90268 34.44917 -2.369148 -13.90265 33.79009 -2.369148 -11.90265 33.79018 -1.741437 -11.90263 33.27089 -3.147895 -13.90278 36.82311 -3.25 -13.90275 36.01486 -3.25 -11.90275 36.01495 -3.147895 -13.90271 35.20662 -2.847997 -11.90268 34.44925 -2.847997 -13.90282 37.58056 -3.147895 -11.90278 36.8232 -3.147895 -11.90271 35.20671 -2.369148 -13.90285 38.23964 -2.847997 -11.90282 37.58065 -1.741437 -13.90287 38.75893 -2.369148 -11.90285 38.23973 -1.004305 -13.90289 39.1058 -1.741437 -11.90287 38.75902 -0.2040692 -13.90289 39.25845 -1.004305 -11.90289 39.10589 0.6089893 -13.90289 39.2073 -0.2040692 -11.90289 39.25854 1.383783 -13.90288 38.95555 0.6089893 -11.90289 39.20739 2.071628 -13.90286 38.51903 1.383783 -11.90288 38.95564 2.629305 -13.90283 37.92517 2.071628 -11.90286 38.51912 3.021774 -13.9028 37.21127 2.629305 -11.90283 37.92526 3.021774 -11.9028 37.21136 3.224373 -13.90277 36.4222 3.224373 -11.90277 36.42229 3.224373 -13.90273 35.60753 3.224373 -11.90273 35.60762 3.021774 -13.90269 34.81846 3.021774 -11.90269 34.81855 2.629305 -13.90266 34.10456 2.071628 -13.90264 33.5107 2.629305 -11.90266 34.10465 1.383783 -13.90262 33.07418 2.071628 -11.90264 33.51079 0.6089893 -13.90261 32.82243 1.383783 -11.90262 33.07427 -0.2040692 -13.9026 32.77128 0.6089893 -11.90261 32.82252 -1.004305 -13.90261 32.92393 -0.2040692 -11.9026 32.77137 -1.741437 -13.90263 33.2708 -1.004305 -11.90261 32.92402 -0.1067439 -18.90267 34.318 0.3185482 -18.90267 34.34475 -0.1067439 -13.90267 34.31822 0.3185482 -13.90267 34.34498 -0.5253289 -18.90268 34.39785 -0.5253289 -13.90268 34.39807 -0.9109056 -18.90268 34.57928 -0.9109056 -13.90268 34.57951 -1.646591 -18.90277 36.43742 -1.7 -18.90275 36.01464 -1.646591 -13.90277 36.43764 -1.7 -13.90275 36.01486 -1.239247 -18.9027 34.85091 -1.239247 -13.9027 34.85113 -1.489721 -18.90278 36.83362 -1.489721 -13.90278 36.83385 -1.489721 -18.90271 35.19566 -1.489721 -13.90271 35.19588 -1.239247 -18.9028 37.17837 -1.239247 -13.9028 37.1786 -1.646591 -18.90273 35.59187 -1.646591 -13.90273 35.59209 -0.9109056 -18.90281 37.45 -0.9109056 -13.90281 37.45022 -0.5253289 -18.90282 37.63144 -0.5253289 -13.90282 37.63166 -0.1067439 -18.90282 37.71129 -0.1067439 -13.90282 37.71151 0.3185482 -18.90282 37.68453 0.3185482 -13.90282 37.68475 0.7238248 -18.90282 37.55285 0.7238248 -13.90282 37.55307 1.083621 -18.90281 37.32451 1.083621 -13.90281 37.32474 1.375329 -18.90279 37.01388 1.375329 -13.90279 37.0141 1.58062 -18.90278 36.64045 1.58062 -13.90278 36.64068 1.686595 -13.90276 36.22793 1.686595 -18.90276 36.22771 1.686595 -13.90274 35.8018 1.686595 -18.90274 35.80158 1.58062 -13.90272 35.38905 1.58062 -18.90272 35.38883 1.375329 -18.9027 35.01541 1.375329 -13.9027 35.01563 1.083621 -18.90269 34.70477 1.083621 -13.90269 34.70499 0.7238248 -18.90268 34.47644 0.7238248 -13.90268 34.47666 -2.847997 -13.90197 18.44917 -2.369148 -13.90194 17.79009 -2.369148 -11.90194 17.79018 -1.741437 -11.90191 17.27089 -3.147895 -13.90207 20.82311 -3.25 -13.90204 20.01486 -3.25 -11.90204 20.01495 -3.147895 -13.902 19.20662 -2.847997 -11.90197 18.44925 -2.847997 -13.90211 21.58056 -3.147895 -11.90207 20.8232 -3.147895 -11.902 19.20671 -2.369148 -13.90213 22.23964 -2.847997 -11.90211 21.58065 -1.741437 -13.90216 22.75893 -2.369148 -11.90213 22.23973 -1.004305 -13.90217 23.1058 -1.741437 -11.90216 22.75902 -0.2040692 -13.90218 23.25845 -1.004305 -11.90217 23.10589 0.6089893 -13.90218 23.2073 -0.2040692 -11.90218 23.25854 1.383783 -13.90217 22.95555 0.6089893 -11.90218 23.20739 2.071628 -13.90215 22.51903 1.383783 -11.90217 22.95564 2.629305 -13.90212 21.92517 2.071628 -11.90215 22.51912 3.021774 -13.90209 21.21127 2.629305 -11.90212 21.92526 3.021774 -11.90209 21.21136 3.224373 -13.90205 20.4222 3.224373 -11.90205 20.42229 3.224373 -13.90202 19.60753 3.224373 -11.90202 19.60762 3.021774 -13.90198 18.81846 3.021774 -11.90198 18.81855 2.629305 -13.90195 18.10456 2.071628 -13.90192 17.5107 2.629305 -11.90195 18.10465 1.383783 -13.9019 17.07418 2.071628 -11.90192 17.51079 0.6089893 -13.90189 16.82243 1.383783 -11.9019 17.07427 -0.2040692 -13.90189 16.77128 0.6089893 -11.90189 16.82252 -1.004305 -13.9019 16.92393 -0.2040692 -11.90189 16.77137 -1.741437 -13.90191 17.2708 -1.004305 -11.9019 16.92402 -0.1067439 -18.90196 18.318 0.3185482 -18.90196 18.34475 -0.1067439 -13.90196 18.31822 0.3185482 -13.90196 18.34498 -0.5253289 -18.90196 18.39785 -0.5253289 -13.90196 18.39807 -0.9109056 -18.90197 18.57928 -0.9109056 -13.90197 18.57951 -1.646591 -18.90205 20.43742 -1.7 -18.90204 20.01464 -1.646591 -13.90205 20.43764 -1.7 -13.90204 20.01486 -1.239247 -18.90198 18.85091 -1.239247 -13.90198 18.85113 -1.489721 -18.90207 20.83362 -1.489721 -13.90207 20.83385 -1.489721 -18.902 19.19566 -1.489721 -13.902 19.19588 -1.239247 -18.90209 21.17837 -1.239247 -13.90209 21.1786 -1.646591 -18.90202 19.59187 -1.646591 -13.90202 19.59209 -0.9109056 -18.9021 21.45 -0.9109056 -13.9021 21.45022 -0.5253289 -18.90211 21.63144 -0.5253289 -13.90211 21.63166 -0.1067439 -18.90211 21.71129 -0.1067439 -13.90211 21.71151 0.3185482 -18.90211 21.68453 0.3185482 -13.90211 21.68475 0.7238248 -18.9021 21.55285 0.7238248 -13.9021 21.55307 1.083621 -18.90209 21.32451 1.083621 -13.90209 21.32474 1.375329 -18.90208 21.01388 1.375329 -13.90208 21.0141 1.58062 -18.90206 20.64045 1.58062 -13.90206 20.64068 1.686595 -13.90204 20.22793 1.686595 -18.90204 20.22771 1.686595 -13.90203 19.8018 1.686595 -18.90203 19.80158 1.58062 -13.90201 19.38905 1.58062 -18.90201 19.38883 1.375329 -18.90199 19.01541 1.375329 -13.90199 19.01563 1.083621 -18.90198 18.70477 1.083621 -13.90198 18.70499 0.7238248 -18.90197 18.47644 0.7238248 -13.90197 18.47666 0.8037402 -11.90234 26.74846 0.4635255 -18.90233 26.58806 0.8037402 -18.90234 26.74815 1.31446 -11.90236 27.29232 1.093453 -11.90235 26.98813 1.093453 -18.90235 26.98782 1.452875 -11.90241 28.38799 1.5 -11.90239 28.01495 1.5 -18.90239 28.01464 1.452875 -11.90237 27.64192 1.31446 -18.90236 27.29201 1.31446 -11.90242 28.73758 1.452875 -18.90241 28.38768 1.452875 -18.90237 27.64161 1.093453 -11.90244 29.04177 1.31446 -18.90242 28.73727 0.8037402 -11.90245 29.28145 1.093453 -18.90244 29.04146 0.4635255 -11.90246 29.44154 0.8037402 -18.90245 29.28113 0.09418578 -11.90246 29.51199 0.4635255 -18.90246 29.44123 -0.281072 -11.90246 29.48838 0.09418578 -18.90246 29.51168 -0.6386689 -11.90245 29.37219 -0.281072 -18.90246 29.48807 -0.956136 -11.90244 29.17072 -0.6386689 -18.90245 29.37188 -1.213525 -11.90243 28.89663 -0.956136 -18.90244 29.17041 -1.394665 -11.90242 28.56714 -1.213525 -18.90243 28.89632 -1.488172 -11.9024 28.20295 -1.394665 -18.90242 28.56683 -1.488172 -18.9024 28.20264 -1.488172 -11.90238 27.82695 -1.488172 -18.90238 27.82664 -1.394665 -11.90237 27.46277 -1.394665 -18.90237 27.46246 -1.213525 -11.90235 27.13328 -0.956136 -11.90234 26.85918 -1.213525 -18.90235 27.13296 -0.6386689 -11.90233 26.65771 -0.956136 -18.90234 26.85887 -0.281072 -11.90233 26.54152 -0.6386689 -18.90233 26.6574 0.09418578 -11.90232 26.51791 -0.281072 -18.90233 26.54121 0.4635255 -11.90233 26.58837 0.09418578 -18.90232 26.5176 -7 4.938625 -0.7810144 -7.5 4.814562 -1.349073 -7.5 4.938625 -0.7810144 -7 4.814562 -1.349073 -7 4.995902 -0.2023941 -7.5 4.995902 -0.2023941 -7 4.985618 0.3789632 -7.5 4.985618 0.3789632 -7 4.907912 0.9551957 -7.5 4.907912 0.9551957 -7.5 4.763835 1.518511 -7 4.763835 1.518511 -7 4.555335 2.061291 -7.5 4.555335 2.061291 -7.5 4.285233 2.576195 -7 4.285233 2.576195 -7 3.957179 3.056261 -7.5 3.957179 3.056261 -7.5 3.575612 3.494996 -7 3.575612 3.494996 -7.5 3.145691 3.886467 -7 3.145691 3.886467 -7.5 2.673229 4.225381 -7 2.673229 4.225381 -7 2.164617 4.507153 -7.5 2.164617 4.507153 -7.5 1.626732 4.727974 -7 1.626732 4.727974 -7.5 1.066849 4.884858 -7 1.066849 4.884858 -7.5 0.4925376 4.975682 -7 0.4925376 4.975682 -7 -0.08843417 4.999218 -7.5 -0.08843417 4.999218 -7 -0.66821 4.955148 -7.5 -0.66821 4.955148 -7 -1.238949 4.844069 -7.5 -1.238949 4.844069 -7.5 -1.792934 4.667482 -7 -1.792934 4.667482 -7.5 -2.322673 4.427775 -7 -2.322673 4.427775 -7.5 -2.821001 4.12819 -7 -2.821001 4.12819 -7.5 -3.28118 3.772779 -7 -3.28118 3.772779 -7.5 -3.696987 3.366347 -7 -3.696987 3.366347 -7 -4.062798 2.914391 -7.5 -4.062798 2.914391 -7.5 -4.373667 2.423023 -7 -4.373667 2.423023 -7.5 -4.625389 1.898887 -7 -4.625389 1.898887 -7.5 -4.814562 1.349073 -7 -4.814562 1.349073 -7.5 -4.938625 0.7810144 -7 -4.938625 0.7810144 -7.5 -4.995902 0.2023941 -7 -4.995902 0.2023941 -7.5 -4.985618 -0.3789632 -7 -4.985618 -0.3789632 -7.5 -4.907912 -0.9551957 -7 -4.907912 -0.9551957 -7.5 -4.763835 -1.518511 -7 -4.763835 -1.518511 -7.5 -4.555335 -2.061291 -7 -4.555335 -2.061291 -7.5 -4.285233 -2.576195 -7 -4.285233 -2.576195 -7.5 -3.957179 -3.056261 -7 -3.957179 -3.056261 -7.5 -3.575612 -3.494996 -7 -3.575612 -3.494996 -7.5 -3.145691 -3.886467 -7 -3.145691 -3.886467 -7.5 -2.673229 -4.225381 -7 -2.673229 -4.225381 -7 -2.164617 -4.507153 -7.5 -2.164617 -4.507153 -7 -1.626732 -4.727974 -7.5 -1.626732 -4.727974 -7.5 -1.066849 -4.884858 -7 -1.066849 -4.884858 -7.5 -0.4925376 -4.975682 -7 -0.4925376 -4.975682 -7 0.08843417 -4.999218 -7.5 0.08843417 -4.999218 -7.5 0.66821 -4.955148 -7 0.66821 -4.955148 -7 1.238949 -4.844069 -7.5 1.238949 -4.844069 -7.5 1.792934 -4.667482 -7 1.792934 -4.667482 -7 2.322673 -4.427775 -7.5 2.322673 -4.427775 -7 2.821001 -4.12819 -7.5 2.821001 -4.12819 -7.5 3.28118 -3.772779 -7 3.28118 -3.772779 -7 3.696987 -3.366347 -7.5 3.696987 -3.366347 -7.5 4.062798 -2.914391 -7 4.062798 -2.914391 -7 4.373667 -2.423023 -7.5 4.373667 -2.423023 -7.5 4.625389 -1.898887 -7 4.625389 -1.898887 7 -4.964106 -0.5980366 7.5 -4.964106 -0.5980366 7.5 -4.999969 -0.01769533 7 -4.999969 -0.01769533 7.5 -4.968215 0.5628853 7 -4.968215 0.5628853 7.5 -4.869275 1.135854 7 -4.869275 1.135854 7.5 -4.704486 1.693462 7 -4.704486 1.693462 7.5 -4.476077 2.228169 7 -4.476077 2.228169 7.5 -4.187137 2.732743 7 -4.187137 2.732743 7.5 -3.841573 3.200363 7 -3.841573 3.200363 7.5 -3.444058 3.624702 7 -3.444058 3.624702 7.5 -2.999968 4.000024 7 -2.999968 4.000024 7.5 -2.515309 4.321252 7 -2.515309 4.321252 7.5 -1.996635 4.584043 7 -1.996635 4.584043 7.5 -1.450959 4.784842 7 -1.450959 4.784842 7.5 -0.885662 4.920935 7 -0.885662 4.920935 7.5 -0.3083877 4.990481 7 -0.3083877 4.990481 7.5 0.2730569 4.992538 7 0.2730569 4.992538 7.5 0.850809 4.927081 7 0.850809 4.927081 7.5 1.417055 4.794993 7 1.417055 4.794993 7.5 1.964138 4.598061 7 1.964138 4.598061 7.5 2.48466 4.338948 7 2.48466 4.338948 7.5 2.97158 4.021158 7 2.97158 4.021158 7.5 3.418316 3.648989 7 3.418316 3.648989 7.5 3.818824 3.227473 7 3.818824 3.227473 7.5 4.167689 2.762312 7 4.167689 2.762312 7.5 4.460194 2.259795 7 4.460194 2.259795 7.5 4.692382 1.726718 7 4.692382 1.726718 7.5 4.861113 1.17029 7 4.861113 1.17029 7.5 4.964106 0.5980366 7 4.964106 0.5980366 7.5 4.999969 0.01769533 7 4.999969 0.01769533 7.5 4.968215 -0.5628853 7 4.968215 -0.5628853 7.5 4.869275 -1.135854 7 4.869275 -1.135854 7.5 4.704486 -1.693462 7 4.704486 -1.693462 7.5 4.476077 -2.228169 7 4.476077 -2.228169 7.5 4.187137 -2.732743 7 4.187137 -2.732743 7.5 3.841573 -3.200363 7 3.841573 -3.200363 7.5 3.444058 -3.624702 7 3.444058 -3.624702 7.5 2.999968 -4.000024 7 2.999968 -4.000024 7.5 2.515309 -4.321252 7 2.515309 -4.321252 7.5 1.996635 -4.584043 7 1.996635 -4.584043 7.5 1.450959 -4.784842 7 1.450959 -4.784842 7.5 0.885662 -4.920935 7 0.885662 -4.920935 7.5 0.3083877 -4.990481 7 0.3083877 -4.990481 7.5 -0.2730569 -4.992538 7 -0.2730569 -4.992538 7.5 -0.850809 -4.927081 7 -0.850809 -4.927081 7.5 -1.417055 -4.794993 7 -1.417055 -4.794993 7.5 -1.964138 -4.598061 7 -1.964138 -4.598061 7.5 -2.48466 -4.338948 7 -2.48466 -4.338948 7.5 -2.97158 -4.021158 7 -2.97158 -4.021158 7.5 -3.418316 -3.648989 7 -3.418316 -3.648989 7.5 -3.818824 -3.227473 7 -3.818824 -3.227473 7.5 -4.167689 -2.762312 7 -4.167689 -2.762312 7.5 -4.460194 -2.259795 7 -4.460194 -2.259795 7 -4.692382 -1.726718 7.5 -4.692382 -1.726718 7.5 -4.861113 -1.17029 7 -4.861113 -1.17029 7 -22.86554 5.91665 7.5 -22.86554 5.91665 7.5 -22.9014 6.496992 7 -22.9014 6.496992 7.5 -22.86965 7.077572 7 -22.86965 7.077572 7.5 -22.77071 7.650541 7 -22.77071 7.650541 7.5 -22.60592 8.208149 7 -22.60592 8.208149 7.5 -22.37751 8.742856 7 -22.37751 8.742856 7.5 -22.08857 9.24743 7 -22.08857 9.24743 7.5 -21.74301 9.715049 7 -21.74301 9.715049 7.5 -21.34549 10.13939 7 -21.34549 10.13939 7.5 -20.9014 10.51471 7 -20.9014 10.51471 7.5 -20.41674 10.83594 7 -20.41674 10.83594 7.5 -19.89807 11.09873 7 -19.89807 11.09873 7.5 -19.35239 11.29953 7 -19.35239 11.29953 7.5 -18.7871 11.43562 7 -18.7871 11.43562 7.5 -18.20982 11.50517 7 -18.20982 11.50517 7.5 -17.62838 11.50723 7 -17.62838 11.50723 7.5 -17.05063 11.44177 7 -17.05063 11.44177 7.5 -16.48438 11.30968 7 -16.48438 11.30968 7.5 -15.9373 11.11275 7 -15.9373 11.11275 7.5 -15.41677 10.85363 7 -15.41677 10.85363 7.5 -14.92985 10.53584 7 -14.92985 10.53584 7.5 -14.48312 10.16368 7 -14.48312 10.16368 7.5 -14.08261 9.74216 7 -14.08261 9.74216 7.5 -13.73375 9.276999 7 -13.73375 9.276999 7.5 -13.44124 8.774482 7 -13.44124 8.774482 7.5 -13.20905 8.241405 7 -13.20905 8.241405 7.5 -13.04032 7.684977 7 -13.04032 7.684977 7.5 -12.93733 7.112724 7 -12.93733 7.112724 7.5 -12.90147 6.532382 7 -12.90147 6.532382 7.5 -12.93322 5.951802 7 -12.93322 5.951802 7.5 -13.03216 5.378833 7 -13.03216 5.378833 7.5 -13.19695 4.821225 7 -13.19695 4.821225 7.5 -13.42536 4.286518 7 -13.42536 4.286518 7.5 -13.7143 3.781943 7 -13.7143 3.781943 7.5 -14.05986 3.314324 7 -14.05986 3.314324 7.5 -14.45738 2.889985 7 -14.45738 2.889985 7.5 -14.90147 2.514663 7 -14.90147 2.514663 7.5 -15.38613 2.193435 7 -15.38613 2.193435 7.5 -15.9048 1.930644 7 -15.9048 1.930644 7.5 -16.45048 1.729844 7 -16.45048 1.729844 7.5 -17.01577 1.593752 7 -17.01577 1.593752 7.5 -17.59305 1.524206 7 -17.59305 1.524206 7.5 -18.17449 1.522148 7 -18.17449 1.522148 7.5 -18.75224 1.587606 7 -18.75224 1.587606 7.5 -19.31849 1.719694 7 -19.31849 1.719694 7.5 -19.86557 1.916626 7 -19.86557 1.916626 7.5 -20.38609 2.175739 7 -20.38609 2.175739 7.5 -20.87301 2.493529 7 -20.87301 2.493529 7.5 -21.31975 2.865698 7 -21.31975 2.865698 7.5 -21.72026 3.287214 7 -21.72026 3.287214 7.5 -22.06912 3.752375 7 -22.06912 3.752375 7.5 -22.36163 4.254892 7 -22.36163 4.254892 7.5 -22.59382 4.787969 7 -22.59382 4.787969 7.5 -22.76255 5.344396 7 -22.76255 5.344396 -7 -12.96281 5.733672 -7.5 -13.08687 5.165614 -7.5 -12.96281 5.733672 -7 -13.08687 5.165614 -7 -12.90553 6.312293 -7.5 -12.90553 6.312293 -7 -12.91582 6.89365 -7.5 -12.91582 6.89365 -7 -12.99352 7.469883 -7.5 -12.99352 7.469883 -7 -13.1376 8.033198 -7.5 -13.1376 8.033198 -7 -13.3461 8.575978 -7.5 -13.3461 8.575978 -7 -13.6162 9.090882 -7.5 -13.6162 9.090882 -7 -13.94426 9.570948 -7.5 -13.94426 9.570948 -7 -14.32582 10.00968 -7.5 -14.32582 10.00968 -7 -14.75574 10.40115 -7.5 -14.75574 10.40115 -7 -15.2282 10.74007 -7.5 -15.2282 10.74007 -7 -15.73682 11.02184 -7.5 -15.73682 11.02184 -7 -16.2747 11.24266 -7.5 -16.2747 11.24266 -7 -16.83459 11.39954 -7.5 -16.83459 11.39954 -7 -17.4089 11.49037 -7.5 -17.4089 11.49037 -7 -17.98987 11.5139 -7.5 -17.98987 11.5139 -7 -18.56964 11.46984 -7.5 -18.56964 11.46984 -7 -19.14038 11.35876 -7.5 -19.14038 11.35876 -7 -19.69437 11.18217 -7.5 -19.69437 11.18217 -7 -20.22411 10.94246 -7.5 -20.22411 10.94246 -7 -20.72244 10.64288 -7.5 -20.72244 10.64288 -7 -21.18261 10.28747 -7.5 -21.18261 10.28747 -7 -21.59842 9.881034 -7.5 -21.59842 9.881034 -7 -21.96423 9.429078 -7.5 -21.96423 9.429078 -7 -22.2751 8.93771 -7.5 -22.2751 8.93771 -7 -22.52682 8.413574 -7.5 -22.52682 8.413574 -7 -22.716 7.86376 -7.5 -22.716 7.86376 -7 -22.84006 7.295701 -7.5 -22.84006 7.295701 -7 -22.89734 6.717081 -7.5 -22.89734 6.717081 -7 -22.88705 6.135724 -7.5 -22.88705 6.135724 -7 -22.80935 5.559491 -7.5 -22.80935 5.559491 -7 -22.66527 4.996176 -7.5 -22.66527 4.996176 -7 -22.45677 4.453396 -7.5 -22.45677 4.453396 -7 -22.18667 3.938492 -7.5 -22.18667 3.938492 -7 -21.85861 3.458426 -7.5 -21.85861 3.458426 -7 -21.47705 3.019691 -7.5 -21.47705 3.019691 -7 -21.04713 2.628219 -7.5 -21.04713 2.628219 -7 -20.57466 2.289306 -7.5 -20.57466 2.289306 -7 -20.06605 2.007533 -7.5 -20.06605 2.007533 -7 -19.52817 1.786712 -7.5 -19.52817 1.786712 -7 -18.96828 1.629829 -7.5 -18.96828 1.629829 -7 -18.39397 1.539005 -7.5 -18.39397 1.539005 -7 -17.813 1.515469 -7.5 -17.813 1.515469 -7 -17.23322 1.559539 -7.5 -17.23322 1.559539 -7 -16.66249 1.670618 -7.5 -16.66249 1.670618 -7 -16.1085 1.847205 -7.5 -16.1085 1.847205 -7 -15.57876 2.086912 -7.5 -15.57876 2.086912 -7 -15.08043 2.386497 -7.5 -15.08043 2.386497 -7 -14.62025 2.741908 -7.5 -14.62025 2.741908 -7 -14.20445 3.14834 -7.5 -14.20445 3.14834 -7 -13.83864 3.600296 -7.5 -13.83864 3.600296 -7.5 -13.52777 4.091664 -7 -13.52777 4.091664 -7 -13.27605 4.6158 -7.5 -13.27605 4.6158 -7 -11.90262 33.19295 -7 -18.90262 33.19264 -6.87059 -18.90262 33.20968 -6.87059 -11.90262 33.20999 -6.75 -11.90263 33.25994 -6.646447 -11.90263 33.3394 -6.75 -18.90263 33.25963 -6.566987 -11.90263 33.44295 -6.646447 -18.90263 33.33909 -6.517037 -11.90264 33.56354 -6.566987 -18.90263 33.44264 -6.5 -11.90264 33.69295 -6.517037 -18.90264 33.56323 -6.517037 -11.90265 33.82236 -6.5 -18.90264 33.69264 -6.566987 -11.90266 33.94295 -6.517037 -18.90265 33.82205 -6.646447 -11.90266 34.04651 -6.566987 -18.90266 33.94264 -6.75 -11.90266 34.12597 -6.646447 -18.90266 34.0462 -6.87059 -11.90267 34.17592 -6.75 -18.90266 34.12566 -6.87059 -18.90267 34.17561 -7 -11.90267 34.19295 -7 -18.90267 34.19264 -6.87059 -11.90244 29.14599 -7 -11.90244 29.12895 -7 -18.90244 29.12864 -6.75 -11.90244 29.19594 -6.87059 -18.90244 29.14568 -6.646447 -11.90245 29.2754 -6.75 -18.90244 29.19563 -6.566987 -11.90245 29.37895 -6.646447 -18.90245 29.27509 -6.517037 -11.90246 29.49954 -6.566987 -18.90245 29.37864 -6.5 -11.90246 29.62895 -6.517037 -18.90246 29.49923 -6.517037 -11.90247 29.75836 -6.5 -18.90246 29.62864 -6.566987 -11.90247 29.87895 -6.517037 -18.90247 29.75805 -6.646447 -11.90248 29.98251 -6.566987 -18.90247 29.87864 -6.75 -11.90248 30.06197 -6.646447 -18.90248 29.9822 -6.87059 -11.90248 30.11192 -6.75 -18.90248 30.06166 -7 -11.90249 30.12895 -6.87059 -18.90248 30.11161 -7 -18.90249 30.12864 -7 4.316224 -4.167758 7 4.316224 -4.167758 7 3.85693 -4.596095 -7 4.728229 -3.693758 -7 3.85693 -4.596095 7 3.355379 -4.974076 -7 3.355379 -4.974076 7 2.817065 -5.29756 -7 2.629987 5.392881 7 2.05187 5.638247 7 2.629987 5.392881 -7 2.05187 5.638247 -7 2.817065 -5.29756 7 2.247887 -5.563003 -7 3.179289 5.08843 7 3.179289 5.08843 -7 2.247887 -5.563003 7 1.654081 -5.767497 -7 3.693758 4.728229 7 3.693758 4.728229 -7 1.654081 -5.767497 7 1.042152 -5.9088 -7 4.167758 4.316224 7 4.167758 4.316224 -7 1.042152 -5.9088 7 0.4188052 -5.985366 -7 4.596095 3.85693 7 4.596095 3.85693 7 4.974076 3.355379 -7 0.4188052 -5.985366 7 -0.2091302 -5.996354 -7 4.974076 3.355379 7 5.29756 2.817065 -7 -0.2091302 -5.996354 7 -0.8347742 -5.941646 -7 5.29756 2.817065 7 5.563003 2.247887 -7 -0.8347742 -5.941646 7 -1.451272 -5.821839 -7 -1.451272 -5.821839 -7 -2.05187 -5.638247 7 -2.05187 -5.638247 -7 5.563003 2.247887 7 5.767496 1.654081 -7 5.767496 1.654081 7 5.9088 1.042152 -7 5.9088 1.042152 7 5.985366 0.4188053 -7 5.985366 0.4188053 7 5.996354 -0.20913 -7 5.996354 -0.20913 7 5.941645 -0.8347741 -7 5.941645 -0.8347741 7 5.821839 -1.451272 -7 5.821839 -1.451272 7 5.638247 -2.05187 -7 5.638247 -2.05187 7 5.392881 -2.629987 -7 5.392881 -2.629987 7 5.08843 -3.179289 -7 5.08843 -3.179289 7 4.728229 -3.693758 7 -23.90143 6.51442 7 -23.85668 5.783206 7 -18.90175 13.51464 7 -11.86041 15.50478 7 -11.90187 16.31786 7 -23.90175 13.51442 7 -18.90244 29.12864 7 -11.90244 29.12895 7 -6.637697 8.800553 7 -7.387589 9.117537 7 -8.10138 9.509095 7 -8.77168 9.971172 7 -9.391545 10.49898 7 -19.9533 0.8764399 7 -9.954556 11.08706 7 -20.62514 1.168527 7 -21.25637 1.540312 7 -10.45488 11.72931 7 -21.83759 1.986254 7 -10.88734 12.41909 7 -11.24746 13.14925 7 -22.36012 2.499705 7 -11.5315 13.91223 7 -22.81619 3.07301 7 -23.19899 3.697622 7 -11.73652 14.70013 7 -23.50282 4.36423 7 -23.72314 5.062896 7 -18.90267 34.19264 7 -11.90267 34.19295 7 -11.9029 39.51495 7 -18.90313 44.51464 7 -13.90313 44.51486 -7 -18.90175 13.51464 6.646447 -18.90245 29.27509 6.75 -18.90244 29.19563 6.566987 -18.90245 29.37864 6.87059 -18.90244 29.14568 6.517037 -18.90246 29.49923 6.5 -18.90246 29.62864 6.517037 -18.90247 29.75805 6.566987 -18.90247 29.87864 -7 -18.90313 44.51464 6.566987 -18.90263 33.44264 6.646447 -18.90248 29.9822 6.646447 -18.90263 33.33909 6.75 -18.90263 33.25963 6.75 -18.90248 30.06166 6.87059 -18.90248 30.11161 6.87059 -18.90262 33.20968 6.517037 -18.90264 33.56323 6.5 -18.90264 33.69264 7 -18.90249 30.12864 7 -18.90262 33.19264 6.517037 -18.90265 33.82205 6.566987 -18.90266 33.94264 6.646447 -18.90266 34.0462 6.75 -18.90266 34.12566 6.87059 -18.90267 34.17561 7 -11.90249 30.12895 7 -11.90262 33.19295 -7 -11.9029 39.51495 -7 -13.90313 44.51486 -7 -20.62514 1.168527 -7 -19.9533 0.8764399 -7 -21.25637 1.540312 -7 -21.83759 1.986254 -7 -22.36012 2.499705 -7 -22.81619 3.07301 -7 -23.19899 3.697622 -7 -23.50282 4.36423 -7 -23.72314 5.062896 -7 -23.85668 5.783206 -7 -23.90143 6.51442 -7 -6.637697 8.800553 -7 -11.90187 16.31786 6.646447 -11.90245 29.2754 6.75 -11.90244 29.19594 6.566987 -11.90245 29.37895 6.87059 -11.90244 29.14599 6.517037 -11.90246 29.49954 6.5 -11.90246 29.62895 6.517037 -11.90247 29.75836 6.566987 -11.90247 29.87895 6.75 -11.90248 30.06197 6.646447 -11.90248 29.98251 6.75 -11.90263 33.25994 6.646447 -11.90263 33.3394 6.566987 -11.90263 33.44295 6.87059 -11.90248 30.11192 6.87059 -11.90262 33.20999 6.517037 -11.90264 33.56354 6.5 -11.90264 33.69295 6.517037 -11.90265 33.82236 6.566987 -11.90266 33.94295 6.646447 -11.90266 34.04651 6.75 -11.90266 34.12597 6.87059 -11.90267 34.17592 -7 -23.90175 13.51442 -7 -11.86041 15.50478 -7 -7.387589 9.117537 -7 -8.10138 9.509095 -7 -8.77168 9.971172 -7 -9.391545 10.49898 -7 -9.954556 11.08706 -7 -10.45488 11.72931 -7 -10.88734 12.41909 -7 -11.24746 13.14925 -7 -11.5315 13.91223 -7 -11.73652 14.70013 -6.5 -2.533055 1.607368 -6.5 -2.853211 0.926924 -7 -2.955231 1.875262 -7 -3.328746 1.081411 -6.5 -2.053739 2.186815 -7 -2.396029 2.551284 -6.5 0.7459402 2.905783 -6.5 -0.0001336508 3 -7 0.8702636 3.39008 -7 -0.0001559074 3.5 -6.5 -1.445378 2.628856 -7 -1.686274 3.066998 -6.5 1.445144 2.628984 -7 1.686001 3.067148 -6.5 -0.7461991 2.905716 -7 -0.8705656 3.390002 -6.5 2.053544 2.186997 -7 2.395801 2.551497 -6.5 2.532912 1.607593 -7 2.955064 1.875525 -6.5 2.853128 0.927178 -7 3.32865 1.081708 -6.5 2.994072 0.1885049 -7 3.493084 0.2199223 -6.5 2.946887 -0.5620127 -7 3.438034 -0.6556815 -6.5 2.714538 -1.277217 -7 3.166961 -1.490087 -6.5 2.311625 -1.912169 -7 2.696896 -2.230864 -6.5 1.763464 -2.426972 -7 2.057374 -2.831468 -6.5 1.104498 -2.78928 -7 1.288581 -3.25416 -7 0.4388208 -3.472382 -6.5 0.3761321 -2.976327 -7 -0.4385119 -3.472421 -6.5 -0.3758673 -2.976361 -7 -1.288291 -3.254275 -6.5 -1.10425 -2.789379 -6.5 -1.763248 -2.427129 -7 -2.057122 -2.831651 -6.5 -2.311455 -1.912375 -7 -2.696697 -2.231104 -6.5 -2.714424 -1.277459 -7 -3.166828 -1.490368 -6.5 -2.946837 -0.5622751 -7 -3.437976 -0.6559876 -6.5 -2.994089 0.1882383 -7 -3.493103 0.2196114 6.5 2.598009 1.500116 6.5 2.897743 0.7765862 6.5 -0.0001336508 3 6.5 2.121226 2.121415 6.5 -0.7765862 2.897743 6.5 1.499884 2.598143 6.5 -1.500116 2.598009 6.5 0.776328 2.897812 6.5 -2.121415 2.121226 6.5 -2.598143 1.499884 6.5 -2.897812 0.7763282 6.5 -3 -0.0001334985 6.5 -2.897743 -0.7765861 6.5 -2.59801 -1.500116 6.5 -2.121226 -2.121415 6.5 -1.499884 -2.598143 6.5 -0.7763283 -2.897812 6.5 0.0001334294 -3 6.5 0.776586 -2.897743 6.5 1.500116 -2.598009 6.5 2.121415 -2.121226 6.5 2.598143 -1.499884 6.5 2.897812 -0.7763281 6.5 3 0.0001335816 7 -3.32865 -1.081708 7 -2.955064 -1.875525 7 -2.395801 -2.551497 7 0.0001556861 -3.5 7 0.8705654 -3.390002 7 -1.686001 -3.067148 7 -0.8702638 -3.39008 7 1.686274 -3.066998 7 2.396028 -2.551284 7 2.955231 -1.875262 7 3.328746 -1.081411 7 3.493103 -0.2196113 7 3.437976 0.6559877 7 3.166828 1.490369 7 2.696697 2.231104 7 2.057122 2.831651 7 1.288291 3.254275 7 0.4385116 3.472421 7 -0.438821 3.472382 7 -1.288581 3.25416 7 -2.057375 2.831468 7 -2.696896 2.230864 7 -3.166961 1.490087 7 -3.438035 0.6556816 7 -3.493084 -0.2199223 -6.5 -19.34681 9.143543 -7 -20.29746 9.06597 -7 -19.58771 9.581685 -6.5 -18.64763 9.420403 -7 -18.772 9.904689 -6.5 -17.90157 9.514687 -7 -17.90159 10.01469 -6.5 -17.15549 9.42047 -7 -17.03117 9.904767 -6.5 -16.45629 9.143671 -7 -16.21543 9.581835 -6.5 -15.84789 8.701684 -7 -15.50563 9.066184 -6.5 -15.36852 8.12228 -7 -14.94637 8.390212 -6.5 -15.04831 7.441865 -7 -14.57278 7.596395 -6.5 -14.90736 6.703192 -7 -14.40835 6.734609 -6.5 -14.95455 5.952674 -7 -14.4634 5.859005 -6.5 -15.1869 5.23747 -7 -14.73447 5.0246 -6.5 -15.58981 4.602518 -7 -15.20454 4.283823 -6.5 -16.13797 4.087714 -7 -15.84406 3.683219 -6.5 -16.79694 3.725407 -7 -16.61285 3.260527 -6.5 -17.5253 3.53836 -7 -17.46261 3.042305 -6.5 -18.2773 3.538326 -7 -18.33995 3.042266 -6.5 -19.00568 3.725308 -7 -19.18973 3.260412 -6.5 -19.66468 4.087557 -7 -19.95856 3.683036 -6.5 -20.21289 4.602312 -7 -20.59813 4.283583 -6.5 -20.61586 5.237228 -7 -21.06826 5.024318 -6.5 -20.84827 5.952412 -7 -21.33941 5.858699 -6.5 -20.89552 6.702925 -7 -21.39454 6.734298 -6.5 -20.75465 7.441611 -7 -21.23018 7.596098 -6.5 -20.43449 8.122055 -7 -20.85667 8.389949 -6.5 -19.95517 8.701501 6.5 -15.30343 8.014803 6.5 -15.00369 7.291273 6.5 -17.90157 9.514687 6.5 -15.78021 8.636102 6.5 -18.67802 9.41243 6.5 -16.40155 9.11283 6.5 -19.40155 9.112696 6.5 -17.12511 9.412499 6.5 -20.02285 8.635913 6.5 -20.49958 8.014571 6.5 -20.79925 7.291015 6.5 -20.90143 6.514553 6.5 -20.79918 5.738101 6.5 -20.49944 5.014571 6.5 -20.02266 4.393272 6.5 -19.40132 3.916544 6.5 -18.67776 3.616875 6.5 -17.9013 3.514687 6.5 -17.12485 3.616944 6.5 -16.40132 3.916677 6.5 -15.78002 4.393461 6.5 -15.30329 5.014803 6.5 -15.00362 5.738359 6.5 -14.90143 6.51482 7 -21.23008 5.432979 7 -20.8565 4.639162 7 -20.29724 3.96319 7 -17.90128 3.014687 7 -17.03087 3.124685 7 -19.58744 3.447538 7 -18.7717 3.124607 7 -16.21516 3.447689 7 -15.50541 3.963403 7 -14.9462 4.639425 7 -14.57269 5.433276 7 -14.40833 6.295076 7 -14.46346 7.170675 7 -14.73461 8.005055 7 -15.20474 8.745791 7 -15.84431 9.346338 7 -16.61314 9.768962 7 -17.46292 9.987108 7 -18.34026 9.987069 7 -19.19002 9.768847 7 -19.95881 9.346155 7 -20.59833 8.745551 7 -21.0684 8.004773 7 -21.33947 7.170368 7 -21.39452 6.294765 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 4 2 5 2 6 2 7 3 0 3 8 3 0 4 2 4 8 4 9 5 4 5 10 5 4 6 6 6 10 6 5 7 7 7 11 7 7 8 8 8 11 8 5 9 11 9 6 9 12 10 9 10 13 10 9 11 10 11 13 11 14 12 12 12 15 12 12 13 13 13 15 13 16 14 14 14 17 14 14 15 15 15 17 15 18 16 16 16 19 16 16 17 17 17 19 17 20 18 18 18 21 18 18 19 19 19 21 19 22 20 20 20 23 20 20 21 21 21 23 21 24 22 22 22 25 22 22 23 23 23 25 23 26 24 24 24 27 24 24 25 25 25 27 25 28 26 26 26 29 26 26 27 27 27 29 27 28 28 29 28 30 28 31 29 28 29 30 29 31 30 30 30 32 30 33 31 31 31 32 31 33 32 32 32 34 32 35 33 33 33 34 33 35 34 34 34 36 34 37 35 35 35 36 35 38 36 37 36 39 36 37 37 36 37 39 37 40 38 38 38 41 38 38 39 39 39 41 39 42 40 40 40 43 40 40 41 41 41 43 41 44 42 42 42 45 42 42 43 43 43 45 43 46 44 44 44 47 44 44 45 45 45 47 45 48 46 46 46 49 46 46 47 47 47 49 47 1 48 48 48 3 48 48 49 49 49 3 49 50 50 51 50 52 50 51 51 53 51 52 51 54 52 50 52 55 52 50 53 52 53 55 53 56 54 54 54 57 54 58 55 59 55 60 55 54 56 55 56 57 56 59 57 61 57 60 57 62 58 56 58 63 58 64 59 58 59 65 59 56 60 57 60 63 60 58 61 60 61 65 61 66 62 62 62 67 62 62 63 63 63 67 63 68 64 64 64 69 64 64 65 65 65 69 65 70 66 66 66 71 66 66 67 67 67 71 67 72 68 68 68 73 68 68 69 69 69 73 69 59 70 70 70 61 70 70 71 71 71 61 71 74 72 72 72 75 72 72 73 73 73 75 73 76 74 74 74 77 74 74 75 75 75 77 75 78 76 76 76 79 76 76 77 77 77 79 77 80 78 78 78 81 78 78 79 79 79 81 79 82 80 80 80 83 80 80 81 81 81 83 81 84 82 82 82 85 82 82 83 83 83 85 83 86 84 84 84 87 84 84 85 85 85 87 85 86 86 87 86 88 86 89 87 86 87 88 87 89 88 88 88 90 88 91 89 89 89 90 89 91 90 90 90 92 90 93 91 91 91 92 91 94 92 93 92 95 92 93 93 92 93 95 93 96 94 94 94 97 94 94 95 95 95 97 95 98 96 96 96 99 96 96 97 97 97 99 97 51 98 98 98 53 98 98 99 99 99 53 99 100 100 101 100 102 100 101 101 103 101 102 101 104 102 105 102 106 102 107 103 100 103 108 103 100 104 102 104 108 104 109 105 104 105 110 105 104 106 106 106 110 106 105 107 107 107 111 107 107 108 108 108 111 108 105 109 111 109 106 109 112 110 109 110 113 110 109 111 110 111 113 111 114 112 112 112 115 112 112 113 113 113 115 113 116 114 114 114 117 114 114 115 115 115 117 115 118 116 116 116 119 116 116 117 117 117 119 117 120 118 118 118 121 118 118 119 119 119 121 119 122 120 120 120 123 120 120 121 121 121 123 121 124 122 122 122 125 122 122 123 123 123 125 123 126 124 124 124 127 124 124 125 125 125 127 125 128 126 126 126 129 126 126 127 127 127 129 127 128 128 129 128 130 128 131 129 128 129 130 129 131 130 130 130 132 130 133 131 131 131 132 131 133 132 132 132 134 132 135 133 133 133 134 133 135 134 134 134 136 134 137 135 135 135 136 135 138 136 137 136 139 136 137 137 136 137 139 137 140 138 138 138 141 138 138 139 139 139 141 139 142 140 140 140 143 140 140 141 141 141 143 141 144 142 142 142 145 142 142 143 143 143 145 143 146 144 144 144 147 144 144 145 145 145 147 145 148 146 146 146 149 146 146 147 147 147 149 147 101 148 148 148 103 148 148 149 149 149 103 149 150 150 151 150 152 150 151 151 153 151 152 151 154 152 150 152 155 152 150 153 152 153 155 153 156 154 154 154 157 154 158 155 159 155 160 155 154 156 155 156 157 156 159 157 161 157 160 157 162 158 156 158 163 158 164 159 158 159 165 159 156 160 157 160 163 160 158 161 160 161 165 161 166 162 162 162 167 162 162 163 163 163 167 163 168 164 164 164 169 164 164 165 165 165 169 165 170 166 166 166 171 166 166 167 167 167 171 167 172 168 168 168 173 168 168 169 169 169 173 169 159 170 170 170 161 170 170 171 171 171 161 171 174 172 172 172 175 172 172 173 173 173 175 173 176 174 174 174 177 174 174 175 175 175 177 175 178 176 176 176 179 176 176 177 177 177 179 177 180 178 178 178 181 178 178 179 179 179 181 179 182 180 180 180 183 180 180 181 181 181 183 181 184 182 182 182 185 182 182 183 183 183 185 183 186 184 184 184 187 184 184 185 185 185 187 185 186 186 187 186 188 186 189 187 186 187 188 187 189 188 188 188 190 188 191 189 189 189 190 189 191 190 190 190 192 190 193 191 191 191 192 191 194 192 193 192 195 192 193 193 192 193 195 193 196 194 194 194 197 194 194 195 195 195 197 195 198 196 196 196 199 196 196 197 197 197 199 197 151 198 198 198 153 198 198 199 199 199 153 199 200 200 201 200 202 200 203 201 204 201 205 201 204 202 202 202 205 202 206 203 207 203 208 203 209 204 203 204 210 204 203 205 205 205 210 205 211 206 206 206 212 206 206 207 208 207 212 207 207 208 209 208 213 208 209 209 210 209 213 209 207 210 213 210 208 210 214 211 211 211 215 211 211 212 212 212 215 212 216 213 214 213 217 213 214 214 215 214 217 214 218 215 216 215 219 215 216 216 217 216 219 216 220 217 218 217 221 217 218 218 219 218 221 218 222 219 220 219 223 219 220 220 221 220 223 220 224 221 222 221 225 221 222 222 223 222 225 222 226 223 224 223 227 223 224 224 225 224 227 224 228 225 226 225 229 225 226 226 227 226 229 226 230 227 228 227 231 227 228 228 229 228 231 228 232 229 230 229 233 229 230 230 231 230 233 230 232 231 233 231 234 231 235 232 232 232 234 232 235 233 234 233 236 233 237 234 235 234 236 234 237 235 236 235 238 235 239 236 237 236 238 236 240 237 239 237 241 237 239 238 238 238 241 238 242 239 240 239 243 239 240 240 241 240 243 240 244 241 242 241 245 241 242 242 243 242 245 242 246 243 244 243 247 243 244 244 245 244 247 244 248 245 246 245 249 245 246 246 247 246 249 246 200 247 248 247 201 247 248 248 249 248 201 248 204 249 200 249 202 249 250 250 251 250 252 250 250 251 253 251 251 251 254 252 252 252 255 252 254 253 250 253 252 253 256 254 255 254 257 254 256 255 254 255 255 255 258 256 257 256 259 256 258 257 259 257 260 257 258 258 256 258 257 258 261 259 258 259 260 259 262 260 260 260 263 260 262 261 263 261 264 261 262 262 261 262 260 262 265 263 262 263 264 263 266 264 264 264 267 264 266 265 267 265 268 265 266 266 265 266 264 266 269 267 268 267 270 267 269 268 266 268 268 268 271 269 270 269 272 269 271 270 269 270 270 270 273 271 271 271 272 271 274 272 272 272 275 272 274 273 275 273 276 273 274 274 273 274 272 274 277 275 276 275 278 275 277 276 274 276 276 276 279 277 278 277 280 277 279 278 277 278 278 278 281 279 279 279 280 279 282 280 280 280 283 280 282 281 281 281 280 281 284 282 283 282 285 282 284 283 282 283 283 283 286 284 285 284 287 284 286 285 287 285 288 285 286 286 284 286 285 286 289 287 288 287 290 287 289 288 286 288 288 288 291 289 290 289 292 289 291 290 289 290 290 290 293 291 292 291 294 291 293 292 291 292 292 292 295 293 293 293 294 293 295 294 294 294 296 294 297 295 295 295 296 295 298 296 297 296 296 296 298 297 296 297 299 297 298 298 299 298 300 298 301 299 298 299 300 299 301 300 300 300 302 300 303 301 301 301 302 301 303 302 302 302 304 302 305 303 303 303 304 303 305 304 304 304 306 304 307 305 305 305 306 305 307 306 306 306 308 306 309 307 308 307 310 307 309 308 307 308 308 308 311 309 310 309 312 309 311 310 309 310 310 310 313 311 312 311 314 311 313 312 311 312 312 312 315 313 314 313 316 313 315 314 313 314 314 314 317 315 316 315 318 315 317 316 315 316 316 316 319 317 318 317 320 317 319 318 317 318 318 318 321 319 320 319 322 319 321 320 319 320 320 320 323 321 322 321 324 321 323 322 321 322 322 322 325 323 324 323 326 323 325 324 323 324 324 324 327 325 325 325 326 325 328 326 326 326 329 326 328 327 327 327 326 327 330 328 329 328 331 328 330 329 331 329 332 329 330 330 328 330 329 330 333 331 332 331 334 331 333 332 330 332 332 332 335 333 333 333 334 333 336 334 334 334 337 334 336 335 337 335 338 335 336 336 335 336 334 336 339 337 336 337 338 337 340 338 338 338 341 338 340 339 341 339 342 339 340 340 339 340 338 340 343 341 340 341 342 341 344 342 343 342 342 342 344 343 342 343 345 343 346 344 344 344 345 344 346 345 345 345 347 345 346 346 347 346 348 346 349 347 346 347 348 347 350 348 349 348 348 348 350 349 348 349 351 349 350 350 351 350 352 350 353 351 350 351 352 351 354 352 353 352 352 352 354 353 352 353 355 353 354 354 355 354 356 354 357 355 354 355 356 355 253 356 357 356 356 356 253 357 356 357 251 357 358 358 359 358 360 358 361 359 360 359 362 359 361 360 358 360 360 360 363 361 362 361 364 361 363 362 361 362 362 362 365 363 364 363 366 363 365 364 363 364 364 364 367 365 366 365 368 365 367 366 365 366 366 366 369 367 368 367 370 367 369 368 367 368 368 368 371 369 370 369 372 369 371 370 369 370 370 370 373 371 372 371 374 371 373 372 371 372 372 372 375 373 374 373 376 373 375 374 373 374 374 374 377 375 376 375 378 375 377 376 375 376 376 376 379 377 378 377 380 377 379 378 377 378 378 378 381 379 380 379 382 379 381 380 379 380 380 380 383 381 382 381 384 381 383 382 381 382 382 382 385 383 384 383 386 383 385 384 383 384 384 384 387 385 386 385 388 385 387 386 385 386 386 386 389 387 388 387 390 387 389 388 387 388 388 388 391 389 390 389 392 389 391 390 389 390 390 390 393 391 392 391 394 391 393 392 391 392 392 392 395 393 394 393 396 393 395 394 393 394 394 394 397 395 396 395 398 395 397 396 395 396 396 396 399 397 398 397 400 397 399 398 397 398 398 398 401 399 400 399 402 399 401 400 399 400 400 400 403 401 401 401 402 401 403 402 402 402 404 402 405 403 403 403 404 403 405 404 404 404 406 404 407 405 405 405 406 405 407 406 406 406 408 406 409 407 407 407 408 407 409 408 408 408 410 408 411 409 409 409 410 409 411 410 410 410 412 410 413 411 411 411 412 411 413 412 412 412 414 412 415 413 413 413 414 413 415 414 414 414 416 414 417 415 416 415 418 415 417 416 415 416 416 416 419 417 418 417 420 417 419 418 417 418 418 418 421 419 420 419 422 419 421 420 419 420 420 420 423 421 422 421 424 421 423 422 421 422 422 422 425 423 424 423 426 423 425 424 423 424 424 424 427 425 426 425 428 425 427 426 425 426 426 426 429 427 428 427 430 427 429 428 427 428 428 428 431 429 430 429 432 429 431 430 429 430 430 430 433 431 432 431 434 431 433 432 431 432 432 432 435 433 434 433 436 433 435 434 433 434 434 434 437 435 436 435 438 435 437 436 435 436 436 436 439 437 438 437 440 437 439 438 437 438 438 438 441 439 440 439 442 439 441 440 439 440 440 440 443 441 442 441 444 441 443 442 441 442 442 442 445 443 444 443 446 443 445 444 443 444 444 444 447 445 446 445 448 445 447 446 445 446 446 446 449 447 448 447 450 447 449 448 447 448 448 448 451 449 450 449 452 449 451 450 449 450 450 450 453 451 451 451 452 451 453 452 452 452 454 452 455 453 453 453 454 453 455 454 454 454 456 454 457 455 455 455 456 455 457 456 456 456 458 456 459 457 457 457 458 457 459 458 458 458 460 458 461 459 459 459 460 459 462 460 461 460 460 460 462 461 460 461 463 461 462 462 463 462 464 462 465 463 462 463 464 463 465 464 464 464 359 464 358 465 465 465 359 465 466 466 467 466 468 466 469 467 468 467 470 467 469 468 466 468 468 468 471 469 470 469 472 469 471 470 469 470 470 470 473 471 472 471 474 471 473 472 471 472 472 472 475 473 474 473 476 473 475 474 473 474 474 474 477 475 476 475 478 475 477 476 475 476 476 476 479 477 478 477 480 477 479 478 477 478 478 478 481 479 480 479 482 479 481 480 479 480 480 480 483 481 482 481 484 481 483 482 481 482 482 482 485 483 484 483 486 483 485 484 483 484 484 484 487 485 486 485 488 485 487 486 485 486 486 486 489 487 488 487 490 487 489 488 487 488 488 488 491 489 490 489 492 489 491 490 489 490 490 490 493 491 492 491 494 491 493 492 491 492 492 492 495 493 494 493 496 493 495 494 493 494 494 494 497 495 496 495 498 495 497 496 495 496 496 496 499 497 498 497 500 497 499 498 497 498 498 498 501 499 500 499 502 499 501 500 499 500 500 500 503 501 502 501 504 501 503 502 501 502 502 502 505 503 504 503 506 503 505 504 503 504 504 504 507 505 506 505 508 505 507 506 505 506 506 506 509 507 508 507 510 507 509 508 507 508 508 508 511 509 509 509 510 509 511 510 510 510 512 510 513 511 511 511 512 511 513 512 512 512 514 512 515 513 513 513 514 513 515 514 514 514 516 514 517 515 515 515 516 515 517 516 516 516 518 516 519 517 517 517 518 517 519 518 518 518 520 518 521 519 519 519 520 519 521 520 520 520 522 520 523 521 521 521 522 521 523 522 522 522 524 522 525 523 524 523 526 523 525 524 523 524 524 524 527 525 526 525 528 525 527 526 525 526 526 526 529 527 528 527 530 527 529 528 527 528 528 528 531 529 530 529 532 529 531 530 529 530 530 530 533 531 532 531 534 531 533 532 531 532 532 532 535 533 534 533 536 533 535 534 533 534 534 534 537 535 536 535 538 535 537 536 535 536 536 536 539 537 538 537 540 537 539 538 537 538 538 538 541 539 540 539 542 539 541 540 539 540 540 540 543 541 542 541 544 541 543 542 541 542 542 542 545 543 544 543 546 543 545 544 543 544 544 544 547 545 546 545 548 545 547 546 545 546 546 546 549 547 548 547 550 547 549 548 547 548 548 548 551 549 550 549 552 549 551 550 549 550 550 550 553 551 552 551 554 551 553 552 551 552 552 552 555 553 554 553 556 553 555 554 553 554 554 554 557 555 556 555 558 555 557 556 555 556 556 556 559 557 558 557 560 557 559 558 557 558 558 558 561 559 559 559 560 559 561 560 560 560 562 560 563 561 561 561 562 561 563 562 562 562 564 562 565 563 563 563 564 563 565 564 564 564 566 564 567 565 565 565 566 565 567 566 566 566 568 566 569 567 567 567 568 567 569 568 568 568 570 568 571 569 569 569 570 569 571 570 570 570 572 570 573 571 571 571 572 571 573 572 572 572 467 572 466 573 573 573 467 573 574 574 575 574 576 574 574 575 577 575 575 575 578 576 576 576 579 576 578 577 574 577 576 577 580 578 579 578 581 578 580 579 578 579 579 579 582 580 581 580 583 580 582 581 580 581 581 581 584 582 583 582 585 582 584 583 582 583 583 583 586 584 585 584 587 584 586 585 584 585 585 585 588 586 587 586 589 586 588 587 586 587 587 587 590 588 589 588 591 588 590 589 588 589 589 589 592 590 591 590 593 590 592 591 590 591 591 591 594 592 593 592 595 592 594 593 592 593 593 593 596 594 595 594 597 594 596 595 594 595 595 595 598 596 597 596 599 596 598 597 596 597 597 597 600 598 599 598 601 598 600 599 598 599 599 599 602 600 601 600 603 600 602 601 600 601 601 601 604 602 603 602 605 602 604 603 602 603 603 603 606 604 605 604 607 604 606 605 604 605 605 605 608 606 607 606 609 606 608 607 606 607 607 607 610 608 609 608 611 608 610 609 608 609 609 609 612 610 611 610 613 610 612 611 610 611 611 611 614 612 613 612 615 612 614 613 612 613 613 613 616 614 615 614 617 614 616 615 614 615 615 615 618 616 616 616 617 616 618 617 617 617 619 617 620 618 618 618 619 618 620 619 619 619 621 619 622 620 620 620 621 620 622 621 621 621 623 621 624 622 622 622 623 622 624 623 623 623 625 623 626 624 624 624 625 624 626 625 625 625 627 625 628 626 626 626 627 626 628 627 627 627 629 627 630 628 628 628 629 628 630 629 629 629 631 629 632 630 630 630 631 630 632 631 631 631 633 631 634 632 633 632 635 632 634 633 632 633 633 633 636 634 635 634 637 634 636 635 634 635 635 635 638 636 637 636 639 636 638 637 636 637 637 637 640 638 639 638 641 638 640 639 638 639 639 639 642 640 641 640 643 640 642 641 640 641 641 641 644 642 643 642 645 642 644 643 642 643 643 643 646 644 645 644 647 644 646 645 644 645 645 645 648 646 647 646 649 646 648 647 646 647 647 647 650 648 649 648 651 648 650 649 648 649 649 649 652 650 651 650 653 650 652 651 650 651 651 651 654 652 653 652 655 652 654 653 652 653 653 653 656 654 655 654 657 654 656 655 654 655 655 655 658 656 657 656 659 656 658 657 656 657 657 657 660 658 659 658 661 658 660 659 658 659 659 659 662 660 661 660 663 660 662 661 660 661 661 661 664 662 663 662 665 662 664 663 662 663 663 663 666 664 665 664 667 664 666 665 664 665 665 665 668 666 666 666 667 666 668 667 667 667 669 667 670 668 668 668 669 668 670 669 669 669 671 669 672 670 670 670 671 670 672 671 671 671 673 671 674 672 672 672 673 672 674 673 673 673 675 673 676 674 674 674 675 674 676 675 675 675 677 675 676 676 677 676 678 676 679 677 676 677 678 677 680 678 679 678 678 678 680 679 678 679 681 679 577 680 680 680 681 680 577 681 681 681 575 681 682 682 683 682 684 682 685 683 682 683 684 683 686 684 685 684 684 684 687 685 686 685 688 685 686 686 684 686 688 686 689 687 687 687 690 687 687 688 688 688 690 688 691 689 689 689 692 689 689 690 690 690 692 690 693 691 691 691 694 691 691 692 692 692 694 692 695 693 693 693 696 693 693 694 694 694 696 694 697 695 695 695 698 695 695 696 696 696 698 696 699 697 697 697 700 697 697 698 698 698 700 698 701 699 699 699 702 699 699 700 700 700 702 700 703 701 701 701 704 701 701 702 702 702 704 702 703 703 704 703 705 703 706 704 703 704 707 704 703 705 705 705 707 705 708 706 709 706 710 706 711 707 708 707 712 707 708 708 710 708 712 708 713 709 711 709 714 709 711 710 712 710 714 710 715 711 713 711 716 711 713 712 714 712 716 712 717 713 715 713 718 713 715 714 716 714 718 714 719 715 717 715 720 715 717 716 718 716 720 716 721 717 719 717 722 717 719 718 720 718 722 718 723 719 721 719 724 719 721 720 722 720 724 720 725 721 723 721 726 721 723 722 724 722 726 722 727 723 725 723 728 723 725 724 726 724 728 724 729 725 727 725 730 725 727 726 728 726 730 726 731 727 729 727 732 727 729 728 730 728 732 728 731 729 732 729 733 729 734 730 735 730 736 730 734 731 737 731 735 731 738 732 736 732 739 732 738 733 734 733 736 733 740 734 739 734 741 734 742 735 743 735 744 735 740 736 738 736 739 736 742 737 745 737 743 737 746 738 741 738 747 738 746 739 740 739 741 739 748 740 744 740 749 740 748 741 742 741 744 741 750 742 747 742 751 742 750 743 746 743 747 743 752 744 749 744 753 744 752 745 748 745 749 745 754 746 751 746 755 746 754 747 750 747 751 747 756 748 753 748 757 748 756 749 752 749 753 749 758 750 755 750 759 750 758 751 754 751 755 751 760 752 761 752 762 752 760 753 757 753 761 753 760 754 756 754 757 754 763 755 759 755 764 755 763 756 758 756 759 756 765 757 762 757 766 757 765 758 760 758 762 758 767 759 764 759 768 759 767 760 763 760 764 760 769 761 766 761 770 761 771 762 768 762 772 762 769 763 765 763 766 763 771 764 767 764 768 764 773 765 771 765 772 765 774 766 772 766 775 766 776 767 770 767 777 767 776 768 769 768 770 768 774 769 773 769 772 769 778 770 777 770 779 770 778 771 776 771 777 771 780 772 778 772 779 772 780 773 779 773 781 773 782 774 780 774 781 774 782 775 781 775 783 775 784 776 782 776 783 776 784 777 783 777 785 777 786 778 785 778 787 778 786 779 784 779 785 779 788 780 786 780 787 780 788 781 787 781 789 781 790 782 789 782 791 782 790 783 788 783 789 783 792 784 791 784 793 784 792 785 790 785 791 785 794 786 793 786 795 786 794 787 792 787 793 787 737 788 795 788 735 788 737 789 794 789 795 789 796 790 469 790 471 790 796 791 797 791 469 791 473 792 796 792 471 792 475 793 796 793 473 793 798 794 491 794 493 794 798 795 489 795 491 795 798 796 487 796 489 796 798 797 501 797 799 797 798 798 799 798 800 798 798 799 499 799 501 799 798 800 497 800 499 800 429 801 736 801 735 801 798 802 495 802 497 802 798 803 493 803 495 803 801 804 485 804 487 804 801 805 483 805 485 805 801 806 481 806 483 806 801 807 479 807 481 807 801 808 477 808 479 808 801 809 475 809 477 809 427 810 735 810 795 810 801 811 796 811 475 811 427 812 429 812 735 812 801 813 487 813 798 813 431 814 739 814 736 814 431 815 736 815 429 815 802 816 798 816 800 816 802 817 800 817 803 817 425 818 795 818 793 818 425 819 427 819 795 819 433 820 741 820 739 820 433 821 739 821 431 821 423 822 793 822 791 822 423 823 425 823 793 823 435 824 747 824 741 824 435 825 741 825 433 825 421 826 791 826 789 826 421 827 789 827 787 827 421 828 423 828 791 828 437 829 751 829 747 829 437 830 747 830 435 830 419 831 421 831 787 831 419 832 787 832 785 832 439 833 751 833 437 833 439 834 759 834 755 834 439 835 755 835 751 835 417 836 419 836 785 836 417 837 785 837 783 837 441 838 759 838 439 838 441 839 764 839 759 839 415 840 417 840 783 840 415 841 783 841 781 841 443 842 768 842 764 842 443 843 764 843 441 843 413 844 415 844 781 844 413 845 781 845 779 845 445 846 772 846 768 846 445 847 768 847 443 847 411 848 413 848 779 848 411 849 779 849 777 849 447 850 775 850 772 850 447 851 772 851 445 851 409 852 777 852 770 852 409 853 411 853 777 853 449 854 775 854 447 854 407 855 770 855 766 855 407 856 409 856 770 856 451 857 775 857 449 857 405 858 407 858 766 858 405 859 766 859 762 859 453 860 775 860 451 860 403 861 762 861 761 861 403 862 405 862 762 862 455 863 775 863 453 863 757 864 403 864 761 864 401 865 403 865 757 865 457 866 775 866 455 866 753 867 401 867 757 867 399 868 401 868 753 868 749 869 397 869 399 869 749 870 399 870 753 870 744 871 395 871 397 871 744 872 397 872 749 872 743 873 393 873 395 873 743 874 395 874 744 874 391 875 393 875 743 875 389 876 391 876 743 876 387 877 389 877 743 877 804 878 385 878 387 878 804 879 383 879 385 879 804 880 381 880 383 880 804 881 379 881 381 881 804 882 377 882 379 882 804 883 375 883 377 883 804 884 373 884 375 884 804 885 371 885 373 885 804 886 369 886 371 886 804 887 387 887 743 887 537 888 358 888 361 888 535 889 537 889 361 889 535 890 361 890 363 890 539 891 465 891 358 891 539 892 358 892 537 892 533 893 535 893 363 893 533 894 363 894 365 894 541 895 462 895 465 895 541 896 465 896 539 896 531 897 533 897 365 897 531 898 365 898 367 898 543 899 461 899 462 899 543 900 462 900 541 900 529 901 531 901 367 901 529 902 367 902 369 902 545 903 459 903 461 903 545 904 461 904 543 904 527 905 369 905 804 905 527 906 529 906 369 906 547 907 457 907 459 907 547 908 459 908 545 908 525 909 804 909 805 909 525 910 527 910 804 910 523 911 805 911 806 911 523 912 525 912 805 912 521 913 806 913 807 913 521 914 523 914 806 914 519 915 807 915 808 915 519 916 521 916 807 916 809 917 457 917 547 917 809 918 551 918 553 918 809 919 549 919 551 919 809 920 547 920 549 920 809 921 775 921 457 921 555 922 809 922 553 922 517 923 808 923 810 923 517 924 519 924 808 924 557 925 809 925 555 925 811 926 809 926 557 926 515 927 517 927 810 927 559 928 811 928 557 928 812 929 811 929 559 929 513 930 810 930 813 930 513 931 515 931 810 931 561 932 812 932 559 932 814 933 812 933 561 933 511 934 513 934 813 934 511 935 813 935 815 935 563 936 814 936 561 936 509 937 511 937 815 937 509 938 815 938 816 938 817 939 814 939 563 939 565 940 817 940 563 940 507 941 509 941 816 941 507 942 816 942 818 942 819 943 565 943 567 943 819 944 817 944 565 944 505 945 507 945 818 945 820 946 819 946 567 946 820 947 567 947 569 947 503 948 505 948 818 948 503 949 818 949 821 949 501 950 503 950 821 950 501 951 821 951 799 951 822 952 820 952 569 952 822 953 569 953 571 953 823 954 822 954 571 954 823 955 571 955 573 955 797 956 466 956 469 956 797 957 573 957 466 957 797 958 823 958 573 958 824 959 825 959 826 959 827 960 826 960 828 960 827 961 824 961 826 961 162 962 829 962 156 962 829 963 162 963 166 963 156 964 829 964 154 964 829 965 166 965 170 965 154 966 829 966 150 966 829 967 170 967 159 967 829 968 159 968 158 968 150 969 829 969 798 969 194 970 196 970 798 970 196 971 198 971 798 971 198 972 151 972 798 972 151 973 150 973 798 973 194 974 798 974 193 974 193 975 798 975 191 975 191 976 798 976 189 976 829 977 158 977 710 977 158 978 164 978 710 978 710 979 164 979 712 979 164 980 168 980 712 980 168 981 172 981 243 981 714 982 712 982 241 982 712 983 168 983 241 983 168 984 243 984 241 984 243 985 172 985 245 985 172 986 174 986 245 986 716 987 714 987 238 987 714 988 241 988 238 988 733 989 732 989 683 989 245 990 174 990 247 990 174 991 176 991 247 991 716 992 238 992 236 992 718 993 716 993 236 993 683 994 732 994 684 994 732 995 730 995 684 995 684 996 730 996 688 996 730 997 728 997 688 997 176 998 178 998 249 998 247 999 176 999 249 999 688 1000 728 1000 690 1000 728 1001 726 1001 690 1001 720 1002 718 1002 234 1002 718 1003 236 1003 234 1003 690 1004 726 1004 692 1004 249 1005 178 1005 201 1005 178 1006 180 1006 201 1006 720 1007 234 1007 233 1007 722 1008 720 1008 233 1008 724 1009 722 1009 233 1009 201 1010 180 1010 202 1010 180 1011 182 1011 202 1011 726 1012 724 1012 231 1012 724 1013 233 1013 231 1013 202 1014 182 1014 205 1014 182 1015 184 1015 205 1015 692 1016 726 1016 229 1016 726 1017 231 1017 229 1017 205 1018 184 1018 210 1018 694 1019 692 1019 62 1019 696 1020 694 1020 62 1020 229 1021 227 1021 56 1021 62 1022 692 1022 56 1022 692 1023 229 1023 56 1023 698 1024 696 1024 66 1024 696 1025 62 1025 66 1025 227 1026 225 1026 54 1026 56 1027 227 1027 54 1027 700 1028 698 1028 70 1028 698 1029 66 1029 70 1029 225 1030 223 1030 50 1030 54 1031 225 1031 50 1031 702 1032 700 1032 59 1032 704 1033 702 1033 59 1033 700 1034 70 1034 59 1034 223 1035 221 1035 51 1035 50 1036 223 1036 51 1036 705 1037 704 1037 58 1037 704 1038 59 1038 58 1038 221 1039 219 1039 98 1039 51 1040 221 1040 98 1040 705 1041 58 1041 64 1041 98 1042 219 1042 96 1042 219 1043 217 1043 96 1043 208 1044 213 1044 830 1044 213 1045 210 1045 831 1045 830 1046 213 1046 831 1046 208 1047 830 1047 832 1047 210 1048 184 1048 833 1048 831 1049 210 1049 833 1049 212 1050 208 1050 834 1050 208 1051 832 1051 834 1051 215 1052 212 1052 835 1052 212 1053 834 1053 835 1053 833 1054 184 1054 802 1054 189 1055 798 1055 802 1055 184 1056 186 1056 802 1056 186 1057 189 1057 802 1057 217 1058 215 1058 836 1058 215 1059 835 1059 836 1059 217 1060 836 1060 837 1060 705 1061 64 1061 838 1061 707 1062 705 1062 838 1062 64 1063 68 1063 838 1063 68 1064 72 1064 838 1064 72 1065 74 1065 838 1065 838 1066 74 1066 76 1066 96 1067 217 1067 839 1067 217 1068 837 1068 839 1068 840 1069 841 1069 839 1069 837 1070 840 1070 839 1070 841 1071 840 1071 842 1071 843 1072 844 1072 842 1072 840 1073 843 1073 842 1073 842 1074 844 1074 845 1074 96 1075 839 1075 846 1075 94 1076 96 1076 846 1076 93 1077 94 1077 847 1077 94 1078 846 1078 847 1078 844 1079 848 1079 849 1079 845 1080 844 1080 849 1080 93 1081 847 1081 850 1081 91 1082 93 1082 851 1082 93 1083 850 1083 851 1083 89 1084 91 1084 852 1084 91 1085 851 1085 852 1085 86 1086 89 1086 853 1086 89 1087 852 1087 853 1087 84 1088 86 1088 854 1088 86 1089 853 1089 854 1089 854 1090 824 1090 827 1090 838 1091 76 1091 827 1091 76 1092 78 1092 827 1092 78 1093 80 1093 827 1093 80 1094 82 1094 827 1094 82 1095 84 1095 827 1095 84 1096 854 1096 827 1096 849 1097 848 1097 855 1097 849 1098 855 1098 856 1098 857 1099 706 1099 707 1099 858 1100 857 1100 838 1100 857 1101 707 1101 838 1101 682 1102 731 1102 683 1102 731 1103 733 1103 683 1103 859 1104 860 1104 809 1104 859 1105 809 1105 811 1105 861 1106 811 1106 812 1106 861 1107 859 1107 811 1107 862 1108 812 1108 814 1108 862 1109 861 1109 812 1109 863 1110 814 1110 817 1110 863 1111 862 1111 814 1111 864 1112 817 1112 819 1112 864 1113 863 1113 817 1113 865 1114 819 1114 820 1114 865 1115 864 1115 819 1115 866 1116 820 1116 822 1116 866 1117 865 1117 820 1117 867 1118 822 1118 823 1118 867 1119 866 1119 822 1119 868 1120 823 1120 797 1120 868 1121 867 1121 823 1121 869 1122 797 1122 796 1122 869 1123 868 1123 797 1123 774 1124 775 1124 860 1124 860 1125 775 1125 809 1125 745 1126 870 1126 804 1126 745 1127 804 1127 743 1127 871 1128 102 1128 103 1128 102 1129 871 1129 108 1129 871 1130 103 1130 149 1130 108 1131 871 1131 111 1131 871 1132 149 1132 147 1132 111 1133 871 1133 106 1133 106 1134 871 1134 110 1134 110 1135 871 1135 709 1135 113 1136 110 1136 709 1136 113 1137 709 1137 708 1137 115 1138 113 1138 708 1138 115 1139 708 1139 711 1139 871 1140 147 1140 800 1140 136 1141 134 1141 800 1141 139 1142 136 1142 800 1142 141 1143 139 1143 800 1143 143 1144 141 1144 800 1144 145 1145 143 1145 800 1145 147 1146 145 1146 800 1146 800 1147 134 1147 132 1147 800 1148 132 1148 130 1148 119 1149 117 1149 240 1149 240 1150 117 1150 239 1150 117 1151 115 1151 239 1151 119 1152 240 1152 242 1152 239 1153 115 1153 237 1153 711 1154 713 1154 237 1154 115 1155 711 1155 237 1155 729 1156 731 1156 682 1156 119 1157 242 1157 244 1157 121 1158 119 1158 244 1158 237 1159 713 1159 235 1159 713 1160 715 1160 235 1160 729 1161 682 1161 685 1161 725 1162 727 1162 686 1162 727 1163 729 1163 686 1163 729 1164 685 1164 686 1164 121 1165 244 1165 246 1165 123 1166 121 1166 246 1166 725 1167 686 1167 687 1167 715 1168 717 1168 232 1168 235 1169 715 1169 232 1169 725 1170 687 1170 689 1170 723 1171 725 1171 689 1171 123 1172 246 1172 248 1172 232 1173 717 1173 230 1173 717 1174 719 1174 230 1174 719 1175 721 1175 230 1175 123 1176 248 1176 200 1176 125 1177 123 1177 200 1177 230 1178 721 1178 228 1178 125 1179 200 1179 204 1179 127 1180 125 1180 204 1180 127 1181 204 1181 203 1181 723 1182 689 1182 2 1182 689 1183 691 1183 2 1183 226 1184 228 1184 3 1184 721 1185 723 1185 3 1185 228 1186 721 1186 3 1186 723 1187 2 1187 3 1187 691 1188 693 1188 8 1188 693 1189 695 1189 8 1189 2 1190 691 1190 8 1190 222 1191 224 1191 49 1191 224 1192 226 1192 49 1192 226 1193 3 1193 49 1193 695 1194 697 1194 11 1194 697 1195 699 1195 11 1195 8 1196 695 1196 11 1196 703 1197 706 1197 857 1197 220 1198 222 1198 47 1198 222 1199 49 1199 47 1199 11 1200 699 1200 6 1200 699 1201 701 1201 6 1201 701 1202 703 1202 6 1202 216 1203 218 1203 45 1203 218 1204 220 1204 45 1204 220 1205 47 1205 45 1205 703 1206 857 1206 10 1206 6 1207 703 1207 10 1207 216 1208 45 1208 43 1208 214 1209 216 1209 43 1209 10 1210 857 1210 13 1210 214 1211 43 1211 41 1211 13 1212 857 1212 15 1212 209 1213 207 1213 872 1213 203 1214 209 1214 873 1214 209 1215 872 1215 873 1215 127 1216 203 1216 873 1216 872 1217 207 1217 874 1217 127 1218 873 1218 875 1218 129 1219 127 1219 875 1219 207 1220 206 1220 876 1220 874 1221 207 1221 876 1221 206 1222 211 1222 877 1222 876 1223 206 1223 877 1223 129 1224 875 1224 803 1224 800 1225 130 1225 803 1225 130 1226 129 1226 803 1226 214 1227 41 1227 878 1227 211 1228 214 1228 878 1228 877 1229 211 1229 878 1229 878 1230 41 1230 879 1230 15 1231 857 1231 17 1231 17 1232 857 1232 19 1232 880 1233 881 1233 882 1233 881 1234 883 1234 882 1234 881 1235 879 1235 884 1235 879 1236 41 1236 884 1236 883 1237 881 1237 884 1237 41 1238 39 1238 884 1238 885 1239 880 1239 886 1239 880 1240 882 1240 886 1240 884 1241 39 1241 887 1241 887 1242 39 1242 888 1242 39 1243 36 1243 888 1243 855 1244 885 1244 856 1244 885 1245 886 1245 856 1245 888 1246 36 1246 889 1246 36 1247 34 1247 890 1247 889 1248 36 1248 890 1248 890 1249 34 1249 891 1249 34 1250 32 1250 892 1250 891 1251 34 1251 892 1251 892 1252 32 1252 893 1252 825 1253 893 1253 826 1253 25 1254 23 1254 826 1254 27 1255 25 1255 826 1255 29 1256 27 1256 826 1256 30 1257 29 1257 826 1257 32 1258 30 1258 826 1258 893 1259 32 1259 826 1259 21 1260 857 1260 826 1260 23 1261 21 1261 826 1261 19 1262 857 1262 21 1262 857 1263 858 1263 826 1263 858 1264 828 1264 826 1264 858 1265 838 1265 828 1265 828 1266 838 1266 827 1266 894 1267 869 1267 796 1267 894 1268 796 1268 801 1268 630 1269 632 1269 869 1269 632 1270 634 1270 869 1270 634 1271 868 1271 869 1271 630 1272 869 1272 628 1272 628 1273 869 1273 626 1273 737 1274 734 1274 350 1274 871 1275 895 1275 829 1275 895 1276 600 1276 829 1276 600 1277 602 1277 829 1277 602 1278 604 1278 829 1278 604 1279 606 1279 829 1279 606 1280 608 1280 829 1280 608 1281 610 1281 829 1281 610 1282 612 1282 829 1282 612 1283 614 1283 829 1283 734 1284 738 1284 349 1284 350 1285 734 1285 349 1285 614 1286 616 1286 894 1286 616 1287 618 1287 894 1287 794 1288 737 1288 353 1288 618 1289 620 1289 894 1289 620 1290 622 1290 894 1290 622 1291 624 1291 894 1291 624 1292 626 1292 894 1292 829 1293 614 1293 894 1293 737 1294 350 1294 353 1294 626 1295 869 1295 894 1295 738 1296 740 1296 346 1296 349 1297 738 1297 346 1297 709 1298 871 1298 710 1298 871 1299 829 1299 710 1299 792 1300 794 1300 354 1300 794 1301 353 1301 354 1301 746 1302 750 1302 344 1302 740 1303 746 1303 344 1303 346 1304 740 1304 344 1304 790 1305 792 1305 357 1305 792 1306 354 1306 357 1306 750 1307 754 1307 343 1307 344 1308 750 1308 343 1308 790 1309 357 1309 253 1309 788 1310 790 1310 253 1310 754 1311 758 1311 340 1311 343 1312 754 1312 340 1312 788 1313 253 1313 250 1313 786 1314 788 1314 250 1314 340 1315 758 1315 339 1315 758 1316 763 1316 339 1316 786 1317 250 1317 254 1317 784 1318 786 1318 254 1318 782 1319 784 1319 254 1319 763 1320 767 1320 336 1320 339 1321 763 1321 336 1321 780 1322 782 1322 256 1322 782 1323 254 1323 256 1323 767 1324 771 1324 335 1324 336 1325 767 1325 335 1325 780 1326 256 1326 258 1326 778 1327 780 1327 258 1327 771 1328 773 1328 333 1328 335 1329 771 1329 333 1329 776 1330 778 1330 261 1330 778 1331 258 1331 261 1331 773 1332 774 1332 330 1332 333 1333 773 1333 330 1333 776 1334 261 1334 262 1334 776 1335 262 1335 769 1335 330 1336 774 1336 328 1336 769 1337 262 1337 265 1337 769 1338 265 1338 765 1338 328 1339 774 1339 327 1339 765 1340 265 1340 266 1340 327 1341 774 1341 325 1341 765 1342 266 1342 760 1342 760 1343 266 1343 269 1343 325 1344 774 1344 323 1344 760 1345 269 1345 756 1345 756 1346 269 1346 271 1346 756 1347 271 1347 752 1347 752 1348 271 1348 273 1348 752 1349 273 1349 748 1349 273 1350 274 1350 742 1350 748 1351 273 1351 742 1351 274 1352 277 1352 745 1352 742 1353 274 1353 745 1353 745 1354 277 1354 279 1354 745 1355 279 1355 281 1355 745 1356 281 1356 282 1356 282 1357 284 1357 870 1357 284 1358 286 1358 870 1358 286 1359 289 1359 870 1359 289 1360 291 1360 870 1360 291 1361 293 1361 870 1361 745 1362 282 1362 870 1362 293 1363 295 1363 870 1363 295 1364 297 1364 870 1364 297 1365 298 1365 870 1365 298 1366 301 1366 870 1366 309 1367 311 1367 674 1367 674 1368 311 1368 672 1368 311 1369 313 1369 672 1369 307 1370 309 1370 676 1370 309 1371 674 1371 676 1371 672 1372 313 1372 670 1372 313 1373 315 1373 670 1373 307 1374 676 1374 679 1374 305 1375 307 1375 679 1375 670 1376 315 1376 668 1376 315 1377 317 1377 668 1377 305 1378 679 1378 680 1378 303 1379 305 1379 680 1379 668 1380 317 1380 666 1380 317 1381 319 1381 666 1381 303 1382 680 1382 577 1382 301 1383 303 1383 577 1383 666 1384 319 1384 664 1384 319 1385 321 1385 664 1385 301 1386 577 1386 574 1386 896 1387 870 1387 574 1387 870 1388 301 1388 574 1388 664 1389 321 1389 662 1389 323 1390 774 1390 662 1390 321 1391 323 1391 662 1391 897 1392 896 1392 578 1392 896 1393 574 1393 578 1393 898 1394 897 1394 580 1394 897 1395 578 1395 580 1395 898 1396 580 1396 582 1396 662 1397 774 1397 860 1397 656 1398 658 1398 860 1398 658 1399 660 1399 860 1399 660 1400 662 1400 860 1400 899 1401 898 1401 584 1401 898 1402 582 1402 584 1402 656 1403 860 1403 654 1403 900 1404 899 1404 586 1404 899 1405 584 1405 586 1405 860 1406 859 1406 652 1406 654 1407 860 1407 652 1407 901 1408 900 1408 588 1408 900 1409 586 1409 588 1409 859 1410 861 1410 650 1410 652 1411 859 1411 650 1411 902 1412 901 1412 590 1412 901 1413 588 1413 590 1413 650 1414 861 1414 648 1414 648 1415 861 1415 862 1415 902 1416 590 1416 592 1416 902 1417 592 1417 903 1417 648 1418 862 1418 646 1418 646 1419 862 1419 863 1419 903 1420 592 1420 594 1420 646 1421 863 1421 644 1421 644 1422 863 1422 864 1422 904 1423 903 1423 596 1423 903 1424 594 1424 596 1424 644 1425 864 1425 642 1425 905 1426 904 1426 598 1426 904 1427 596 1427 598 1427 642 1428 864 1428 865 1428 642 1429 865 1429 640 1429 895 1430 905 1430 600 1430 905 1431 598 1431 600 1431 640 1432 865 1432 866 1432 638 1433 640 1433 866 1433 636 1434 638 1434 867 1434 638 1435 866 1435 867 1435 634 1436 636 1436 868 1436 636 1437 867 1437 868 1437 871 1438 800 1438 799 1438 895 1439 871 1439 799 1439 905 1440 895 1440 821 1440 895 1441 799 1441 821 1441 904 1442 905 1442 818 1442 905 1443 821 1443 818 1443 903 1444 904 1444 816 1444 904 1445 818 1445 816 1445 902 1446 903 1446 815 1446 903 1447 816 1447 815 1447 901 1448 902 1448 813 1448 902 1449 815 1449 813 1449 900 1450 901 1450 810 1450 901 1451 813 1451 810 1451 899 1452 900 1452 808 1452 898 1453 899 1453 808 1453 900 1454 810 1454 808 1454 897 1455 898 1455 807 1455 898 1456 808 1456 807 1456 896 1457 897 1457 806 1457 897 1458 807 1458 806 1458 870 1459 896 1459 805 1459 896 1460 806 1460 805 1460 870 1461 805 1461 804 1461 829 1462 894 1462 798 1462 798 1463 894 1463 801 1463 885 1464 855 1464 844 1464 855 1465 848 1465 844 1465 880 1466 885 1466 843 1466 885 1467 844 1467 843 1467 881 1468 880 1468 840 1468 880 1469 843 1469 840 1469 879 1470 881 1470 837 1470 881 1471 840 1471 837 1471 878 1472 879 1472 836 1472 879 1473 837 1473 836 1473 877 1474 878 1474 835 1474 878 1475 836 1475 835 1475 876 1476 877 1476 834 1476 877 1477 835 1477 834 1477 874 1478 876 1478 832 1478 876 1479 834 1479 832 1479 872 1480 874 1480 830 1480 874 1481 832 1481 830 1481 873 1482 872 1482 831 1482 872 1483 830 1483 831 1483 875 1484 873 1484 833 1484 873 1485 831 1485 833 1485 803 1486 875 1486 802 1486 875 1487 833 1487 802 1487 893 1488 825 1488 854 1488 825 1489 824 1489 854 1489 892 1490 893 1490 853 1490 893 1491 854 1491 853 1491 891 1492 892 1492 852 1492 892 1493 853 1493 852 1493 890 1494 891 1494 851 1494 891 1495 852 1495 851 1495 889 1496 890 1496 850 1496 890 1497 851 1497 850 1497 888 1498 889 1498 847 1498 889 1499 850 1499 847 1499 887 1500 888 1500 846 1500 888 1501 847 1501 846 1501 884 1502 887 1502 839 1502 887 1503 846 1503 839 1503 883 1504 884 1504 841 1504 884 1505 839 1505 841 1505 882 1506 883 1506 842 1506 883 1507 841 1507 842 1507 886 1508 882 1508 845 1508 882 1509 842 1509 845 1509 856 1510 886 1510 849 1510 886 1511 845 1511 849 1511 633 1512 637 1512 635 1512 633 1513 639 1513 637 1513 633 1514 641 1514 639 1514 633 1515 643 1515 641 1515 667 1516 671 1516 669 1516 633 1517 645 1517 643 1517 633 1518 667 1518 649 1518 599 1519 593 1519 591 1519 599 1520 595 1520 593 1520 599 1521 597 1521 595 1521 675 1522 673 1522 671 1522 629 1523 633 1523 631 1523 661 1524 665 1524 663 1524 661 1525 667 1525 665 1525 605 1526 601 1526 599 1526 605 1527 603 1527 601 1527 678 1528 677 1528 675 1528 678 1529 671 1529 667 1529 678 1530 675 1530 671 1530 625 1531 629 1531 627 1531 625 1532 633 1532 629 1532 657 1533 661 1533 659 1533 621 1534 625 1534 623 1534 611 1535 591 1535 587 1535 611 1536 607 1536 605 1536 576 1537 681 1537 678 1537 611 1538 609 1538 607 1538 576 1539 575 1539 681 1539 611 1540 599 1540 591 1540 611 1541 605 1541 599 1541 653 1542 657 1542 655 1542 619 1543 587 1543 667 1543 653 1544 661 1544 657 1544 619 1545 667 1545 633 1545 619 1546 633 1546 625 1546 619 1547 625 1547 621 1547 619 1548 611 1548 587 1548 579 1549 576 1549 678 1549 615 1550 613 1550 611 1550 615 1551 619 1551 617 1551 615 1552 611 1552 619 1552 649 1553 653 1553 651 1553 649 1554 667 1554 661 1554 649 1555 661 1555 653 1555 645 1556 649 1556 647 1556 587 1557 581 1557 579 1557 587 1558 583 1558 581 1558 587 1559 585 1559 583 1559 587 1560 678 1560 667 1560 587 1561 579 1561 678 1561 591 1562 589 1562 587 1562 633 1563 649 1563 645 1563 524 1564 532 1564 528 1564 524 1565 528 1565 526 1565 490 1566 488 1566 486 1566 490 1567 478 1567 532 1567 558 1568 562 1568 560 1568 490 1569 486 1569 478 1569 490 1570 532 1570 524 1570 520 1571 524 1571 522 1571 554 1572 558 1572 556 1572 568 1573 566 1573 564 1573 496 1574 492 1574 490 1574 496 1575 494 1575 492 1575 496 1576 490 1576 524 1576 496 1577 524 1577 520 1577 516 1578 520 1578 518 1578 550 1579 554 1579 552 1579 512 1580 516 1580 514 1580 572 1581 564 1581 562 1581 572 1582 570 1582 568 1582 502 1583 498 1583 496 1583 572 1584 568 1584 564 1584 502 1585 500 1585 498 1585 510 1586 496 1586 520 1586 510 1587 520 1587 516 1587 510 1588 516 1588 512 1588 546 1589 550 1589 548 1589 504 1590 502 1590 496 1590 504 1591 496 1591 510 1591 546 1592 558 1592 554 1592 546 1593 554 1593 550 1593 508 1594 504 1594 510 1594 468 1595 467 1595 572 1595 506 1596 504 1596 508 1596 470 1597 468 1597 572 1597 540 1598 544 1598 542 1598 474 1599 472 1599 470 1599 536 1600 540 1600 538 1600 478 1601 476 1601 474 1601 478 1602 546 1602 544 1602 478 1603 562 1603 558 1603 478 1604 572 1604 562 1604 478 1605 558 1605 546 1605 478 1606 470 1606 572 1606 478 1607 474 1607 470 1607 534 1608 540 1608 536 1608 534 1609 544 1609 540 1609 534 1610 478 1610 544 1610 532 1611 478 1611 534 1611 484 1612 480 1612 478 1612 484 1613 482 1613 480 1613 528 1614 532 1614 530 1614 486 1615 484 1615 478 1615 374 1616 456 1616 454 1616 374 1617 458 1617 456 1617 374 1618 360 1618 458 1618 374 1619 450 1619 440 1619 374 1620 440 1620 436 1620 374 1621 366 1621 362 1621 420 1622 424 1622 422 1622 420 1623 426 1623 424 1623 378 1624 376 1624 374 1624 446 1625 450 1625 448 1625 416 1626 420 1626 418 1626 382 1627 380 1627 378 1627 382 1628 374 1628 436 1628 382 1629 378 1629 374 1629 414 1630 426 1630 420 1630 414 1631 420 1631 416 1631 442 1632 446 1632 444 1632 464 1633 460 1633 458 1633 410 1634 414 1634 412 1634 464 1635 463 1635 460 1635 388 1636 384 1636 382 1636 388 1637 386 1637 384 1637 388 1638 382 1638 436 1638 440 1639 450 1639 446 1639 440 1640 446 1640 442 1640 360 1641 359 1641 464 1641 360 1642 464 1642 458 1642 436 1643 440 1643 438 1643 394 1644 390 1644 388 1644 394 1645 392 1645 390 1645 394 1646 426 1646 414 1646 394 1647 414 1647 410 1647 394 1648 388 1648 436 1648 394 1649 436 1649 426 1649 402 1650 406 1650 404 1650 400 1651 408 1651 406 1651 400 1652 410 1652 408 1652 400 1653 394 1653 410 1653 400 1654 406 1654 402 1654 366 1655 364 1655 362 1655 398 1656 396 1656 394 1656 398 1657 394 1657 400 1657 430 1658 434 1658 432 1658 430 1659 436 1659 434 1659 370 1660 368 1660 366 1660 426 1661 436 1661 430 1661 426 1662 430 1662 428 1662 374 1663 362 1663 360 1663 374 1664 370 1664 366 1664 374 1665 372 1665 370 1665 374 1666 452 1666 450 1666 374 1667 454 1667 452 1667 308 1668 320 1668 316 1668 308 1669 312 1669 310 1669 308 1670 314 1670 312 1670 308 1671 316 1671 314 1671 342 1672 347 1672 345 1672 275 1673 268 1673 267 1673 275 1674 272 1674 268 1674 351 1675 348 1675 347 1675 304 1676 329 1676 320 1676 304 1677 320 1677 308 1677 304 1678 308 1678 306 1678 304 1679 355 1679 342 1679 304 1680 342 1680 329 1680 304 1681 255 1681 355 1681 337 1682 341 1682 338 1682 337 1683 342 1683 341 1683 355 1684 352 1684 351 1684 280 1685 276 1685 275 1685 280 1686 278 1686 276 1686 355 1687 347 1687 342 1687 355 1688 351 1688 347 1688 300 1689 304 1689 302 1689 332 1690 337 1690 334 1690 332 1691 342 1691 337 1691 296 1692 300 1692 299 1692 287 1693 267 1693 255 1693 287 1694 255 1694 304 1694 287 1695 283 1695 280 1695 287 1696 285 1696 283 1696 287 1697 304 1697 300 1697 287 1698 275 1698 267 1698 287 1699 280 1699 275 1699 252 1700 356 1700 355 1700 252 1701 251 1701 356 1701 329 1702 332 1702 331 1702 329 1703 342 1703 332 1703 290 1704 288 1704 287 1704 290 1705 294 1705 292 1705 290 1706 296 1706 294 1706 255 1707 252 1707 355 1707 290 1708 287 1708 300 1708 290 1709 300 1709 296 1709 324 1710 329 1710 326 1710 259 1711 257 1711 255 1711 260 1712 259 1712 255 1712 320 1713 324 1713 322 1713 320 1714 329 1714 324 1714 316 1715 320 1715 318 1715 267 1716 260 1716 255 1716 267 1717 263 1717 260 1717 267 1718 264 1718 263 1718 272 1719 270 1719 268 1719 140 1720 199 1720 138 1720 104 1721 109 1721 165 1721 104 1722 160 1722 161 1722 104 1723 165 1723 160 1723 142 1724 199 1724 140 1724 142 1725 153 1725 199 1725 183 1726 124 1726 126 1726 105 1727 104 1727 161 1727 185 1728 126 1728 128 1728 185 1729 183 1729 126 1729 181 1730 120 1730 122 1730 181 1731 122 1731 124 1731 144 1732 152 1732 153 1732 181 1733 124 1733 183 1733 144 1734 153 1734 142 1734 107 1735 105 1735 161 1735 187 1736 185 1736 128 1736 107 1737 171 1737 167 1737 107 1738 161 1738 171 1738 179 1739 118 1739 120 1739 146 1740 152 1740 144 1740 146 1741 155 1741 152 1741 179 1742 120 1742 181 1742 146 1743 157 1743 155 1743 188 1744 128 1744 131 1744 100 1745 107 1745 167 1745 188 1746 187 1746 128 1746 100 1747 167 1747 163 1747 148 1748 163 1748 157 1748 148 1749 157 1749 146 1749 177 1750 116 1750 118 1750 101 1751 100 1751 163 1751 177 1752 118 1752 179 1752 101 1753 163 1753 148 1753 190 1754 131 1754 133 1754 190 1755 188 1755 131 1755 175 1756 116 1756 177 1756 192 1757 133 1757 135 1757 192 1758 190 1758 133 1758 173 1759 114 1759 116 1759 173 1760 116 1760 175 1760 195 1761 135 1761 137 1761 195 1762 192 1762 135 1762 112 1763 173 1763 169 1763 112 1764 114 1764 173 1764 138 1765 195 1765 137 1765 138 1766 197 1766 195 1766 165 1767 112 1767 169 1767 199 1768 197 1768 138 1768 109 1769 112 1769 165 1769 4 1770 9 1770 65 1770 4 1771 60 1771 61 1771 4 1772 65 1772 60 1772 42 1773 99 1773 40 1773 42 1774 53 1774 99 1774 83 1775 24 1775 26 1775 5 1776 4 1776 61 1776 85 1777 26 1777 28 1777 85 1778 83 1778 26 1778 44 1779 53 1779 42 1779 81 1780 20 1780 22 1780 81 1781 22 1781 24 1781 44 1782 52 1782 53 1782 81 1783 24 1783 83 1783 7 1784 5 1784 61 1784 87 1785 85 1785 28 1785 7 1786 61 1786 71 1786 46 1787 52 1787 44 1787 79 1788 18 1788 20 1788 46 1789 55 1789 52 1789 46 1790 57 1790 55 1790 79 1791 20 1791 81 1791 88 1792 28 1792 31 1792 0 1793 7 1793 71 1793 0 1794 67 1794 63 1794 0 1795 71 1795 67 1795 88 1796 87 1796 28 1796 48 1797 63 1797 57 1797 48 1798 57 1798 46 1798 77 1799 16 1799 18 1799 1 1800 0 1800 63 1800 1 1801 63 1801 48 1801 77 1802 18 1802 79 1802 90 1803 31 1803 33 1803 90 1804 33 1804 35 1804 90 1805 88 1805 31 1805 75 1806 16 1806 77 1806 92 1807 90 1807 35 1807 37 1808 92 1808 35 1808 73 1809 14 1809 16 1809 73 1810 16 1810 75 1810 95 1811 92 1811 37 1811 12 1812 73 1812 69 1812 12 1813 14 1813 73 1813 38 1814 95 1814 37 1814 38 1815 97 1815 95 1815 65 1816 12 1816 69 1816 9 1817 12 1817 65 1817 40 1818 97 1818 38 1818 40 1819 99 1819 97 1819 906 1820 907 1820 908 1820 907 1821 909 1821 908 1821 910 1822 906 1822 911 1822 906 1823 908 1823 911 1823 912 1824 913 1824 914 1824 913 1825 915 1825 914 1825 916 1826 910 1826 917 1826 910 1827 911 1827 917 1827 918 1828 912 1828 919 1828 912 1829 914 1829 919 1829 920 1830 916 1830 921 1830 916 1831 917 1831 921 1831 922 1832 918 1832 923 1832 913 1833 920 1833 915 1833 918 1834 919 1834 923 1834 920 1835 921 1835 915 1835 924 1836 922 1836 925 1836 922 1837 923 1837 925 1837 926 1838 924 1838 927 1838 924 1839 925 1839 927 1839 928 1840 926 1840 929 1840 926 1841 927 1841 929 1841 930 1842 928 1842 931 1842 928 1843 929 1843 931 1843 932 1844 930 1844 933 1844 930 1845 931 1845 933 1845 934 1846 932 1846 935 1846 932 1847 933 1847 935 1847 936 1848 934 1848 937 1848 934 1849 935 1849 937 1849 938 1850 936 1850 939 1850 936 1851 937 1851 939 1851 938 1852 939 1852 940 1852 941 1853 938 1853 940 1853 941 1854 940 1854 942 1854 943 1855 941 1855 942 1855 943 1856 942 1856 944 1856 945 1857 943 1857 944 1857 946 1858 945 1858 947 1858 945 1859 944 1859 947 1859 948 1860 946 1860 949 1860 946 1861 947 1861 949 1861 950 1862 948 1862 951 1862 948 1863 949 1863 951 1863 952 1864 950 1864 953 1864 950 1865 951 1865 953 1865 954 1866 952 1866 955 1866 952 1867 953 1867 955 1867 907 1868 954 1868 909 1868 954 1869 955 1869 909 1869 924 1870 926 1870 956 1870 926 1871 957 1871 956 1871 920 1872 913 1872 958 1872 922 1873 924 1873 959 1873 924 1874 956 1874 959 1874 916 1875 920 1875 960 1875 920 1876 958 1876 960 1876 918 1877 922 1877 961 1877 922 1878 959 1878 961 1878 910 1879 916 1879 962 1879 916 1880 960 1880 962 1880 912 1881 918 1881 963 1881 918 1882 961 1882 963 1882 913 1883 912 1883 958 1883 906 1884 910 1884 964 1884 912 1885 963 1885 958 1885 910 1886 962 1886 964 1886 907 1887 906 1887 965 1887 906 1888 964 1888 965 1888 954 1889 907 1889 966 1889 907 1890 965 1890 966 1890 952 1891 954 1891 967 1891 954 1892 966 1892 967 1892 950 1893 952 1893 968 1893 952 1894 967 1894 968 1894 948 1895 950 1895 969 1895 950 1896 968 1896 969 1896 946 1897 948 1897 970 1897 948 1898 969 1898 970 1898 945 1899 946 1899 971 1899 946 1900 970 1900 971 1900 943 1901 945 1901 972 1901 945 1902 971 1902 972 1902 943 1903 972 1903 973 1903 941 1904 943 1904 973 1904 941 1905 973 1905 974 1905 938 1906 941 1906 974 1906 938 1907 974 1907 975 1907 936 1908 938 1908 975 1908 934 1909 936 1909 976 1909 936 1910 975 1910 976 1910 934 1911 976 1911 977 1911 932 1912 934 1912 977 1912 930 1913 932 1913 978 1913 932 1914 977 1914 978 1914 928 1915 930 1915 979 1915 930 1916 978 1916 979 1916 926 1917 928 1917 957 1917 928 1918 979 1918 957 1918 969 1919 980 1919 981 1919 969 1920 981 1920 970 1920 970 1921 981 1921 982 1921 970 1922 982 1922 971 1922 973 1923 983 1923 984 1923 974 1924 973 1924 984 1924 971 1925 982 1925 985 1925 971 1926 985 1926 972 1926 972 1927 985 1927 986 1927 975 1928 974 1928 987 1928 974 1929 984 1929 987 1929 972 1930 986 1930 973 1930 973 1931 986 1931 983 1931 976 1932 975 1932 988 1932 975 1933 987 1933 988 1933 977 1934 976 1934 989 1934 976 1935 988 1935 989 1935 978 1936 977 1936 990 1936 977 1937 989 1937 990 1937 979 1938 978 1938 991 1938 978 1939 990 1939 991 1939 957 1940 979 1940 992 1940 979 1941 991 1941 992 1941 956 1942 957 1942 993 1942 957 1943 992 1943 993 1943 959 1944 956 1944 994 1944 956 1945 993 1945 994 1945 961 1946 959 1946 995 1946 959 1947 994 1947 995 1947 963 1948 961 1948 996 1948 961 1949 995 1949 996 1949 958 1950 963 1950 997 1950 963 1951 996 1951 997 1951 960 1952 958 1952 998 1952 958 1953 997 1953 998 1953 962 1954 960 1954 999 1954 960 1955 998 1955 999 1955 964 1956 962 1956 1000 1956 962 1957 999 1957 1000 1957 965 1958 964 1958 1001 1958 964 1959 1000 1959 1001 1959 966 1960 965 1960 1002 1960 965 1961 1001 1961 1002 1961 967 1962 966 1962 1003 1962 966 1963 1002 1963 1003 1963 968 1964 967 1964 1004 1964 967 1965 1003 1965 1004 1965 969 1966 968 1966 980 1966 968 1967 1004 1967 980 1967 940 1968 939 1968 937 1968 927 1969 937 1969 935 1969 927 1970 935 1970 933 1970 927 1971 933 1971 931 1971 927 1972 931 1972 929 1972 944 1973 942 1973 940 1973 944 1974 940 1974 937 1974 947 1975 937 1975 927 1975 947 1976 944 1976 937 1976 919 1977 927 1977 925 1977 919 1978 925 1978 923 1978 919 1979 947 1979 927 1979 951 1980 949 1980 947 1980 953 1981 951 1981 947 1981 955 1982 953 1982 947 1982 921 1983 919 1983 914 1983 921 1984 914 1984 915 1984 909 1985 947 1985 919 1985 909 1986 955 1986 947 1986 908 1987 909 1987 919 1987 911 1988 921 1988 917 1988 911 1989 919 1989 921 1989 911 1990 908 1990 919 1990 987 1991 984 1991 983 1991 988 1992 987 1992 983 1992 989 1993 988 1993 983 1993 990 1994 989 1994 983 1994 991 1995 990 1995 992 1995 990 1996 983 1996 993 1996 992 1997 990 1997 993 1997 983 1998 986 1998 985 1998 983 1999 985 1999 982 1999 994 2000 993 2000 995 2000 993 2001 983 2001 995 2001 983 2002 982 2002 981 2002 980 2003 1004 2003 1003 2003 981 2004 980 2004 1003 2004 983 2005 981 2005 1003 2005 983 2006 1003 2006 1002 2006 996 2007 995 2007 1000 2007 997 2008 996 2008 1000 2008 998 2009 997 2009 1000 2009 999 2010 998 2010 1000 2010 995 2011 983 2011 1000 2011 983 2012 1002 2012 1001 2012 1000 2013 983 2013 1001 2013 1005 2014 1006 2014 1007 2014 1005 2015 1007 2015 1008 2015 1008 2016 1007 2016 1009 2016 1010 2017 1011 2017 1012 2017 1008 2018 1009 2018 1010 2018 1010 2019 1009 2019 1011 2019 1012 2020 1011 2020 1013 2020 1012 2021 1013 2021 1014 2021 1014 2022 1013 2022 1015 2022 1014 2023 1015 2023 1016 2023 1016 2024 1015 2024 1017 2024 1016 2025 1017 2025 1018 2025 1018 2026 1017 2026 1019 2026 1018 2027 1019 2027 1020 2027 1020 2028 1019 2028 1021 2028 1020 2029 1021 2029 1022 2029 1022 2030 1021 2030 1023 2030 1022 2031 1023 2031 1024 2031 1024 2032 1023 2032 1025 2032 1024 2033 1025 2033 1026 2033 1026 2034 1025 2034 1027 2034 1026 2035 1027 2035 1028 2035 1028 2036 1027 2036 1029 2036 1028 2037 1029 2037 1030 2037 1030 2038 1029 2038 1031 2038 1030 2039 1031 2039 1032 2039 1032 2040 1031 2040 1033 2040 1032 2041 1033 2041 1034 2041 1034 2042 1033 2042 1035 2042 1034 2043 1035 2043 1036 2043 1036 2044 1035 2044 1037 2044 1036 2045 1037 2045 1038 2045 1038 2046 1037 2046 1039 2046 1038 2047 1039 2047 1040 2047 1040 2048 1039 2048 1041 2048 1040 2049 1041 2049 1042 2049 1042 2050 1041 2050 1043 2050 1042 2051 1043 2051 1044 2051 1044 2052 1043 2052 1045 2052 1044 2053 1045 2053 1046 2053 1046 2054 1045 2054 1047 2054 1046 2055 1047 2055 1048 2055 1048 2056 1047 2056 1049 2056 1048 2057 1049 2057 1050 2057 1050 2058 1049 2058 1051 2058 1050 2059 1051 2059 1052 2059 1052 2060 1051 2060 1053 2060 1052 2061 1053 2061 1054 2061 1054 2062 1053 2062 1006 2062 1054 2063 1006 2063 1005 2063 1018 2064 1020 2064 1055 2064 1020 2065 1056 2065 1055 2065 1008 2066 1010 2066 1057 2066 1016 2067 1018 2067 1058 2067 1018 2068 1055 2068 1058 2068 1005 2069 1008 2069 1059 2069 1008 2070 1057 2070 1059 2070 1014 2071 1016 2071 1060 2071 1016 2072 1058 2072 1060 2072 1054 2073 1005 2073 1061 2073 1005 2074 1059 2074 1061 2074 1012 2075 1014 2075 1062 2075 1014 2076 1060 2076 1062 2076 1010 2077 1012 2077 1057 2077 1052 2078 1054 2078 1063 2078 1012 2079 1062 2079 1057 2079 1054 2080 1061 2080 1063 2080 1050 2081 1052 2081 1064 2081 1052 2082 1063 2082 1064 2082 1048 2083 1050 2083 1065 2083 1050 2084 1064 2084 1065 2084 1046 2085 1048 2085 1066 2085 1048 2086 1065 2086 1066 2086 1044 2087 1046 2087 1067 2087 1046 2088 1066 2088 1067 2088 1042 2089 1044 2089 1068 2089 1044 2090 1067 2090 1068 2090 1040 2091 1042 2091 1069 2091 1042 2092 1068 2092 1069 2092 1038 2093 1040 2093 1070 2093 1040 2094 1069 2094 1070 2094 1036 2095 1038 2095 1071 2095 1038 2096 1070 2096 1071 2096 1036 2097 1071 2097 1072 2097 1034 2098 1036 2098 1072 2098 1034 2099 1072 2099 1073 2099 1032 2100 1034 2100 1073 2100 1032 2101 1073 2101 1074 2101 1030 2102 1032 2102 1074 2102 1028 2103 1030 2103 1075 2103 1030 2104 1074 2104 1075 2104 1028 2105 1075 2105 1076 2105 1026 2106 1028 2106 1076 2106 1024 2107 1026 2107 1077 2107 1026 2108 1076 2108 1077 2108 1022 2109 1024 2109 1078 2109 1024 2110 1077 2110 1078 2110 1020 2111 1022 2111 1056 2111 1022 2112 1078 2112 1056 2112 1068 2113 1079 2113 1080 2113 1068 2114 1080 2114 1069 2114 1069 2115 1080 2115 1081 2115 1069 2116 1081 2116 1070 2116 1072 2117 1082 2117 1083 2117 1073 2118 1072 2118 1083 2118 1070 2119 1081 2119 1084 2119 1070 2120 1084 2120 1071 2120 1071 2121 1084 2121 1085 2121 1074 2122 1073 2122 1086 2122 1073 2123 1083 2123 1086 2123 1071 2124 1085 2124 1072 2124 1072 2125 1085 2125 1082 2125 1075 2126 1074 2126 1087 2126 1074 2127 1086 2127 1087 2127 1076 2128 1075 2128 1088 2128 1075 2129 1087 2129 1088 2129 1077 2130 1076 2130 1089 2130 1076 2131 1088 2131 1089 2131 1078 2132 1077 2132 1090 2132 1077 2133 1089 2133 1090 2133 1056 2134 1078 2134 1091 2134 1078 2135 1090 2135 1091 2135 1055 2136 1056 2136 1092 2136 1056 2137 1091 2137 1092 2137 1058 2138 1055 2138 1093 2138 1055 2139 1092 2139 1093 2139 1060 2140 1058 2140 1094 2140 1058 2141 1093 2141 1094 2141 1062 2142 1060 2142 1095 2142 1060 2143 1094 2143 1095 2143 1057 2144 1062 2144 1096 2144 1062 2145 1095 2145 1096 2145 1059 2146 1057 2146 1097 2146 1057 2147 1096 2147 1097 2147 1061 2148 1059 2148 1098 2148 1059 2149 1097 2149 1098 2149 1063 2150 1061 2150 1099 2150 1061 2151 1098 2151 1099 2151 1064 2152 1063 2152 1100 2152 1063 2153 1099 2153 1100 2153 1065 2154 1064 2154 1101 2154 1064 2155 1100 2155 1101 2155 1066 2156 1065 2156 1102 2156 1065 2157 1101 2157 1102 2157 1067 2158 1066 2158 1103 2158 1066 2159 1102 2159 1103 2159 1068 2160 1067 2160 1079 2160 1067 2161 1103 2161 1079 2161 1011 2162 1047 2162 1045 2162 1011 2163 1045 2163 1043 2163 1011 2164 1043 2164 1041 2164 1011 2165 1041 2165 1039 2165 1011 2166 1039 2166 1037 2166 1011 2167 1037 2167 1035 2167 1011 2168 1035 2168 1033 2168 1011 2169 1033 2169 1031 2169 1011 2170 1031 2170 1029 2170 1011 2171 1029 2171 1027 2171 1011 2172 1027 2172 1025 2172 1011 2173 1025 2173 1023 2173 1011 2174 1023 2174 1021 2174 1011 2175 1021 2175 1019 2175 1011 2176 1019 2176 1017 2176 1011 2177 1017 2177 1015 2177 1011 2178 1015 2178 1013 2178 1049 2179 1047 2179 1011 2179 1051 2180 1049 2180 1011 2180 1007 2181 1011 2181 1009 2181 1053 2182 1051 2182 1011 2182 1006 2183 1011 2183 1007 2183 1006 2184 1053 2184 1011 2184 1089 2185 1088 2185 1090 2185 1083 2186 1082 2186 1085 2186 1091 2187 1090 2187 1092 2187 1086 2188 1083 2188 1084 2188 1083 2189 1085 2189 1084 2189 1084 2190 1081 2190 1080 2190 1093 2191 1092 2191 1095 2191 1094 2192 1093 2192 1095 2192 1087 2193 1086 2193 1079 2193 1088 2194 1087 2194 1079 2194 1090 2195 1088 2195 1079 2195 1086 2196 1084 2196 1079 2196 1092 2197 1090 2197 1079 2197 1084 2198 1080 2198 1079 2198 1096 2199 1095 2199 1098 2199 1097 2200 1096 2200 1098 2200 1103 2201 1102 2201 1101 2201 1079 2202 1103 2202 1101 2202 1099 2203 1098 2203 1100 2203 1092 2204 1079 2204 1100 2204 1095 2205 1092 2205 1100 2205 1079 2206 1101 2206 1100 2206 1098 2207 1095 2207 1100 2207

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae new file mode 100644 index 0000000..c58db53 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_inner_knuckle.dae @@ -0,0 +1,98 @@ + + + 2016-07-18T08:46:47.901362 + 2016-07-18T08:46:47.901368 + Z_UP + + + + + + + + 0.007843 0.007843 0.007843 1 + + + 0.08 0.08 0.08 1 + + + 0.08 0.08 0.08 1 + + + 0.312500 + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.000000 + + + + + + 0 + + + + + + + + + + 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 2.775558e-16 -0.9505075 0.8118101 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.329071e-16 1.824974 -1.558675 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -5.551115e-16 1.901015 -1.62362 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1 -2.461417e-16 5.370255e-17 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 2.220446e-16 -0.760406 0.649448 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -1.332268e-15 4.562436 -3.896688 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 -2.220446e-16 0.760406 -0.649448 2.46519e-32 0.649448 0.760406 2.46519e-32 0.649448 0.760406 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 1 2.392573e-16 -6.176306e-17 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 -1 -2.861995e-16 6.800802e-18 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 -2.46519e-32 -0.649448 -0.760406 -2.46519e-32 -0.649448 -0.760406 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -1.058275e-15 -8.971836e-16 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 -1 -2.627284e-16 3.428193e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.461417e-16 -5.370255e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 1 2.627284e-16 -3.428193e-17 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 -5 -8.442202e-16 7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 5 8.442202e-16 -7.210322e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 3.2 5.403009e-16 -4.614606e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 -1 -1.68844e-16 1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 1 1.68844e-16 -1.442064e-16 + + + + + + + + + + 12 16.70278 19.80951 12 16.51712 20.08076 17 16.65698 19.86347 17 16.49326 20.13063 12 16.95273 19.59603 17 16.88199 19.64542 11.98571 18.71382 20.01857 11.99775 18.58302 19.83321 17 18.58302 19.83321 12 17.24968 19.45509 17 17.15416 19.49017 11.96386 18.81153 20.22983 17 18.75505 20.0951 12 17.57312 19.39643 17 17.45639 19.40749 11.92728 18.87423 20.50419 17 18.85654 20.39154 12 17.90065 19.42412 17 17.76968 19.40257 11.88699 18.87559 20.77617 17 18.88113 20.70391 12 18.20965 19.53623 17 18.07436 19.47572 11.84806 18.81648 21.04505 17 18.82726 21.01257 12 18.47874 19.72502 17 18.35127 19.62233 11.80146 18.52382 21.52118 11.81721 18.69651 21.30081 17 18.69831 21.29815 11.80327 18.3125 21.69356 17 18.50241 21.54268 11.82232 18.06085 21.8193 17 18.25184 21.73081 11.85551 17.78676 21.88514 17 17.96236 21.85072 11.89498 17.51421 21.8894 17 17.65215 21.89487 17 17.34071 21.86048 11.93518 17.24542 21.83327 17 17.0476 21.74973 11.97 16.98869 21.71633 17 16.79125 21.56956 11.99248 16.76636 21.54602 17 16.58776 21.3313 12 16.59146 21.3369 12 16.44709 21.0416 17 16.44991 21.04992 12 16.3847 20.71887 17 16.38637 20.7431 12 16.40859 20.39103 17 16.40113 20.43011 -17 17.15416 19.49017 -17 16.88199 19.64542 -12 16.95273 19.59603 -12 16.70278 19.80951 -17 17.45639 19.40749 -12 17.24968 19.45509 -17 18.75505 20.0951 -17 18.58302 19.83321 -11.98173 18.7383 20.06285 -11.99775 18.58302 19.83321 -17 17.76968 19.40257 -12 17.57312 19.39643 -17 18.85654 20.39154 -11.95165 18.84141 20.32738 -17 18.07436 19.47572 -12 17.90065 19.42412 -17 18.88113 20.70391 -11.91252 18.88166 20.60522 -17 18.35127 19.62233 -12 18.20965 19.53623 -17 18.82726 21.01257 -11.87217 18.86079 20.87591 -12 18.47874 19.72502 -17 18.69831 21.29815 -11.835 18.77836 21.14435 -17 18.50241 21.54268 -11.80923 18.63571 21.39021 -17 18.25184 21.73081 -11.8 18.44675 21.59345 -17 17.96236 21.85072 -11.80881 18.2175 21.74932 -11.83422 17.95295 21.85318 -17 17.65215 21.89487 -11.87123 17.67493 21.89408 -17 17.34071 21.86048 -11.91156 17.40419 21.87378 -11.9508 17.13583 21.79201 -17 17.0476 21.74973 -11.98117 16.88988 21.65011 -17 16.79125 21.56956 -17 16.58776 21.3313 -11.99534 16.72556 21.5051 -17 16.44991 21.04992 -12 16.59146 21.3369 -12 16.44709 21.0416 -17 16.38637 20.7431 -17 16.40113 20.43011 -12 16.3847 20.71887 -17 16.49326 20.13063 -12 16.40859 20.39103 -17 16.65698 19.86347 -12 16.51712 20.08076 12 11.61136 12.56384 17 11.30913 12.64652 17 11.61136 12.56384 12 12.22933 12.63206 12 11.92465 12.55892 17 11.92465 12.55892 12 12.91002 13.25144 12 12.73799 12.98956 17 12.73799 12.98956 12 12.50624 12.77868 17 12.22933 12.63206 12 13.01151 13.54788 17 12.91002 13.25144 17 12.50624 12.77868 12 13.03609 13.86025 17 13.01151 13.54788 12 12.98222 14.16892 17 13.03609 13.86025 12 12.85328 14.45449 17 12.98222 14.16892 12 12.65737 14.69903 17 12.85328 14.45449 12 12.40681 14.88716 17 12.65737 14.69903 12 12.11732 15.00707 17 12.40681 14.88716 12 11.80712 15.05121 17 12.11732 15.00707 12 11.49568 15.01683 17 11.80712 15.05121 12 11.20257 14.90608 17 11.49568 15.01683 12 10.94622 14.72591 17 11.20257 14.90608 17 10.94622 14.72591 12 10.74272 14.48765 17 10.74272 14.48765 12 10.60488 14.20627 17 10.60488 14.20627 12 10.54134 13.89944 12 10.5561 13.58646 17 10.54134 13.89944 12 10.64823 13.28698 17 10.5561 13.58646 12 10.81194 13.01981 17 10.64823 13.28698 12 11.03696 12.80176 17 10.81194 13.01981 12 11.30913 12.64652 17 11.03696 12.80176 -17 11.03696 12.80176 -17 10.81194 13.01981 -12 11.03696 12.80176 -12 10.81194 13.01981 -17 11.30913 12.64652 -12 11.30913 12.64652 -17 11.61136 12.56384 -12 11.61136 12.56384 -17 12.91002 13.25144 -17 12.73799 12.98956 -12 12.91002 13.25144 -12 12.73799 12.98956 -17 11.92465 12.55892 -12 11.92465 12.55892 -17 13.01151 13.54788 -12 13.01151 13.54788 -17 12.22933 12.63206 -12 12.22933 12.63206 -17 13.03609 13.86025 -12 13.03609 13.86025 -17 12.50624 12.77868 -12 12.50624 12.77868 -17 12.98222 14.16892 -12 12.98222 14.16892 -17 12.85328 14.45449 -12 12.85328 14.45449 -17 12.65737 14.69903 -12 12.65737 14.69903 -17 12.40681 14.88716 -12 12.40681 14.88716 -17 12.11732 15.00707 -12 12.11732 15.00707 -17 11.80712 15.05121 -12 11.80712 15.05121 -17 11.49568 15.01683 -12 11.49568 15.01683 -17 11.20257 14.90608 -12 11.20257 14.90608 -12 10.94622 14.72591 -17 10.94622 14.72591 -12 10.74272 14.48765 -17 10.74272 14.48765 -12 10.60488 14.20627 -17 10.60488 14.20627 -17 10.54134 13.89944 -12 10.54134 13.89944 -17 10.5561 13.58646 -12 10.5561 13.58646 -17 10.64823 13.28698 -12 10.64823 13.28698 7.5 37.39029 40.9723 -7.5 37.39029 40.9723 -7.5 37.99964 41.11859 7.5 36.7637 40.98214 7.5 39.01697 41.83358 -7.5 39.01697 41.83358 -7.5 39.36102 42.35735 7.5 37.99964 41.11859 -7.5 38.55347 41.41183 7.5 39.36102 42.35735 -7.5 39.56401 42.95023 7.5 38.55347 41.41183 7.5 39.56401 42.95023 -7.5 39.61318 43.57497 7.5 39.61318 43.57497 -7.5 39.50544 44.1923 7.5 39.50544 44.1923 -7.5 39.24756 44.76345 7.5 39.24756 44.76345 -7.5 38.85574 45.25252 7.5 38.85574 45.25252 -7.5 38.3546 45.62878 7.5 38.3546 45.62878 -7.5 37.77564 45.86859 7.5 37.77564 45.86859 -7.5 37.15522 45.95689 7.5 37.15522 45.95689 -7.5 36.53234 45.88813 7.5 36.53234 45.88813 -7.5 35.94613 45.66662 7.5 35.94613 45.66662 -7.5 35.43342 45.30628 7.5 35.43342 45.30628 -7.5 35.02644 44.82976 7.5 35.02644 44.82976 -7.5 34.75074 44.26699 7.5 34.75074 44.26699 -7.5 34.62366 43.65335 7.5 34.62366 43.65335 -7.5 34.65318 43.02738 7.5 34.65318 43.02738 -7.5 34.83745 42.42842 7.5 34.83745 42.42842 -7.5 35.16488 41.89409 7.5 35.16488 41.89409 -7.5 35.61491 41.45799 7.5 35.61491 41.45799 -7.5 36.15925 41.1475 7.5 36.15925 41.1475 -7.5 36.7637 40.98214 -12 35.67495 41.53796 -12.7 35.24292 41.95662 -12.7 35.67495 41.53796 -12.7 36.19752 41.23989 -12 35.24292 41.95662 -12 36.19752 41.23989 -12 36.77779 41.08114 -12.7 36.77779 41.08114 -12.7 37.37932 41.07169 -12 39.27122 42.40135 -12.7 38.94093 41.89853 -12.7 39.27122 42.40135 -12 38.94093 41.89853 -12 37.37932 41.07169 -12 39.46609 42.97051 -12.7 39.46609 42.97051 -12 37.9643 41.21214 -12.7 37.9643 41.21214 -12 39.51329 43.57026 -12.7 39.51329 43.57026 -12 38.49597 41.49364 -12.7 38.49597 41.49364 -12 39.40986 44.1629 -12.7 39.40986 44.1629 -12.7 39.16229 44.7112 -12 39.16229 44.7112 -12 38.78615 45.1807 -12.7 38.78615 45.1807 -12 38.30506 45.54192 -12.7 38.30506 45.54192 -12 37.74925 45.77214 -12.7 37.74925 45.77214 -12 37.15365 45.8569 -12.7 37.15365 45.8569 -12 36.55569 45.79089 -12.7 36.55569 45.79089 -12 35.99292 45.57824 -12.7 35.99292 45.57824 -12 35.50073 45.23232 -12.7 35.50073 45.23232 -12 35.11002 44.77486 -12.7 35.11002 44.77486 -12 34.84535 44.2346 -12.7 34.84535 44.2346 -12 34.72335 43.6455 -12.7 34.72335 43.6455 -12 34.75169 43.04457 -12.7 34.75169 43.04457 -12.7 34.92859 42.46957 -12 34.92859 42.46957 -12.7 36.15925 41.1475 -13.5 36.15925 41.1475 -13.5 36.7637 40.98214 -12.7 35.61491 41.45799 -12.7 36.7637 40.98214 -12.7 37.39029 40.9723 -13.5 37.39029 40.9723 -12.7 39.36102 42.35735 -13.5 39.01697 41.83358 -13.5 39.36102 42.35735 -12.7 39.01697 41.83358 -12.7 37.99964 41.11859 -13.5 37.99964 41.11859 -12.7 39.56401 42.95023 -13.5 39.56401 42.95023 -12.7 38.55347 41.41183 -13.5 38.55347 41.41183 -12.7 39.61318 43.57497 -13.5 39.61318 43.57497 -12.7 39.50544 44.1923 -13.5 39.50544 44.1923 -12.7 39.24756 44.76345 -13.5 39.24756 44.76345 -12.7 38.85574 45.25252 -13.5 38.85574 45.25252 -13.5 38.3546 45.62878 -12.7 38.3546 45.62878 -13.5 37.77564 45.86859 -12.7 37.77564 45.86859 -12.7 37.15522 45.95689 -13.5 37.15522 45.95689 -13.5 36.53234 45.88813 -12.7 36.53234 45.88813 -12.7 35.94613 45.66662 -13.5 35.94613 45.66662 -13.5 35.43342 45.30628 -12.7 35.43342 45.30628 -13.5 35.02644 44.82976 -12.7 35.02644 44.82976 -13.5 34.75074 44.26699 -12.7 34.75074 44.26699 -13.5 34.62366 43.65335 -12.7 34.62366 43.65335 -12.7 34.65318 43.02738 -13.5 34.65318 43.02738 -13.5 34.83745 42.42842 -12.7 34.83745 42.42842 -12.7 35.16488 41.89409 -13.5 35.16488 41.89409 -13.5 35.61491 41.45799 12.7 36.19752 41.23989 12 36.19752 41.23989 12 36.77779 41.08114 12.7 35.67495 41.53796 12.7 36.77779 41.08114 12 37.37932 41.07169 12.7 37.37932 41.07169 12 37.9643 41.21214 12.7 39.27122 42.40135 12 38.94093 41.89853 12 39.27122 42.40135 12.7 38.94093 41.89853 12.7 37.9643 41.21214 12 38.49597 41.49364 12.7 39.46609 42.97051 12 39.46609 42.97051 12.7 38.49597 41.49364 12.7 39.51329 43.57026 12 39.51329 43.57026 12.7 39.40986 44.1629 12 39.40986 44.1629 12.7 39.16229 44.7112 12 39.16229 44.7112 12.7 38.78615 45.1807 12 38.78615 45.1807 12.7 38.30506 45.54192 12 38.30506 45.54192 12 37.74925 45.77214 12.7 37.74925 45.77214 12.7 37.15365 45.8569 12 37.15365 45.8569 12.7 36.55569 45.79089 12 36.55569 45.79089 12 35.99292 45.57824 12.7 35.99292 45.57824 12.7 35.50073 45.23232 12 35.50073 45.23232 12 35.11002 44.77486 12.7 35.11002 44.77486 12 34.84535 44.2346 12.7 34.84535 44.2346 12.7 34.72335 43.6455 12 34.72335 43.6455 12.7 34.75169 43.04457 12 34.75169 43.04457 12 34.92859 42.46957 12.7 34.92859 42.46957 12 35.24292 41.95662 12.7 35.24292 41.95662 12 35.67495 41.53796 13.5 36.15925 41.1475 12.7 35.61491 41.45799 12.7 36.15925 41.1475 13.5 35.61491 41.45799 13.5 36.7637 40.98214 12.7 36.7637 40.98214 12.7 37.39029 40.9723 13.5 39.36102 42.35735 12.7 39.01697 41.83358 12.7 39.36102 42.35735 13.5 37.39029 40.9723 13.5 39.01697 41.83358 13.5 37.99964 41.11859 12.7 37.99964 41.11859 13.5 39.56401 42.95023 12.7 39.56401 42.95023 12.7 39.61318 43.57497 13.5 38.55347 41.41183 12.7 38.55347 41.41183 13.5 39.61318 43.57497 12.7 39.50544 44.1923 13.5 39.50544 44.1923 12.7 39.24756 44.76345 13.5 39.24756 44.76345 13.5 38.85574 45.25252 12.7 38.85574 45.25252 12.7 38.3546 45.62878 13.5 38.3546 45.62878 13.5 37.77564 45.86859 12.7 37.77564 45.86859 12.7 37.15522 45.95689 13.5 37.15522 45.95689 13.5 36.53234 45.88813 12.7 36.53234 45.88813 13.5 35.94613 45.66662 12.7 35.94613 45.66662 13.5 35.43342 45.30628 12.7 35.43342 45.30628 13.5 35.02644 44.82976 12.7 35.02644 44.82976 13.5 34.75074 44.26699 12.7 34.75074 44.26699 12.7 34.62366 43.65335 13.5 34.62366 43.65335 13.5 34.65318 43.02738 12.7 34.65318 43.02738 12.7 34.83745 42.42842 13.5 34.83745 42.42842 13.5 35.16488 41.89409 12.7 35.16488 41.89409 -12 39.16133 44.89471 -12 38.73958 45.35822 -12 37.54578 40.99443 -12 36.91981 40.96491 -12 34.94438 44.69585 -12 35.32064 45.19698 -12 38.14474 41.17869 -12 36.30616 41.09199 -12 38.2158 45.70227 -12 38.67906 41.50612 -12 35.80971 45.5888 -12 35.7434 41.36768 -12 37.62292 45.90526 -12 36.38086 45.84668 -12 39.11517 41.95615 -12 36.99819 45.95443 -12 35.26688 41.77467 -12 39.42565 42.50049 -12 34.90654 42.28738 -12 39.59102 43.10495 -12 34.68503 42.87359 -12 39.60086 43.73154 -12 34.61626 43.49647 -12 39.45457 44.34089 -12 34.70456 44.11688 12 35.55285 45.40828 12 39.61565 43.41793 12 39.54688 44.04081 12 36.01611 41.21213 12 35.49234 41.55619 12 35.11674 44.95825 12 39.52735 42.79752 12 39.32537 44.62703 12 35.07058 42.01969 12 39.28753 42.21855 12 34.80626 44.41391 12 38.96503 45.13973 12 34.77735 42.57351 12 38.91127 41.71742 12 38.48851 45.54672 12 34.6409 43.80945 12 34.63105 43.18287 12 38.4222 41.3256 12 37.92575 45.82241 12 37.85106 41.06772 12 37.3121 45.94949 12 37.23372 40.95998 12 36.68613 45.91997 12 36.60899 41.00914 12 36.08717 45.73571 -17 13.08482 6.081738 -17 3.959946 13.87511 -17 27.16334 22.56557 -17 18.03846 30.35894 -12 0.4707546 -5.981504 -12 -0.3140157 -5.991777 -19.5 0.4707546 -5.981504 -12 1.24747 -5.868886 -19.5 1.24747 -5.868886 -19.5 2.002841 -5.655849 -12 -5.032023 3.267834 -12 -4.562436 3.896688 -19.5 -4.562436 3.896688 -19.5 -5.032023 3.267834 -12 2.002841 -5.655849 -12 2.723943 -5.346039 -19.5 2.723943 -5.346039 -12 -5.415512 2.583067 -19.5 -5.415512 2.583067 -12 3.398437 -4.944757 -19.5 3.398437 -4.944757 -19.5 4.014784 -4.458869 -12 -5.706339 1.854102 -19.5 -5.706339 1.854102 -12 4.014784 -4.458869 -19.5 4.562436 -3.896688 -12 4.562436 -3.896688 -12 -5.899529 1.093413 -19.5 -5.899529 1.093413 -12 -5.991777 0.3140157 -19.5 -5.991777 0.3140157 -12 -5.981504 -0.4707546 -19.5 -5.981504 -0.4707546 -12 -5.868886 -1.24747 -19.5 -5.868886 -1.24747 -12 -5.655849 -2.002841 -19.5 -5.655849 -2.002841 -12 -5.346039 -2.723943 -19.5 -5.346039 -2.723943 -12 -4.944757 -3.398437 -19.5 -4.944757 -3.398437 -12 -4.458869 -4.014784 -19.5 -4.458869 -4.014784 -12 -3.896688 -4.562436 -19.5 -3.896688 -4.562436 -12 -3.267834 -5.032023 -19.5 -3.267834 -5.032023 -19.5 -2.583067 -5.415512 -12 -2.583067 -5.415512 -12 -1.854102 -5.706339 -19.5 -1.854102 -5.706339 -19.5 -1.093413 -5.899529 -12 -1.093413 -5.899529 -19.5 -0.3140157 -5.991777 -7.5 36.6452 49.4387 -12 37.42997 49.44898 -12 36.6452 49.4387 -7.5 37.42997 49.44898 -7.5 35.86849 49.32609 -12 35.86849 49.32609 -7.5 41.67839 39.56051 -12 41.67839 39.56051 -12 42.14798 40.18937 -7.5 35.11311 49.11305 -12 35.11311 49.11305 -7.5 42.14798 40.18937 -12 42.53147 40.87413 -7.5 34.39201 48.80324 -12 34.39201 48.80324 -7.5 42.53147 40.87413 -12 42.8223 41.6031 -7.5 33.71752 48.40196 -12 33.71752 48.40196 -7.5 42.8223 41.6031 -12 43.01549 42.36379 -7.5 33.10117 47.91607 -12 33.10117 47.91607 -7.5 43.01549 42.36379 -12 43.10773 43.14319 -7.5 32.55352 47.35389 -12 32.55352 47.35389 -7.5 43.10773 43.14319 -12 43.09746 43.92796 -7.5 43.09746 43.92796 -7.5 42.98484 44.70467 -12 42.98484 44.70467 -7.5 42.7718 45.46004 -12 42.7718 45.46004 -7.5 42.462 46.18114 -12 42.462 46.18114 -7.5 42.06071 46.85564 -12 42.06071 46.85564 -7.5 41.57482 47.47198 -12 41.57482 47.47198 -7.5 41.01264 48.01964 -12 41.01264 48.01964 -7.5 40.38379 48.48922 -12 40.38379 48.48922 -7.5 39.69902 48.87271 -12 39.69902 48.87271 -7.5 38.97006 49.16354 -12 38.97006 49.16354 -7.5 38.20937 49.35673 -12 38.20937 49.35673 -19.5 0.1315058 9.392588 -19.5 9.256377 1.599211 19.5 -0.3140157 -5.991777 19.5 0.4707546 -5.981504 19.5 -1.093413 -5.899529 19.5 -2.583067 -5.415512 19.5 -1.854102 -5.706339 19.5 -3.267834 -5.032023 19.5 3.398437 -4.944757 19.5 4.014784 -4.458869 19.5 4.562436 -3.896688 19.5 2.723943 -5.346039 19.5 2.002841 -5.655849 19.5 1.24747 -5.868886 19.5 -3.896688 -4.562436 19.5 -4.944757 -3.398437 19.5 -4.458869 -4.014784 19.5 -5.346039 -2.723943 19.5 -5.655849 -2.002841 19.5 -5.868886 -1.24747 19.5 -5.981504 -0.4707546 19.5 -5.991777 0.3140157 19.5 -5.899529 1.093413 19.5 -5.706339 1.854102 19.5 -5.032023 3.267834 19.5 -5.415512 2.583067 19.5 -4.562436 3.896688 19.5 9.256377 1.599211 19.5 0.1315058 9.392588 12 -0.3140157 -5.991777 12 0.4707546 -5.981504 12 1.24747 -5.868886 12 -4.562436 3.896688 12 -5.032023 3.267834 12 2.002841 -5.655849 12 -5.415512 2.583067 12 2.723943 -5.346039 12 -5.706339 1.854102 12 3.398437 -4.944757 12 -5.899529 1.093413 12 4.014784 -4.458869 12 4.562436 -3.896688 12 -5.991777 0.3140157 12 -5.981504 -0.4707546 12 -5.868886 -1.24747 12 -5.655849 -2.002841 12 -5.346039 -2.723943 12 -4.944757 -3.398437 12 -4.458869 -4.014784 12 -3.896688 -4.562436 12 -3.267834 -5.032023 12 -2.583067 -5.415512 12 -1.854102 -5.706339 12 -1.093413 -5.899529 -9.5 15.78485 27.7203 -16.1687 19.83145 32.45826 -16.5265 19.41781 31.97395 5.9 21.14189 33.99258 5.128221 20.93427 33.74949 7 16.2199 28.22968 4.3 20.86346 33.66658 8.294095 16.10925 28.10013 17 18.03846 30.35894 11.82963 13.81311 25.41169 12 12.97266 24.42765 12 32.55352 47.35389 7.5 32.55352 47.35389 12 22.94169 36.09988 -7.5 22.94169 36.09988 -16.78767 18.97472 31.45515 -4.3 20.86346 33.66658 -16.94663 18.51164 30.91296 -11.33013 14.59628 26.32866 -10.53553 15.26881 27.11609 -11.82963 13.81311 25.41169 -7.390963 22.4038 35.4701 -12 22.94169 36.09988 17 3.959946 13.87511 -12 12.97266 24.42765 17.97561 2.46592 12.12584 17.44682 2.900726 12.63493 17.11373 3.41082 13.23217 -7.071281 21.90257 34.88323 -12.13589 22.34249 35.3983 7.5 22.94169 36.09988 7.390963 22.4038 35.4701 -6.562742 21.47216 34.37928 -12.53203 21.79418 34.75632 12.13589 22.34249 35.3983 12.53203 21.79418 34.75632 7.071281 21.90257 34.88323 6.562742 21.47216 34.37928 -17.11373 3.41082 13.23217 -17.44682 2.900726 12.63493 13.15477 21.34333 34.22844 -17.97561 2.46592 12.12584 -18.80184 1.786536 11.33038 -19.3223 0.9895141 10.39719 -13.15477 21.34333 34.22844 19.3223 0.9895141 10.39719 18.80184 1.786536 11.33038 -5.128221 20.93427 33.74949 -7 16.2199 28.22968 -5.9 21.14189 33.99258 -8.294095 16.10925 28.10013 16.94663 18.51164 30.91296 9.5 15.78485 27.7203 16.78767 18.97472 31.45515 16.5265 19.41781 31.97395 16.1687 19.83145 32.45826 15.72191 20.20682 32.89776 10.53553 15.26881 27.11609 15.19567 20.5359 33.28307 14.60121 20.81167 33.60595 13.95122 21.02824 33.85951 11.33013 14.59628 26.32866 -13.95122 21.02824 33.85951 -14.60121 20.81167 33.60595 -15.19567 20.5359 33.28307 -15.72191 20.20682 32.89776 12 36.6452 49.4387 12 37.42997 49.44898 7.5 37.42997 49.44898 7.5 36.6452 49.4387 12 35.86849 49.32609 12 41.67839 39.56051 7.5 41.67839 39.56051 7.5 42.14798 40.18937 7.5 35.86849 49.32609 12 35.11311 49.11305 12 42.14798 40.18937 7.5 42.53147 40.87413 7.5 35.11311 49.11305 12 34.39201 48.80324 12 42.53147 40.87413 7.5 42.8223 41.6031 7.5 34.39201 48.80324 12 33.71752 48.40196 7.5 33.71752 48.40196 12 42.8223 41.6031 7.5 43.01549 42.36379 12 33.10117 47.91607 7.5 33.10117 47.91607 12 43.01549 42.36379 7.5 43.10773 43.14319 12 43.10773 43.14319 7.5 43.09746 43.92796 12 43.09746 43.92796 12 42.98484 44.70467 7.5 42.98484 44.70467 12 42.7718 45.46004 7.5 42.7718 45.46004 12 42.462 46.18114 7.5 42.462 46.18114 12 42.06071 46.85564 7.5 42.06071 46.85564 12 41.57482 47.47198 7.5 41.57482 47.47198 12 41.01264 48.01964 7.5 41.01264 48.01964 12 40.38379 48.48922 7.5 40.38379 48.48922 12 39.69902 48.87271 7.5 39.69902 48.87271 12 38.97006 49.16354 7.5 38.97006 49.16354 12 38.20937 49.35673 7.5 38.20937 49.35673 -17.44682 12.0256 4.841552 -17.11373 12.53569 5.438795 -9.5 24.90973 19.92693 -16.94663 27.63651 23.11958 -16.78767 28.09959 23.66178 -8.294095 25.23413 20.30675 -13.15477 30.4682 26.43506 -6.562742 30.59703 26.5859 19.3223 10.11439 2.60381 18.80184 10.91141 3.537003 -7.071281 31.02744 27.08985 -12.53203 30.91905 26.96294 17.97561 11.59079 4.332459 12.53203 30.91905 26.96294 13.15477 30.4682 26.43506 6.562742 30.59703 26.5859 -13.95122 30.15311 26.06614 8.294095 25.23413 20.30675 17.44682 12.0256 4.841552 -16.5265 28.54268 24.18057 7 25.34477 20.4363 5.9 30.26676 26.19921 -12.13589 31.46736 27.60493 17.11373 12.53569 5.438795 12.13589 31.46736 27.60493 7.071281 31.02744 27.08985 -7.390963 31.52867 27.67672 17 13.08482 6.081738 -14.60121 29.93654 25.81257 12 32.06656 28.3065 7.390963 31.52867 27.67672 -16.1687 28.95632 24.66488 -15.19567 29.66077 25.48969 5.128221 30.05914 25.95612 -15.72191 29.33169 25.10439 12 22.09753 16.63427 11.82963 22.93798 17.61831 17 27.16334 22.56557 4.3 29.98833 25.87321 -12 32.06656 28.3065 7.5 32.06656 28.3065 11.33013 23.72115 18.53529 -7.5 32.06656 28.3065 10.53553 24.39368 19.32271 -12 22.09753 16.63427 9.5 24.90973 19.92693 16.1687 28.95632 24.66488 16.5265 28.54268 24.18057 -7 25.34477 20.4363 -4.3 29.98833 25.87321 16.78767 28.09959 23.66178 16.94663 27.63651 23.11958 15.72191 29.33169 25.10439 -5.128221 30.05914 25.95612 15.19567 29.66077 25.48969 14.60121 29.93654 25.81257 -5.9 30.26676 26.19921 13.95122 30.15311 26.06614 -19.3223 10.11439 2.60381 -18.80184 10.91141 3.537003 -17.97561 11.59079 4.332459 -10.53553 24.39368 19.32271 -11.33013 23.72115 18.53529 -11.82963 22.93798 17.61831 + + + + + + + + + + + + + + +

0 0 1 0 2 0 1 1 3 1 2 1 4 2 0 2 5 2 6 3 7 3 8 3 0 4 2 4 5 4 9 5 4 5 10 5 11 6 6 6 12 6 4 7 5 7 10 7 6 8 8 8 12 8 13 9 9 9 14 9 15 10 11 10 16 10 9 11 10 11 14 11 11 12 12 12 16 12 17 13 13 13 18 13 19 14 15 14 20 14 13 15 14 15 18 15 15 16 16 16 20 16 21 17 17 17 22 17 17 18 18 18 22 18 23 19 19 19 24 19 19 20 20 20 24 20 25 21 21 21 26 21 21 22 22 22 26 22 7 23 25 23 8 23 25 24 26 24 8 24 27 25 28 25 29 25 28 26 23 26 29 26 23 27 24 27 29 27 30 28 27 28 31 28 27 29 29 29 31 29 32 30 30 30 33 30 30 31 31 31 33 31 34 32 32 32 35 32 32 33 33 33 35 33 36 34 34 34 37 34 34 35 35 35 37 35 36 36 37 36 38 36 39 37 36 37 38 37 39 38 38 38 40 38 41 39 39 39 40 39 41 40 40 40 42 40 43 41 41 41 42 41 43 42 42 42 44 42 45 43 43 43 44 43 46 44 45 44 47 44 45 45 44 45 47 45 48 46 46 46 49 46 46 47 47 47 49 47 50 48 48 48 51 48 48 49 49 49 51 49 1 50 50 50 3 50 50 51 51 51 3 51 52 52 53 52 54 52 53 53 55 53 54 53 56 54 52 54 57 54 52 55 54 55 57 55 58 56 59 56 60 56 59 57 61 57 60 57 62 58 56 58 63 58 56 59 57 59 63 59 64 60 58 60 65 60 58 61 60 61 65 61 66 62 62 62 67 62 62 63 63 63 67 63 68 64 64 64 69 64 64 65 65 65 69 65 70 66 66 66 71 66 66 67 67 67 71 67 72 68 68 68 73 68 68 69 69 69 73 69 59 70 70 70 74 70 70 71 71 71 74 71 59 72 74 72 61 72 75 73 72 73 76 73 72 74 73 74 76 74 77 75 75 75 78 75 75 76 76 76 78 76 79 77 77 77 80 77 77 78 78 78 80 78 81 79 79 79 82 79 79 80 80 80 82 80 81 81 82 81 83 81 84 82 81 82 85 82 81 83 83 83 85 83 86 84 84 84 87 84 84 85 85 85 87 85 86 86 87 86 88 86 89 87 86 87 88 87 89 88 88 88 90 88 91 89 89 89 90 89 92 90 91 90 93 90 91 91 90 91 93 91 94 92 92 92 95 92 92 93 93 93 95 93 94 94 95 94 96 94 97 95 94 95 96 95 98 96 97 96 99 96 97 97 96 97 99 97 100 98 98 98 101 98 98 99 99 99 101 99 102 100 100 100 103 100 100 101 101 101 103 101 53 102 102 102 55 102 102 103 103 103 55 103 104 104 105 104 106 104 107 105 108 105 109 105 108 106 106 106 109 106 110 107 111 107 112 107 113 108 107 108 114 108 107 109 109 109 114 109 115 110 110 110 116 110 110 111 112 111 116 111 111 112 113 112 117 112 113 113 114 113 117 113 111 114 117 114 112 114 118 115 115 115 119 115 115 116 116 116 119 116 120 117 118 117 121 117 118 118 119 118 121 118 122 119 120 119 123 119 120 120 121 120 123 120 124 121 122 121 125 121 122 122 123 122 125 122 126 123 124 123 127 123 124 124 125 124 127 124 128 125 126 125 129 125 126 126 127 126 129 126 130 127 128 127 131 127 128 128 129 128 131 128 132 129 130 129 133 129 130 130 131 130 133 130 134 131 132 131 135 131 132 132 133 132 135 132 136 133 134 133 137 133 134 134 135 134 137 134 136 135 137 135 138 135 139 136 136 136 138 136 139 137 138 137 140 137 141 138 139 138 140 138 141 139 140 139 142 139 143 140 141 140 142 140 144 141 143 141 145 141 143 142 142 142 145 142 146 143 144 143 147 143 144 144 145 144 147 144 148 145 146 145 149 145 146 146 147 146 149 146 150 147 148 147 151 147 148 148 149 148 151 148 152 149 150 149 153 149 150 150 151 150 153 150 104 151 152 151 105 151 152 152 153 152 105 152 108 153 104 153 106 153 154 154 155 154 156 154 155 155 157 155 156 155 158 156 154 156 159 156 154 157 156 157 159 157 160 158 158 158 161 158 162 159 163 159 164 159 158 160 159 160 161 160 163 161 165 161 164 161 166 162 160 162 167 162 168 163 162 163 169 163 160 164 161 164 167 164 162 165 164 165 169 165 170 166 166 166 171 166 166 167 167 167 171 167 172 168 168 168 173 168 168 169 169 169 173 169 174 170 170 170 175 170 170 171 171 171 175 171 176 172 172 172 177 172 172 173 173 173 177 173 163 174 174 174 165 174 174 175 175 175 165 175 178 176 176 176 179 176 176 177 177 177 179 177 180 178 178 178 181 178 178 179 179 179 181 179 182 180 180 180 183 180 180 181 181 181 183 181 184 182 182 182 185 182 182 183 183 183 185 183 186 184 184 184 187 184 184 185 185 185 187 185 188 186 186 186 189 186 186 187 187 187 189 187 190 188 188 188 191 188 188 189 189 189 191 189 190 190 191 190 192 190 193 191 190 191 192 191 193 192 192 192 194 192 195 193 193 193 194 193 195 194 194 194 196 194 197 195 195 195 196 195 198 196 197 196 199 196 197 197 196 197 199 197 200 198 198 198 201 198 198 199 199 199 201 199 202 200 200 200 203 200 200 201 201 201 203 201 155 202 202 202 157 202 202 203 203 203 157 203 204 204 205 204 206 204 204 205 207 205 205 205 208 206 209 206 210 206 211 207 206 207 212 207 211 208 204 208 206 208 213 209 210 209 214 209 213 210 208 210 210 210 215 211 212 211 209 211 215 212 211 212 212 212 208 213 215 213 209 213 216 214 214 214 217 214 216 215 213 215 214 215 218 216 217 216 219 216 218 217 216 217 217 217 220 218 219 218 221 218 220 219 218 219 219 219 222 220 221 220 223 220 222 221 220 221 221 221 224 222 223 222 225 222 224 223 222 223 223 223 226 224 225 224 227 224 226 225 224 225 225 225 228 226 227 226 229 226 228 227 226 227 227 227 230 228 229 228 231 228 230 229 228 229 229 229 232 230 231 230 233 230 232 231 230 231 231 231 234 232 233 232 235 232 234 233 232 233 233 233 236 234 234 234 235 234 236 235 235 235 237 235 238 236 236 236 237 236 238 237 237 237 239 237 240 238 239 238 241 238 240 239 238 239 239 239 242 240 241 240 243 240 242 241 240 241 241 241 244 242 243 242 245 242 244 243 242 243 243 243 246 244 245 244 247 244 246 245 244 245 245 245 248 246 247 246 249 246 248 247 246 247 247 247 250 248 249 248 251 248 250 249 248 249 249 249 252 250 251 250 253 250 252 251 250 251 251 251 207 252 253 252 205 252 207 253 252 253 253 253 254 254 255 254 256 254 254 255 256 255 257 255 254 256 258 256 255 256 259 257 254 257 257 257 260 258 257 258 261 258 260 259 261 259 262 259 260 260 259 260 257 260 263 261 264 261 265 261 263 262 266 262 264 262 267 263 260 263 262 263 268 264 265 264 269 264 268 265 263 265 265 265 270 266 262 266 271 266 270 267 267 267 262 267 272 268 269 268 273 268 272 269 268 269 269 269 274 270 271 270 275 270 274 271 275 271 264 271 274 272 270 272 271 272 266 273 274 273 264 273 276 274 273 274 277 274 276 275 277 275 278 275 276 276 272 276 273 276 279 277 276 277 278 277 280 278 278 278 281 278 280 279 279 279 278 279 282 280 281 280 283 280 282 281 280 281 281 281 284 282 283 282 285 282 284 283 282 283 283 283 286 284 285 284 287 284 286 285 284 285 285 285 288 286 287 286 289 286 288 287 286 287 287 287 290 288 289 288 291 288 290 289 288 289 289 289 292 290 290 290 291 290 292 291 291 291 293 291 294 292 292 292 293 292 294 293 293 293 295 293 296 294 294 294 295 294 296 295 295 295 297 295 298 296 297 296 299 296 298 297 296 297 297 297 300 298 299 298 301 298 300 299 301 299 302 299 300 300 298 300 299 300 303 301 300 301 302 301 258 302 302 302 255 302 258 303 303 303 302 303 304 304 305 304 306 304 304 305 307 305 305 305 308 306 304 306 306 306 309 307 306 307 310 307 311 308 312 308 313 308 309 309 308 309 306 309 311 310 314 310 312 310 315 311 310 311 316 311 315 312 309 312 310 312 317 313 313 313 318 313 317 314 311 314 313 314 319 315 316 315 320 315 319 316 315 316 316 316 321 317 318 317 322 317 321 318 317 318 318 318 314 319 320 319 312 319 314 320 319 320 320 320 323 321 322 321 324 321 323 322 321 322 322 322 325 323 324 323 326 323 325 324 323 324 324 324 327 325 326 325 328 325 327 326 328 326 329 326 327 327 325 327 326 327 330 328 329 328 331 328 330 329 327 329 329 329 332 330 330 330 331 330 333 331 331 331 334 331 333 332 334 332 335 332 333 333 332 333 331 333 336 334 333 334 335 334 337 335 335 335 338 335 337 336 338 336 339 336 337 337 336 337 335 337 340 338 337 338 339 338 340 339 339 339 341 339 342 340 341 340 343 340 342 341 340 341 341 341 344 342 342 342 343 342 344 343 343 343 345 343 346 344 344 344 345 344 347 345 345 345 348 345 347 346 348 346 349 346 347 347 346 347 345 347 350 348 347 348 349 348 351 349 349 349 352 349 351 350 350 350 349 350 307 351 352 351 353 351 307 352 353 352 305 352 307 353 351 353 352 353 354 354 355 354 356 354 354 355 357 355 355 355 358 356 356 356 359 356 358 357 354 357 356 357 360 358 359 358 361 358 362 359 363 359 364 359 360 360 358 360 359 360 362 361 365 361 363 361 366 362 361 362 367 362 366 363 360 363 361 363 368 364 364 364 369 364 368 365 362 365 364 365 370 366 367 366 363 366 370 367 366 367 367 367 371 368 369 368 372 368 365 369 370 369 363 369 371 370 368 370 369 370 373 371 372 371 374 371 373 372 371 372 372 372 375 373 374 373 376 373 375 374 373 374 374 374 377 375 376 375 378 375 377 376 375 376 376 376 379 377 378 377 380 377 379 378 380 378 381 378 379 379 377 379 378 379 382 380 379 380 381 380 383 381 381 381 384 381 383 382 382 382 381 382 385 383 384 383 386 383 385 384 386 384 387 384 385 385 383 385 384 385 388 386 385 386 387 386 389 387 388 387 387 387 389 388 387 388 390 388 389 389 390 389 391 389 392 390 389 390 391 390 392 391 391 391 393 391 394 392 392 392 393 392 395 393 394 393 393 393 395 394 393 394 396 394 397 395 396 395 398 395 397 396 395 396 396 396 397 397 398 397 399 397 400 398 399 398 401 398 400 399 397 399 399 399 402 400 401 400 403 400 402 401 400 401 401 401 357 402 403 402 355 402 357 403 402 403 403 403 404 404 405 404 406 404 404 405 407 405 405 405 408 406 406 406 409 406 408 407 409 407 410 407 408 408 404 408 406 408 411 409 412 409 413 409 414 410 408 410 410 410 411 411 415 411 412 411 416 412 410 412 417 412 418 413 413 413 419 413 416 414 414 414 410 414 418 415 419 415 420 415 418 416 411 416 413 416 421 417 417 417 422 417 421 418 422 418 412 418 421 419 416 419 417 419 423 420 420 420 424 420 423 421 418 421 420 421 415 422 421 422 412 422 425 423 424 423 426 423 425 424 423 424 424 424 427 425 425 425 426 425 428 426 426 426 429 426 428 427 429 427 430 427 428 428 427 428 426 428 431 429 428 429 430 429 432 430 430 430 433 430 432 431 433 431 434 431 432 432 431 432 430 432 435 433 432 433 434 433 436 434 434 434 437 434 436 435 435 435 434 435 438 436 437 436 439 436 438 437 436 437 437 437 440 438 438 438 439 438 440 439 439 439 441 439 442 440 440 440 441 440 442 441 441 441 443 441 444 442 442 442 443 442 444 443 443 443 445 443 444 444 445 444 446 444 447 445 444 445 446 445 448 446 446 446 449 446 448 447 449 447 450 447 448 448 447 448 446 448 451 449 448 449 450 449 452 450 450 450 453 450 452 451 453 451 405 451 452 452 451 452 450 452 407 453 452 453 405 453 454 454 279 454 280 454 454 455 280 455 455 455 456 456 457 456 267 456 294 457 458 457 459 457 267 458 457 458 260 458 294 459 459 459 292 459 460 460 456 460 270 460 456 461 267 461 270 461 455 462 280 462 282 462 260 463 457 463 461 463 455 464 282 464 462 464 260 465 461 465 259 465 463 466 460 466 274 466 292 467 459 467 464 467 460 468 270 468 274 468 290 469 292 469 464 469 259 470 461 470 465 470 462 471 282 471 284 471 259 472 465 472 254 472 463 473 274 473 266 473 462 474 284 474 466 474 284 475 286 475 466 475 288 476 290 476 467 476 463 477 266 477 468 477 290 478 464 478 467 478 466 479 286 479 469 479 254 480 465 480 470 480 286 481 288 481 469 481 288 482 467 482 469 482 254 483 470 483 258 483 468 484 266 484 263 484 468 485 263 485 471 485 258 486 470 486 472 486 258 487 472 487 303 487 471 488 263 488 268 488 471 489 268 489 473 489 303 490 472 490 474 490 303 491 474 491 300 491 473 492 268 492 272 492 473 493 272 493 475 493 300 494 474 494 476 494 300 495 476 495 298 495 475 496 272 496 276 496 475 497 276 497 477 497 298 498 476 498 478 498 298 499 478 499 296 499 477 500 276 500 279 500 477 501 279 501 454 501 296 502 478 502 458 502 296 503 458 503 294 503 387 504 479 504 390 504 480 505 481 505 372 505 482 506 355 506 403 506 482 507 403 507 483 507 390 508 479 508 484 508 372 509 481 509 374 509 485 510 480 510 369 510 390 511 484 511 391 511 480 512 372 512 369 512 483 513 403 513 401 513 374 514 481 514 486 514 483 515 401 515 487 515 374 516 486 516 376 516 488 517 485 517 364 517 485 518 369 518 364 518 391 519 484 519 489 519 393 520 391 520 489 520 376 521 486 521 490 521 487 522 401 522 399 522 376 523 490 523 378 523 488 524 364 524 363 524 399 525 398 525 491 525 488 526 363 526 492 526 487 527 399 527 491 527 378 528 490 528 493 528 396 529 393 529 494 529 393 530 489 530 494 530 491 531 398 531 495 531 398 532 396 532 495 532 378 533 493 533 380 533 396 534 494 534 495 534 492 535 363 535 367 535 492 536 367 536 496 536 380 537 493 537 497 537 380 538 497 538 381 538 496 539 367 539 361 539 496 540 361 540 498 540 381 541 497 541 499 541 381 542 499 542 384 542 498 543 361 543 359 543 498 544 359 544 500 544 384 545 499 545 501 545 384 546 501 546 386 546 500 547 359 547 356 547 500 548 356 548 502 548 386 549 501 549 503 549 386 550 503 550 387 550 502 551 356 551 355 551 502 552 355 552 482 552 387 553 503 553 479 553 166 554 504 554 160 554 504 555 166 555 170 555 180 556 182 556 102 556 160 557 504 557 158 557 53 558 180 558 102 558 504 559 170 559 174 559 102 560 182 560 100 560 158 561 504 561 154 561 182 562 184 562 100 562 504 563 174 563 163 563 100 564 184 564 98 564 184 565 186 565 98 565 504 566 163 566 162 566 98 567 186 567 97 567 186 568 188 568 97 568 504 569 162 569 168 569 190 570 505 570 94 570 97 571 188 571 94 571 188 572 190 572 94 572 94 573 505 573 92 573 197 574 198 574 505 574 198 575 200 575 505 575 200 576 202 576 505 576 202 577 155 577 505 577 155 578 154 578 505 578 59 579 58 579 506 579 154 580 504 580 505 580 58 581 64 581 506 581 64 582 68 582 506 582 68 583 72 583 506 583 197 584 505 584 195 584 72 585 75 585 506 585 75 586 77 586 506 586 504 587 70 587 506 587 70 588 59 588 506 588 195 589 505 589 193 589 193 590 505 590 190 590 77 591 79 591 507 591 79 592 81 592 507 592 81 593 84 593 507 593 84 594 86 594 507 594 86 595 89 595 507 595 89 596 91 596 507 596 91 597 92 597 507 597 506 598 77 598 507 598 92 599 505 599 507 599 168 600 172 600 62 600 62 601 172 601 56 601 172 602 176 602 56 602 168 603 62 603 66 603 504 604 168 604 66 604 176 605 178 605 52 605 56 606 176 606 52 606 504 607 66 607 70 607 52 608 178 608 53 608 178 609 180 609 53 609 508 610 509 610 510 610 511 611 508 611 510 611 511 612 512 612 513 612 511 613 510 613 512 613 514 614 515 614 516 614 514 615 516 615 517 615 518 616 511 616 513 616 519 617 513 617 520 617 521 618 517 618 522 618 519 619 518 619 513 619 521 620 514 620 517 620 523 621 524 621 525 621 523 622 520 622 524 622 523 623 519 623 520 623 526 624 522 624 527 624 526 625 521 625 522 625 528 626 525 626 529 626 528 627 523 627 525 627 530 628 528 628 529 628 531 629 527 629 532 629 531 630 526 630 527 630 533 631 532 631 534 631 533 632 531 632 532 632 535 633 534 633 536 633 535 634 533 634 534 634 537 635 536 635 538 635 537 636 535 636 536 636 539 637 538 637 540 637 539 638 537 638 538 638 541 639 540 639 542 639 541 640 539 640 540 640 543 641 542 641 544 641 543 642 541 642 542 642 545 643 544 643 546 643 545 644 543 644 544 644 547 645 545 645 546 645 547 646 546 646 548 646 549 647 547 647 548 647 549 648 550 648 551 648 549 649 548 649 550 649 552 650 549 650 551 650 553 651 552 651 551 651 553 652 554 652 555 652 553 653 551 653 554 653 556 654 553 654 555 654 509 655 556 655 555 655 509 656 557 656 510 656 509 657 555 657 557 657 558 658 559 658 560 658 558 659 561 659 559 659 562 660 560 660 563 660 564 661 565 661 566 661 562 662 558 662 560 662 567 663 563 663 568 663 569 664 566 664 570 664 567 665 562 665 563 665 569 666 564 666 566 666 571 667 568 667 572 667 573 668 570 668 574 668 571 669 567 669 568 669 573 670 569 670 570 670 575 671 572 671 576 671 577 672 574 672 578 672 575 673 571 673 572 673 577 674 573 674 574 674 579 675 576 675 580 675 579 676 575 676 576 676 581 677 578 677 582 677 583 678 579 678 580 678 583 679 580 679 584 679 581 680 577 680 578 680 585 681 582 681 586 681 585 682 581 682 582 682 587 683 585 683 586 683 588 684 586 684 589 684 588 685 587 685 586 685 590 686 589 686 591 686 590 687 588 687 589 687 592 688 591 688 593 688 592 689 590 689 591 689 594 690 593 690 595 690 594 691 592 691 593 691 596 692 595 692 597 692 596 693 594 693 595 693 598 694 596 694 597 694 598 695 597 695 599 695 600 696 598 696 599 696 600 697 599 697 601 697 602 698 600 698 601 698 602 699 601 699 603 699 604 700 602 700 603 700 604 701 603 701 605 701 606 702 605 702 607 702 606 703 604 703 605 703 561 704 607 704 559 704 561 705 606 705 607 705 555 706 510 706 557 706 550 707 554 707 551 707 529 708 525 708 524 708 529 709 524 709 520 709 529 710 520 710 513 710 529 711 513 711 512 711 529 712 512 712 510 712 529 713 555 713 554 713 529 714 510 714 555 714 529 715 554 715 550 715 544 716 550 716 548 716 544 717 548 717 546 717 544 718 529 718 550 718 538 719 544 719 542 719 538 720 542 720 540 720 538 721 529 721 544 721 534 722 538 722 536 722 532 723 538 723 534 723 517 724 532 724 527 724 517 725 527 725 522 725 517 726 529 726 538 726 517 727 538 727 532 727 516 728 529 728 517 728 608 729 609 729 529 729 608 730 529 730 516 730 610 731 611 731 612 731 613 732 614 732 615 732 616 733 617 733 618 733 619 734 616 734 618 734 620 735 619 735 618 735 621 736 620 736 618 736 611 737 621 737 618 737 614 738 612 738 618 738 612 739 611 739 618 739 615 740 614 740 618 740 622 741 615 741 623 741 624 742 622 742 623 742 625 743 623 743 626 743 615 744 618 744 626 744 623 745 615 745 626 745 626 746 618 746 627 746 628 747 627 747 629 747 629 748 627 748 630 748 631 749 630 749 632 749 633 750 631 750 632 750 627 751 618 751 632 751 630 752 627 752 632 752 632 753 618 753 634 753 618 754 635 754 636 754 634 755 618 755 636 755 611 756 610 756 637 756 621 757 638 757 639 757 621 758 611 758 638 758 634 759 640 759 641 759 620 760 639 760 642 760 620 761 621 761 639 761 632 762 641 762 643 762 632 763 634 763 641 763 619 764 642 764 644 764 619 765 620 765 642 765 633 766 643 766 645 766 633 767 632 767 643 767 616 768 644 768 646 768 616 769 619 769 644 769 631 770 645 770 647 770 631 771 633 771 645 771 617 772 646 772 648 772 617 773 616 773 646 773 618 774 617 774 648 774 618 775 648 775 649 775 630 776 647 776 650 776 630 777 631 777 647 777 629 778 650 778 651 778 629 779 630 779 650 779 628 780 651 780 652 780 628 781 629 781 651 781 627 782 652 782 653 782 627 783 628 783 652 783 626 784 627 784 653 784 625 785 653 785 654 785 625 786 626 786 653 786 623 787 654 787 655 787 623 788 625 788 654 788 624 789 655 789 656 789 624 790 623 790 655 790 622 791 624 791 656 791 622 792 656 792 657 792 615 793 622 793 657 793 615 794 657 794 658 794 613 795 615 795 658 795 613 796 658 796 659 796 614 797 613 797 659 797 614 798 659 798 660 798 612 799 660 799 661 799 612 800 614 800 660 800 610 801 661 801 637 801 610 802 612 802 661 802 611 803 637 803 638 803 662 804 663 804 664 804 665 805 666 805 667 805 666 806 668 806 667 806 669 807 665 807 667 807 670 808 671 808 672 808 673 809 674 809 675 809 583 810 584 810 676 810 662 811 664 811 677 811 667 812 668 812 678 812 662 813 677 813 679 813 662 814 679 814 507 814 680 815 681 815 507 815 681 816 662 816 507 816 680 817 507 817 682 817 683 818 676 818 684 818 676 819 584 819 684 819 670 820 672 820 685 820 682 821 507 821 686 821 634 822 636 822 640 822 687 823 688 823 640 823 688 824 689 824 640 824 689 825 685 825 640 825 636 826 687 826 640 826 690 827 683 827 691 827 686 828 507 828 505 828 683 829 684 829 691 829 675 830 674 830 692 830 675 831 692 831 693 831 694 832 690 832 695 832 696 833 675 833 693 833 690 834 691 834 695 834 697 835 696 835 698 835 696 836 693 836 698 836 697 837 698 837 699 837 505 838 700 838 515 838 700 839 701 839 515 839 702 840 697 840 699 840 701 841 703 841 515 841 515 842 703 842 608 842 703 843 704 843 608 843 704 844 705 844 608 844 694 845 695 845 706 845 515 846 608 846 516 846 505 847 515 847 686 847 685 848 672 848 640 848 707 849 708 849 636 849 708 850 687 850 636 850 678 851 709 851 710 851 709 852 711 852 710 852 667 853 678 853 710 853 711 854 694 854 712 854 670 855 713 855 714 855 713 856 715 856 714 856 694 857 706 857 712 857 715 858 716 858 714 858 716 859 717 859 714 859 717 860 718 860 714 860 719 861 670 861 714 861 718 862 720 862 714 862 710 863 711 863 712 863 720 864 721 864 714 864 721 865 722 865 714 865 722 866 702 866 714 866 670 867 719 867 723 867 706 868 724 868 662 868 724 869 725 869 662 869 725 870 726 870 662 870 726 871 727 871 662 871 670 872 723 872 671 872 712 873 706 873 662 873 702 874 699 874 669 874 714 875 702 875 669 875 699 876 665 876 669 876 662 877 727 877 663 877 728 878 729 878 730 878 728 879 730 879 731 879 732 880 728 880 731 880 733 881 734 881 735 881 732 882 731 882 736 882 737 883 732 883 736 883 738 884 735 884 739 884 737 885 736 885 740 885 738 886 733 886 735 886 741 887 737 887 740 887 742 888 739 888 743 888 741 889 740 889 744 889 742 890 738 890 739 890 745 891 741 891 744 891 745 892 744 892 746 892 747 893 743 893 748 893 747 894 742 894 743 894 749 895 745 895 746 895 749 896 746 896 750 896 751 897 748 897 752 897 751 898 747 898 748 898 673 899 750 899 674 899 673 900 749 900 750 900 753 901 752 901 754 901 753 902 751 902 752 902 755 903 753 903 754 903 756 904 754 904 757 904 756 905 755 905 754 905 758 906 757 906 759 906 758 907 756 907 757 907 760 908 759 908 761 908 760 909 758 909 759 909 762 910 761 910 763 910 762 911 760 911 761 911 764 912 763 912 765 912 764 913 762 913 763 913 766 914 764 914 765 914 766 915 765 915 767 915 768 916 766 916 767 916 768 917 767 917 769 917 770 918 768 918 769 918 770 919 769 919 771 919 772 920 770 920 771 920 772 921 771 921 773 921 774 922 772 922 773 922 774 923 773 923 775 923 729 924 774 924 775 924 729 925 775 925 730 925 530 926 776 926 777 926 778 927 779 927 780 927 530 928 777 928 504 928 635 929 618 929 649 929 781 930 778 930 782 930 783 931 781 931 782 931 784 932 635 932 785 932 786 933 783 933 787 933 635 934 649 934 788 934 783 935 782 935 787 935 785 936 635 936 788 936 789 937 790 937 791 937 782 938 778 938 792 938 790 939 793 939 791 939 788 940 649 940 794 940 778 941 780 941 795 941 793 942 796 942 797 942 786 943 787 943 798 943 791 944 793 944 797 944 794 945 649 945 799 945 800 946 789 946 801 946 789 947 791 947 801 947 802 948 786 948 798 948 799 949 649 949 803 949 792 950 778 950 804 950 805 951 800 951 806 951 800 952 801 952 806 952 778 953 795 953 807 953 804 954 778 954 808 954 797 955 796 955 809 955 778 956 807 956 810 956 811 957 812 957 813 957 808 958 778 958 810 958 809 959 796 959 814 959 802 960 798 960 815 960 803 961 811 961 813 961 805 962 806 962 816 962 813 963 812 963 817 963 818 964 802 964 815 964 818 965 815 965 564 965 813 966 817 966 819 966 564 967 815 967 565 967 803 968 649 968 811 968 504 969 820 969 530 969 813 970 819 970 821 970 822 971 823 971 821 971 796 972 824 972 825 972 823 973 826 973 821 973 826 974 827 974 821 974 827 975 813 975 821 975 814 976 796 976 825 976 822 977 821 977 828 977 825 978 824 978 829 978 828 979 821 979 830 979 805 980 816 980 733 980 830 981 821 981 831 981 824 982 781 982 832 982 829 983 824 983 832 983 831 984 821 984 833 984 832 985 781 985 783 985 530 986 529 986 609 986 821 987 793 987 790 987 833 988 821 988 790 988 733 989 816 989 734 989 609 990 834 990 835 990 530 991 609 991 836 991 609 992 835 992 836 992 530 993 836 993 776 993 778 994 837 994 506 994 837 995 838 995 506 995 838 996 839 996 506 996 839 997 820 997 506 997 820 998 504 998 506 998 778 999 506 999 779 999 814 1000 825 1000 668 1000 825 1001 678 1001 668 1001 564 1002 212 1002 206 1002 227 1003 606 1003 229 1003 606 1004 561 1004 229 1004 564 1005 206 1005 205 1005 229 1006 561 1006 558 1006 229 1007 558 1007 231 1007 231 1008 558 1008 562 1008 231 1009 562 1009 567 1009 233 1010 231 1010 567 1010 233 1011 567 1011 571 1011 587 1012 588 1012 217 1012 585 1013 587 1013 217 1013 590 1014 592 1014 219 1014 588 1015 590 1015 219 1015 233 1016 571 1016 575 1016 217 1017 588 1017 219 1017 581 1018 585 1018 214 1018 235 1019 233 1019 575 1019 577 1020 581 1020 214 1020 585 1021 217 1021 214 1021 235 1022 575 1022 579 1022 243 1023 241 1023 583 1023 241 1024 239 1024 583 1024 239 1025 237 1025 583 1025 237 1026 235 1026 583 1026 235 1027 579 1027 583 1027 564 1028 205 1028 818 1028 594 1029 596 1029 221 1029 205 1030 253 1030 818 1030 592 1031 594 1031 221 1031 253 1032 251 1032 818 1032 251 1033 249 1033 818 1033 219 1034 592 1034 221 1034 573 1035 577 1035 210 1035 569 1036 573 1036 210 1036 243 1037 583 1037 676 1037 249 1038 247 1038 676 1038 247 1039 245 1039 676 1039 245 1040 243 1040 676 1040 818 1041 249 1041 676 1041 577 1042 214 1042 210 1042 596 1043 598 1043 223 1043 221 1044 596 1044 223 1044 564 1045 569 1045 209 1045 569 1046 210 1046 209 1046 600 1047 602 1047 225 1047 598 1048 600 1048 225 1048 223 1049 598 1049 225 1049 564 1050 209 1050 212 1050 604 1051 606 1051 227 1051 602 1052 604 1052 227 1052 225 1053 602 1053 227 1053 761 1054 222 1054 763 1054 763 1055 222 1055 765 1055 222 1056 224 1056 765 1056 236 1057 238 1057 674 1057 238 1058 240 1058 674 1058 240 1059 242 1059 674 1059 734 1060 816 1060 204 1060 242 1061 244 1061 674 1061 244 1062 692 1062 674 1062 765 1063 224 1063 767 1063 224 1064 226 1064 767 1064 204 1065 816 1065 207 1065 236 1066 674 1066 750 1066 734 1067 204 1067 211 1067 767 1068 226 1068 769 1068 207 1069 816 1069 252 1069 734 1070 211 1070 215 1070 234 1071 236 1071 746 1071 236 1072 750 1072 746 1072 816 1073 692 1073 250 1073 226 1074 228 1074 771 1074 252 1075 816 1075 250 1075 769 1076 226 1076 771 1076 735 1077 734 1077 208 1077 734 1078 215 1078 208 1078 234 1079 746 1079 744 1079 771 1080 228 1080 773 1080 250 1081 692 1081 248 1081 232 1082 234 1082 740 1082 739 1083 735 1083 213 1083 743 1084 739 1084 213 1084 234 1085 744 1085 740 1085 773 1086 228 1086 775 1086 735 1087 208 1087 213 1087 228 1088 230 1088 775 1088 232 1089 740 1089 736 1089 248 1090 692 1090 246 1090 775 1091 230 1091 730 1091 748 1092 743 1092 216 1092 230 1093 232 1093 731 1093 752 1094 748 1094 216 1094 232 1095 736 1095 731 1095 743 1096 213 1096 216 1096 730 1097 230 1097 731 1097 246 1098 692 1098 244 1098 752 1099 216 1099 218 1099 752 1100 218 1100 754 1100 754 1101 218 1101 757 1101 218 1102 220 1102 757 1102 757 1103 220 1103 759 1103 759 1104 220 1104 761 1104 220 1105 222 1105 761 1105 101 1106 99 1106 686 1106 99 1107 96 1107 686 1107 96 1108 95 1108 686 1108 515 1109 194 1109 686 1109 194 1110 192 1110 686 1110 192 1111 191 1111 686 1111 191 1112 189 1112 686 1112 189 1113 187 1113 686 1113 515 1114 157 1114 203 1114 187 1115 101 1115 686 1115 515 1116 203 1116 201 1116 515 1117 201 1117 199 1117 511 1118 518 1118 519 1118 508 1119 511 1119 519 1119 509 1120 508 1120 519 1120 515 1121 199 1121 196 1121 515 1122 196 1122 194 1122 556 1123 509 1123 549 1123 553 1124 556 1124 549 1124 552 1125 553 1125 549 1125 523 1126 528 1126 530 1126 519 1127 523 1127 530 1127 547 1128 549 1128 545 1128 175 1129 530 1129 820 1129 165 1130 175 1130 820 1130 543 1131 545 1131 541 1131 173 1132 169 1132 820 1132 169 1133 164 1133 820 1133 164 1134 165 1134 820 1134 173 1135 820 1135 63 1135 177 1136 173 1136 63 1136 63 1137 820 1137 67 1137 533 1138 535 1138 531 1138 531 1139 535 1139 526 1139 179 1140 177 1140 57 1140 177 1141 63 1141 57 1141 67 1142 820 1142 71 1142 181 1143 179 1143 54 1143 179 1144 57 1144 54 1144 526 1145 535 1145 515 1145 539 1146 541 1146 515 1146 537 1147 539 1147 515 1147 535 1148 537 1148 515 1148 521 1149 526 1149 515 1149 71 1150 820 1150 74 1150 514 1151 521 1151 515 1151 509 1152 519 1152 515 1152 549 1153 509 1153 515 1153 545 1154 549 1154 515 1154 519 1155 530 1155 515 1155 541 1156 545 1156 515 1156 183 1157 181 1157 55 1157 181 1158 54 1158 55 1158 530 1159 167 1159 161 1159 185 1160 183 1160 103 1160 167 1161 530 1161 171 1161 183 1162 55 1162 103 1162 530 1163 161 1163 159 1163 187 1164 185 1164 101 1164 185 1165 103 1165 101 1165 171 1166 530 1166 175 1166 530 1167 159 1167 156 1167 515 1168 530 1168 156 1168 515 1169 156 1169 157 1169 824 1170 796 1170 710 1170 796 1171 667 1171 710 1171 45 1172 46 1172 672 1172 46 1173 48 1173 672 1173 48 1174 50 1174 672 1174 146 1175 640 1175 144 1175 130 1176 132 1176 672 1176 132 1177 134 1177 672 1177 134 1178 136 1178 672 1178 136 1179 139 1179 672 1179 50 1180 130 1180 672 1180 139 1181 640 1181 672 1181 144 1182 640 1182 143 1182 637 1183 661 1183 660 1183 143 1184 640 1184 141 1184 639 1185 638 1185 644 1185 642 1186 639 1186 644 1186 638 1187 637 1187 659 1187 637 1188 660 1188 659 1188 141 1189 640 1189 139 1189 646 1190 644 1190 648 1190 644 1191 638 1191 648 1191 658 1192 657 1192 656 1192 659 1193 658 1193 656 1193 638 1194 659 1194 656 1194 648 1195 638 1195 656 1195 649 1196 113 1196 811 1196 111 1197 110 1197 811 1197 656 1198 655 1198 654 1198 110 1199 115 1199 811 1199 115 1200 118 1200 811 1200 113 1201 111 1201 811 1201 118 1202 120 1202 13 1202 811 1203 118 1203 13 1203 653 1204 652 1204 651 1204 811 1205 13 1205 17 1205 120 1206 122 1206 9 1206 650 1207 647 1207 645 1207 651 1208 650 1208 645 1208 654 1209 653 1209 645 1209 13 1210 120 1210 9 1210 653 1211 651 1211 645 1211 648 1212 656 1212 645 1212 656 1213 654 1213 645 1213 811 1214 17 1214 21 1214 122 1215 124 1215 4 1215 648 1216 645 1216 640 1216 643 1217 641 1217 640 1217 9 1218 122 1218 4 1218 645 1219 643 1219 640 1219 649 1220 648 1220 640 1220 811 1221 21 1221 25 1221 124 1222 126 1222 0 1222 108 1223 649 1223 104 1223 649 1224 108 1224 107 1224 4 1225 124 1225 0 1225 126 1226 128 1226 1 1226 104 1227 649 1227 152 1227 649 1228 107 1228 113 1228 0 1229 126 1229 1 1229 128 1230 130 1230 50 1230 649 1231 640 1231 150 1231 152 1232 649 1232 150 1232 1 1233 128 1233 50 1233 150 1234 640 1234 148 1234 148 1235 640 1235 146 1235 593 1236 454 1236 595 1236 454 1237 455 1237 597 1237 565 1238 815 1238 457 1238 595 1239 454 1239 597 1239 456 1240 565 1240 457 1240 459 1241 458 1241 584 1241 458 1242 478 1242 584 1242 565 1243 456 1243 460 1243 478 1244 476 1244 584 1244 476 1245 474 1245 584 1245 474 1246 684 1246 584 1246 457 1247 815 1247 461 1247 597 1248 455 1248 599 1248 459 1249 584 1249 580 1249 565 1250 460 1250 463 1250 464 1251 459 1251 580 1251 599 1252 455 1252 601 1252 815 1253 684 1253 465 1253 455 1254 462 1254 601 1254 461 1255 815 1255 465 1255 566 1256 565 1256 468 1256 464 1257 580 1257 576 1257 601 1258 462 1258 603 1258 565 1259 463 1259 468 1259 467 1260 464 1260 572 1260 464 1261 576 1261 572 1261 465 1262 684 1262 470 1262 570 1263 566 1263 471 1263 574 1264 570 1264 471 1264 462 1265 466 1265 605 1265 566 1266 468 1266 471 1266 603 1267 462 1267 605 1267 467 1268 572 1268 568 1268 470 1269 684 1269 472 1269 605 1270 466 1270 607 1270 578 1271 574 1271 473 1271 582 1272 578 1272 473 1272 467 1273 568 1273 563 1273 574 1274 471 1274 473 1274 469 1275 467 1275 563 1275 466 1276 469 1276 559 1276 607 1277 466 1277 559 1277 472 1278 684 1278 474 1278 469 1279 563 1279 560 1279 559 1280 469 1280 560 1280 586 1281 582 1281 475 1281 582 1282 473 1282 475 1282 475 1283 477 1283 589 1283 586 1284 475 1284 589 1284 589 1285 477 1285 591 1285 591 1286 477 1286 593 1286 477 1287 454 1287 593 1287 2 1288 3 1288 129 1288 127 1289 2 1289 129 1289 20 1290 813 1290 24 1290 22 1291 119 1291 803 1291 26 1292 22 1292 803 1292 116 1293 112 1293 803 1293 813 1294 20 1294 16 1294 119 1295 116 1295 803 1295 813 1296 26 1296 803 1296 803 1297 112 1297 117 1297 24 1298 813 1298 29 1298 129 1299 3 1299 131 1299 813 1300 16 1300 12 1300 3 1301 51 1301 131 1301 813 1302 670 1302 31 1302 803 1303 117 1303 114 1303 29 1304 813 1304 31 1304 51 1305 49 1305 133 1305 131 1306 51 1306 133 1306 803 1307 114 1307 109 1307 813 1308 12 1308 8 1308 31 1309 670 1309 33 1309 49 1310 47 1310 135 1310 813 1311 8 1311 26 1311 133 1312 49 1312 135 1312 803 1313 109 1313 106 1313 33 1314 670 1314 35 1314 135 1315 47 1315 137 1315 35 1316 670 1316 37 1316 803 1317 106 1317 105 1317 37 1318 670 1318 38 1318 803 1319 105 1319 153 1319 38 1320 670 1320 40 1320 40 1321 670 1321 42 1321 42 1322 670 1322 44 1322 47 1323 44 1323 685 1323 137 1324 47 1324 685 1324 138 1325 137 1325 685 1325 140 1326 138 1326 685 1326 142 1327 140 1327 685 1327 145 1328 142 1328 685 1328 147 1329 145 1329 685 1329 149 1330 147 1330 685 1330 151 1331 149 1331 685 1331 803 1332 153 1332 685 1332 153 1333 151 1333 685 1333 44 1334 670 1334 685 1334 18 1335 14 1335 121 1335 14 1336 10 1336 123 1336 121 1337 14 1337 123 1337 22 1338 18 1338 119 1338 18 1339 121 1339 119 1339 123 1340 10 1340 125 1340 10 1341 5 1341 125 1341 125 1342 5 1342 127 1342 5 1343 2 1343 127 1343 772 1344 774 1344 497 1344 770 1345 772 1345 497 1345 493 1346 770 1346 497 1346 733 1347 496 1347 498 1347 774 1348 729 1348 499 1348 497 1349 774 1349 499 1349 499 1350 729 1350 728 1350 733 1351 498 1351 500 1351 499 1352 728 1352 501 1352 501 1353 728 1353 732 1353 501 1354 732 1354 737 1354 503 1355 501 1355 737 1355 503 1356 737 1356 741 1356 753 1357 755 1357 480 1357 751 1358 753 1358 480 1358 479 1359 503 1359 745 1359 503 1360 741 1360 745 1360 756 1361 758 1361 481 1361 755 1362 756 1362 481 1362 480 1363 755 1363 481 1363 479 1364 745 1364 749 1364 747 1365 751 1365 485 1365 742 1366 747 1366 485 1366 495 1367 494 1367 673 1367 494 1368 489 1368 673 1368 489 1369 484 1369 673 1369 484 1370 479 1370 673 1370 751 1371 480 1371 485 1371 479 1372 749 1372 673 1372 733 1373 500 1373 805 1373 500 1374 502 1374 805 1374 502 1375 482 1375 805 1375 482 1376 483 1376 805 1376 760 1377 762 1377 486 1377 495 1378 673 1378 675 1378 758 1379 760 1379 486 1379 483 1380 487 1380 675 1380 487 1381 491 1381 675 1381 491 1382 495 1382 675 1382 481 1383 758 1383 486 1383 805 1384 483 1384 675 1384 738 1385 742 1385 488 1385 733 1386 738 1386 488 1386 742 1387 485 1387 488 1387 764 1388 766 1388 490 1388 762 1389 764 1389 490 1389 486 1390 762 1390 490 1390 733 1391 488 1391 492 1391 768 1392 770 1392 493 1392 766 1393 768 1393 493 1393 490 1394 766 1394 493 1394 733 1395 492 1395 496 1395 688 1396 687 1396 788 1396 688 1397 788 1397 794 1397 689 1398 688 1398 799 1398 685 1399 689 1399 799 1399 688 1400 794 1400 799 1400 685 1401 799 1401 803 1401 505 1402 504 1402 777 1402 700 1403 505 1403 777 1403 701 1404 700 1404 776 1404 700 1405 777 1405 776 1405 703 1406 701 1406 836 1406 701 1407 776 1407 836 1407 702 1408 722 1408 833 1408 697 1409 702 1409 790 1409 702 1410 833 1410 790 1410 696 1411 697 1411 789 1411 697 1412 790 1412 789 1412 675 1413 696 1413 800 1413 696 1414 789 1414 800 1414 675 1415 800 1415 805 1415 684 1416 815 1416 798 1416 691 1417 684 1417 798 1417 695 1418 691 1418 787 1418 691 1419 798 1419 787 1419 706 1420 695 1420 782 1420 695 1421 787 1421 782 1421 724 1422 706 1422 792 1422 706 1423 782 1423 792 1423 833 1424 722 1424 721 1424 831 1425 833 1425 721 1425 830 1426 721 1426 720 1426 830 1427 831 1427 721 1427 828 1428 720 1428 718 1428 828 1429 830 1429 720 1429 822 1430 718 1430 717 1430 822 1431 828 1431 718 1431 823 1432 717 1432 716 1432 823 1433 822 1433 717 1433 826 1434 716 1434 715 1434 826 1435 823 1435 716 1435 827 1436 715 1436 713 1436 827 1437 826 1437 715 1437 813 1438 713 1438 670 1438 813 1439 827 1439 713 1439 506 1440 507 1440 679 1440 779 1441 679 1441 677 1441 779 1442 506 1442 679 1442 780 1443 677 1443 664 1443 780 1444 779 1444 677 1444 795 1445 664 1445 663 1445 795 1446 780 1446 664 1446 807 1447 663 1447 727 1447 807 1448 795 1448 663 1448 810 1449 727 1449 726 1449 810 1450 807 1450 727 1450 808 1451 726 1451 725 1451 808 1452 810 1452 726 1452 804 1453 725 1453 724 1453 804 1454 808 1454 725 1454 792 1455 804 1455 724 1455 788 1456 687 1456 708 1456 785 1457 708 1457 707 1457 785 1458 788 1458 708 1458 784 1459 707 1459 636 1459 784 1460 785 1460 707 1460 635 1461 784 1461 636 1461 609 1462 608 1462 705 1462 834 1463 705 1463 704 1463 834 1464 609 1464 705 1464 835 1465 704 1465 703 1465 835 1466 834 1466 704 1466 836 1467 835 1467 703 1467 686 1468 95 1468 93 1468 686 1469 93 1469 90 1469 682 1470 686 1470 88 1470 686 1471 90 1471 88 1471 682 1472 88 1472 87 1472 61 1473 74 1473 820 1473 60 1474 61 1474 820 1474 65 1475 60 1475 820 1475 682 1476 87 1476 85 1476 682 1477 85 1477 83 1477 682 1478 83 1478 82 1478 82 1479 80 1479 680 1479 682 1480 82 1480 680 1480 69 1481 65 1481 839 1481 73 1482 69 1482 839 1482 76 1483 73 1483 839 1483 78 1484 76 1484 839 1484 65 1485 820 1485 839 1485 681 1486 680 1486 838 1486 80 1487 78 1487 838 1487 680 1488 80 1488 838 1488 78 1489 839 1489 838 1489 662 1490 681 1490 837 1490 681 1491 838 1491 837 1491 712 1492 662 1492 778 1492 662 1493 837 1493 778 1493 710 1494 712 1494 781 1494 712 1495 778 1495 781 1495 710 1496 781 1496 824 1496 669 1497 667 1497 796 1497 714 1498 669 1498 793 1498 669 1499 796 1499 793 1499 719 1500 714 1500 821 1500 714 1501 793 1501 821 1501 723 1502 719 1502 819 1502 719 1503 821 1503 819 1503 723 1504 819 1504 817 1504 671 1505 723 1505 30 1505 671 1506 30 1506 32 1506 723 1507 817 1507 27 1507 30 1508 723 1508 27 1508 671 1509 32 1509 34 1509 671 1510 34 1510 36 1510 671 1511 36 1511 39 1511 672 1512 671 1512 41 1512 671 1513 39 1513 41 1513 672 1514 41 1514 43 1514 28 1515 27 1515 812 1515 23 1516 28 1516 812 1516 19 1517 23 1517 812 1517 15 1518 19 1518 812 1518 11 1519 15 1519 812 1519 27 1520 817 1520 812 1520 672 1521 43 1521 45 1521 6 1522 11 1522 811 1522 7 1523 6 1523 811 1523 25 1524 7 1524 811 1524 11 1525 812 1525 811 1525 709 1526 678 1526 825 1526 711 1527 709 1527 829 1527 709 1528 825 1528 829 1528 694 1529 711 1529 832 1529 711 1530 829 1530 832 1530 690 1531 694 1531 783 1531 694 1532 832 1532 783 1532 683 1533 690 1533 786 1533 690 1534 783 1534 786 1534 683 1535 786 1535 802 1535 676 1536 683 1536 818 1536 683 1537 802 1537 818 1537 692 1538 816 1538 806 1538 693 1539 692 1539 806 1539 698 1540 693 1540 801 1540 693 1541 806 1541 801 1541 699 1542 698 1542 791 1542 698 1543 801 1543 791 1543 665 1544 699 1544 797 1544 699 1545 791 1545 797 1545 666 1546 665 1546 809 1546 665 1547 797 1547 809 1547 668 1548 666 1548 814 1548 666 1549 809 1549 814 1549 451 1550 447 1550 448 1550 442 1551 444 1551 447 1551 404 1552 451 1552 452 1552 404 1553 452 1553 407 1553 438 1554 440 1554 442 1554 414 1555 404 1555 408 1555 414 1556 447 1556 451 1556 414 1557 451 1557 404 1557 421 1558 435 1558 436 1558 421 1559 436 1559 438 1559 421 1560 414 1560 416 1560 421 1561 442 1561 447 1561 421 1562 438 1562 442 1562 421 1563 447 1563 414 1563 431 1564 432 1564 435 1564 411 1565 421 1565 415 1565 411 1566 435 1566 421 1566 427 1567 428 1567 431 1567 418 1568 431 1568 435 1568 418 1569 427 1569 431 1569 418 1570 435 1570 411 1570 423 1571 425 1571 427 1571 423 1572 427 1572 418 1572 443 1573 392 1573 394 1573 360 1574 410 1574 409 1574 429 1575 375 1575 377 1575 429 1576 426 1576 375 1576 389 1577 392 1577 443 1577 358 1578 360 1578 409 1578 366 1579 417 1579 410 1579 366 1580 410 1580 360 1580 441 1581 389 1581 443 1581 379 1582 429 1582 377 1582 430 1583 429 1583 379 1583 354 1584 409 1584 406 1584 388 1585 389 1585 441 1585 354 1586 358 1586 409 1586 370 1587 422 1587 417 1587 382 1588 430 1588 379 1588 370 1589 417 1589 366 1589 439 1590 388 1590 441 1590 405 1591 354 1591 406 1591 433 1592 430 1592 382 1592 357 1593 354 1593 405 1593 383 1594 433 1594 382 1594 365 1595 412 1595 422 1595 365 1596 422 1596 370 1596 437 1597 385 1597 388 1597 437 1598 388 1598 439 1598 453 1599 357 1599 405 1599 434 1600 383 1600 385 1600 434 1601 385 1601 437 1601 434 1602 433 1602 383 1602 402 1603 357 1603 453 1603 413 1604 412 1604 365 1604 362 1605 413 1605 365 1605 400 1606 453 1606 450 1606 400 1607 402 1607 453 1607 368 1608 419 1608 413 1608 368 1609 413 1609 362 1609 449 1610 400 1610 450 1610 397 1611 400 1611 449 1611 371 1612 420 1612 419 1612 371 1613 419 1613 368 1613 446 1614 395 1614 397 1614 446 1615 397 1615 449 1615 373 1616 420 1616 371 1616 424 1617 420 1617 373 1617 394 1618 395 1618 446 1618 445 1619 394 1619 446 1619 375 1620 424 1620 373 1620 426 1621 424 1621 375 1621 443 1622 394 1622 445 1622 320 1623 316 1623 310 1623 353 1624 306 1624 305 1624 352 1625 310 1625 306 1625 352 1626 306 1626 353 1626 313 1627 312 1627 320 1627 313 1628 320 1628 310 1628 313 1629 310 1629 352 1629 345 1630 349 1630 348 1630 345 1631 352 1631 349 1631 324 1632 318 1632 313 1632 324 1633 322 1633 318 1633 324 1634 313 1634 352 1634 343 1635 352 1635 345 1635 339 1636 343 1636 341 1636 339 1637 352 1637 343 1637 329 1638 328 1638 326 1638 338 1639 326 1639 324 1639 338 1640 324 1640 352 1640 338 1641 329 1641 326 1641 338 1642 352 1642 339 1642 331 1643 329 1643 338 1643 334 1644 338 1644 335 1644 334 1645 331 1645 338 1645 301 1646 346 1646 347 1646 327 1647 330 1647 283 1647 327 1648 283 1648 281 1648 299 1649 346 1649 301 1649 350 1650 301 1650 347 1650 278 1651 327 1651 281 1651 302 1652 301 1652 350 1652 311 1653 265 1653 264 1653 297 1654 344 1654 346 1654 311 1655 264 1655 314 1655 297 1656 346 1656 299 1656 325 1657 327 1657 278 1657 351 1658 302 1658 350 1658 269 1659 265 1659 311 1659 255 1660 302 1660 351 1660 342 1661 344 1661 297 1661 277 1662 325 1662 278 1662 295 1663 342 1663 297 1663 307 1664 255 1664 351 1664 317 1665 269 1665 311 1665 323 1666 325 1666 277 1666 256 1667 255 1667 307 1667 321 1668 273 1668 269 1668 321 1669 277 1669 273 1669 321 1670 269 1670 317 1670 340 1671 342 1671 295 1671 321 1672 323 1672 277 1672 293 1673 340 1673 295 1673 257 1674 307 1674 304 1674 257 1675 256 1675 307 1675 291 1676 337 1676 340 1676 291 1677 340 1677 293 1677 308 1678 257 1678 304 1678 261 1679 257 1679 308 1679 289 1680 336 1680 337 1680 289 1681 337 1681 291 1681 309 1682 262 1682 261 1682 309 1683 261 1683 308 1683 333 1684 289 1684 287 1684 333 1685 336 1685 289 1685 315 1686 262 1686 309 1686 315 1687 271 1687 262 1687 332 1688 333 1688 287 1688 332 1689 287 1689 285 1689 319 1690 271 1690 315 1690 319 1691 275 1691 271 1691 330 1692 332 1692 285 1692 330 1693 285 1693 283 1693 264 1694 275 1694 319 1694 314 1695 264 1695 319 1695

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae new file mode 100644 index 0000000..6050188 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_finger.dae @@ -0,0 +1,98 @@ + + + 2016-07-17T22:12:38.778959 + 2016-07-17T22:12:38.778970 + Z_UP + + + + + + + + 0.007843 0.007843 0.007843 1 + + + 0.08 0.08 0.08 1 + + + 0.08 0.08 0.08 1 + + + 0.312500 + + + 0 0 0 1 + + + 1 1 1 1 + + + 1.000000 + + + + + + 0 + + + + + + + + + + -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.700781e-16 2.267012 -0.7878182 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 6.97998e-16 2.361471 -0.820644 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.551115e-16 -2.5 -5.551115e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 -5.329071e-16 -2.4 -5.329071e-16 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 -2.207149e-16 -0.9916864 0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 2.207149e-16 0.9916864 -0.1286779 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1.856786e-15 -0.7720676 -5.950119 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 3.094643e-16 -0.1286779 -0.9916864 3.094643e-16 -0.1286779 -0.9916864 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -3.094643e-16 0.1286779 0.9916864 -3.094643e-16 0.1286779 0.9916864 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 3.175 -5.959349e-16 8.532109e-16 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 -3.175 4.852524e-16 -1.706211e-15 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 3.175 -7.066173e-16 2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -3.175 7.066173e-16 -2.109429e-19 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 1 -1.790588e-16 3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 1.790588e-16 -3.352927e-16 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 1 -2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 -1 2.220446e-16 0 + + + + + + + + + + -5 -1.339567 -2.11082 -5 -0.7725425 -2.377641 5 -1.339567 -2.11082 -5 -2.5 -6.661338e-15 5 -2.5 -6.661338e-15 5 -2.421458 0.6217247 -5 -1.822422 -1.711368 5 -1.822422 -1.711368 5 -2.190767 -1.204384 -5 -2.421458 0.6217247 5 -2.190767 1.204384 -5 -2.190767 -1.204384 -5 -2.421458 -0.6217247 5 -2.421458 -0.6217247 -5 -2.190767 1.204384 5 -1.822422 1.711368 -5 -1.822422 1.711368 5 -1.339567 2.11082 -5 -1.339567 2.11082 5 -0.7725425 2.377641 -5 -0.7725425 2.377641 5 -0.1569763 2.495067 -5 -0.1569763 2.495067 5 0.4684533 2.455718 -5 0.4684533 2.455718 5 1.064448 2.262068 -5 1.064448 2.262068 -5 1.59356 1.926283 5 1.59356 1.926283 5 2.022542 1.469463 -5 2.022542 1.469463 5 2.324441 0.9203114 -5 2.324441 0.9203114 5 2.480287 0.3133331 -5 2.480287 0.3133331 -5 2.480287 -0.3133331 5 2.480287 -0.3133331 5 2.324441 -0.9203114 -5 2.324441 -0.9203114 -5 2.022542 -1.469463 5 2.022542 -1.469463 5 1.59356 -1.926283 -5 1.59356 -1.926283 -5 1.064448 -2.262068 5 1.064448 -2.262068 5 0.4684533 -2.455718 -5 0.4684533 -2.455718 5 -0.1569763 -2.495067 -5 -0.1569763 -2.495067 5 -0.7725425 -2.377641 -12.7 -0.1506972 -2.395264 -12 0.4497152 -2.357489 -12 -0.1506972 -2.395264 -12.7 0.4497152 -2.357489 -12.7 -0.7416408 -2.282536 -12 -0.7416408 -2.282536 -12.7 -1.285984 -2.026387 -12 -1.285984 -2.026387 -12.7 -2.3246 0.5968557 -12 -2.4 -5.551115e-15 -12 -2.3246 0.5968557 -12.7 -2.4 -6.661338e-15 -12.7 -1.749525 -1.642913 -12 -1.749525 -1.642913 -12.7 -2.103136 1.156209 -12 -2.103136 1.156209 -12.7 -2.103136 -1.156209 -12 -2.103136 -1.156209 -12 -2.3246 -0.5968557 -12.7 -1.749525 1.642913 -12 -1.749525 1.642913 -12.7 -2.3246 -0.5968557 -12.7 -1.285984 2.026387 -12 -1.285984 2.026387 -12.7 -0.7416408 2.282536 -12 -0.7416408 2.282536 -12.7 -0.1506972 2.395264 -12 -0.1506972 2.395264 -12.7 0.4497152 2.357489 -12 0.4497152 2.357489 -12.7 1.02187 2.171585 -12 1.02187 2.171585 -12.7 1.529818 1.849232 -12 1.529818 1.849232 -12.7 1.941641 1.410685 -12 1.941641 1.410685 -12.7 2.231464 0.8834989 -12 2.231464 0.8834989 -12.7 2.381075 0.3007998 -12 2.381075 0.3007998 -12.7 2.381075 -0.3007998 -12 2.381075 -0.3007998 -12.7 2.231464 -0.8834989 -12 2.231464 -0.8834989 -12.7 1.941641 -1.410685 -12 1.941641 -1.410685 -12.7 1.529818 -1.849232 -12 1.529818 -1.849232 -12.7 1.02187 -2.171585 -12 1.02187 -2.171585 -13.5 -1.822422 -1.711368 -12.7 -1.822422 -1.711368 -12.7 -2.190767 -1.204384 -13.5 -1.339567 -2.11082 -13.5 -2.5 -6.661338e-15 -12.7 -2.5 -6.661338e-15 -12.7 -2.421458 0.6217247 -13.5 -2.190767 -1.204384 -12.7 -2.421458 -0.6217247 -13.5 -2.421458 0.6217247 -12.7 -2.190767 1.204384 -13.5 -2.421458 -0.6217247 -13.5 -2.190767 1.204384 -12.7 -1.822422 1.711368 -13.5 -1.822422 1.711368 -12.7 -1.339567 2.11082 -13.5 -1.339567 2.11082 -12.7 -0.7725425 2.377641 -13.5 -0.7725425 2.377641 -12.7 -0.1569763 2.495067 -13.5 -0.1569763 2.495067 -12.7 0.4684533 2.455718 -13.5 0.4684533 2.455718 -12.7 1.064448 2.262068 -13.5 1.064448 2.262068 -12.7 1.59356 1.926283 -13.5 1.59356 1.926283 -12.7 2.022542 1.469463 -13.5 2.022542 1.469463 -12.7 2.324441 0.9203114 -13.5 2.324441 0.9203114 -12.7 2.480287 0.3133331 -13.5 2.480287 0.3133331 -12.7 2.480287 -0.3133331 -13.5 2.480287 -0.3133331 -12.7 2.324441 -0.9203114 -13.5 2.324441 -0.9203114 -12.7 2.022542 -1.469463 -13.5 2.022542 -1.469463 -12.7 1.59356 -1.926283 -13.5 1.59356 -1.926283 -12.7 1.064448 -2.262068 -13.5 1.064448 -2.262068 -12.7 0.4684533 -2.455718 -13.5 0.4684533 -2.455718 -12.7 -0.1569763 -2.495067 -13.5 -0.1569763 -2.495067 -12.7 -0.7725425 -2.377641 -13.5 -0.7725425 -2.377641 -12.7 -1.339567 -2.11082 7.5 5.444029 44.7166 -7.5 4.866172 44.95907 -7.5 5.444029 44.7166 7.5 4.866172 44.95907 7.5 6.064031 44.62545 -7.5 6.064031 44.62545 7.5 6.687222 44.69136 -7.5 6.687222 44.69136 7.5 8.606142 46.91735 -7.5 8.476246 46.3043 -7.5 8.606142 46.91735 7.5 8.476246 46.3043 7.5 7.274444 44.91018 -7.5 7.274444 44.91018 7.5 8.579496 47.54345 -7.5 8.579496 47.54345 7.5 7.7888 45.26816 -7.5 7.7888 45.26816 7.5 8.397983 48.14325 -7.5 8.397983 48.14325 7.5 8.19797 45.7428 -7.5 8.19797 45.7428 7.5 8.073007 48.67907 -7.5 8.073007 48.67907 7.5 7.624989 49.11724 -7.5 7.624989 49.11724 7.5 7.082078 49.43022 -7.5 7.082078 49.43022 7.5 6.478388 49.59836 -7.5 6.478388 49.59836 7.5 5.851851 49.61108 -7.5 5.851851 49.61108 7.5 5.241835 49.46758 -7.5 5.241835 49.46758 7.5 4.686668 49.17689 -7.5 4.686668 49.17689 7.5 4.221235 48.75727 -7.5 4.221235 48.75727 7.5 3.87478 48.23508 -7.5 3.87478 48.23508 7.5 3.669072 47.64314 -7.5 3.669072 47.64314 7.5 3.617037 47.01864 -7.5 3.617037 47.01864 7.5 3.721943 46.40082 -7.5 3.721943 46.40082 7.5 3.977201 45.82849 -7.5 3.977201 45.82849 7.5 4.36677 45.33763 -7.5 4.36677 45.33763 -12 6.066061 44.72543 -12 5.470859 44.81293 -12.7 6.066061 44.72543 -12 6.664324 44.7887 -12.7 6.664324 44.7887 -12 7.228057 44.99877 -12.7 7.228057 44.99877 -12.7 7.721839 45.34243 -12 8.506488 46.92565 -12.7 8.381787 46.33712 -12.7 8.506488 46.92565 -12.7 8.480908 47.52671 -12 8.381787 46.33712 -12 7.721839 45.34243 -12 8.480908 47.52671 -12 8.114643 45.79809 -12.7 8.114643 45.79809 -12 8.306655 48.10252 -12.7 8.306655 48.10252 -12 7.994678 48.61691 -12.7 7.994678 48.61691 -12.7 7.56458 49.03755 -12 7.56458 49.03755 -12.7 7.043386 49.33801 -12 7.043386 49.33801 -12 6.463844 49.49942 -12.7 6.463844 49.49942 -12.7 5.862368 49.51163 -12 5.862368 49.51163 -12.7 5.276752 49.37388 -12 5.276752 49.37388 -12.7 4.743793 49.09481 -12 4.743793 49.09481 -12.7 4.296977 48.69198 -12 4.296977 48.69198 -12 3.96438 48.19068 -12.7 3.96438 48.19068 -12 3.7669 47.62241 -12.7 3.7669 47.62241 -12.7 3.716946 47.02289 -12 3.716946 47.02289 -12 3.817657 46.42978 -12.7 3.817657 46.42978 -12.7 4.062704 45.88035 -12 4.062704 45.88035 -12 4.43669 45.40912 -12.7 4.43669 45.40912 -12 4.916116 45.04571 -12.7 4.916116 45.04571 -12.7 5.470859 44.81293 -12.7 6.064031 44.62545 -12.7 5.444029 44.7166 -13.5 6.064031 44.62545 -12.7 6.687222 44.69136 -13.5 6.687222 44.69136 -12.7 7.274444 44.91018 -13.5 7.274444 44.91018 -12.7 8.606142 46.91735 -13.5 8.476246 46.3043 -13.5 8.606142 46.91735 -13.5 8.579496 47.54345 -12.7 8.476246 46.3043 -12.7 7.7888 45.26816 -13.5 7.7888 45.26816 -13.5 8.19797 45.7428 -12.7 8.579496 47.54345 -12.7 8.19797 45.7428 -12.7 8.397983 48.14325 -13.5 8.397983 48.14325 -13.5 8.073007 48.67907 -12.7 8.073007 48.67907 -12.7 7.624989 49.11724 -13.5 7.624989 49.11724 -13.5 7.082078 49.43022 -12.7 7.082078 49.43022 -12.7 6.478388 49.59836 -13.5 6.478388 49.59836 -12.7 5.851851 49.61108 -13.5 5.851851 49.61108 -12.7 5.241835 49.46758 -13.5 5.241835 49.46758 -12.7 4.686668 49.17689 -13.5 4.686668 49.17689 -13.5 4.221235 48.75727 -12.7 4.221235 48.75727 -12.7 3.87478 48.23508 -13.5 3.87478 48.23508 -12.7 3.669072 47.64314 -13.5 3.669072 47.64314 -12.7 3.617037 47.01864 -13.5 3.617037 47.01864 -12.7 3.721943 46.40082 -13.5 3.721943 46.40082 -13.5 3.977201 45.82849 -12.7 3.977201 45.82849 -12.7 4.36677 45.33763 -13.5 4.36677 45.33763 -13.5 4.866172 44.95907 -12.7 4.866172 44.95907 -13.5 5.444029 44.7166 5 -3.277269 -5.025884 12 -2.693941 -5.36122 12 -3.277269 -5.025884 5 -2.693941 -5.36122 5 -3.819382 -4.627345 12 -3.819382 -4.627345 5 5.826261 -1.433415 12 5.950119 -0.7720676 12 5.826261 -1.433415 5 5.950119 -0.7720676 5 -4.313465 -4.170614 12 -4.313465 -4.170614 5 5.629136 -2.076736 12 5.629136 -2.076736 5 -4.753303 -3.661435 12 -4.753303 -3.661435 5 5.36122 -2.693941 12 5.36122 -2.693941 5 -5.133366 -3.106211 12 -5.133366 -3.106211 5 5.025884 -3.277269 12 5.025884 -3.277269 5 -5.448874 -2.511926 12 -5.448874 -2.511926 5 4.627345 -3.819382 12 4.627345 -3.819382 5 -5.695859 -1.886051 12 -5.695859 -1.886051 5 4.170614 -4.313465 12 4.170614 -4.313465 5 -5.871216 -1.236458 12 -5.871216 -1.236458 5 3.661435 -4.753303 12 3.661435 -4.753303 5 -5.972738 -0.5713157 12 -5.972738 -0.5713157 5 -5.99915 0.1010111 12 -5.99915 0.1010111 5 3.106211 -5.133366 12 3.106211 -5.133366 5 -5.950119 0.7720676 12 -5.950119 0.7720676 5 2.511926 -5.448874 12 2.511926 -5.448874 5 1.886051 -5.695859 12 1.886051 -5.695859 5 1.236458 -5.871216 12 1.236458 -5.871216 5 0.5713157 -5.972738 12 0.5713157 -5.972738 5 -0.1010111 -5.99915 12 -0.1010111 -5.99915 5 -0.7720676 -5.950119 12 -0.7720676 -5.950119 5 -1.433415 -5.826261 12 -1.433415 -5.826261 5 -2.076736 -5.629136 12 -2.076736 -5.629136 -12 -3.277269 -5.025884 -5 -2.693941 -5.36122 -5 -3.277269 -5.025884 -12 -2.693941 -5.36122 -12 -3.819382 -4.627345 -5 -3.819382 -4.627345 -12 5.826261 -1.433415 -5 5.950119 -0.7720676 -5 5.826261 -1.433415 -12 5.950119 -0.7720676 -12 -4.313465 -4.170614 -5 -4.313465 -4.170614 -12 5.629136 -2.076736 -5 5.629136 -2.076736 -12 -4.753303 -3.661435 -5 -4.753303 -3.661435 -5 -5.133366 -3.106211 -12 5.36122 -2.693941 -5 5.36122 -2.693941 -12 -5.133366 -3.106211 -5 -5.448874 -2.511926 -12 5.025884 -3.277269 -5 5.025884 -3.277269 -12 -5.448874 -2.511926 -5 -5.695859 -1.886051 -12 -5.695859 -1.886051 -5 -5.871216 -1.236458 -12 4.627345 -3.819382 -5 4.627345 -3.819382 -12 -5.871216 -1.236458 -5 -5.972738 -0.5713157 -12 4.170614 -4.313465 -5 4.170614 -4.313465 -12 -5.972738 -0.5713157 -5 -5.99915 0.1010111 -12 3.661435 -4.753303 -5 3.661435 -4.753303 -12 -5.99915 0.1010111 -5 -5.950119 0.7720676 -12 -5.950119 0.7720676 -12 3.106211 -5.133366 -5 3.106211 -5.133366 -12 2.511926 -5.448874 -5 2.511926 -5.448874 -12 1.886051 -5.695859 -5 1.886051 -5.695859 -12 1.236458 -5.871216 -5 1.236458 -5.871216 -12 0.5713157 -5.972738 -5 0.5713157 -5.972738 -12 -0.1010111 -5.99915 -5 -0.1010111 -5.99915 -12 -0.7720676 -5.950119 -5 -0.7720676 -5.950119 -12 -1.433415 -5.826261 -5 -1.433415 -5.826261 -12 -2.076736 -5.629136 -5 -2.076736 -5.629136 12.7 6.066061 44.72543 12 5.470859 44.81293 12 6.066061 44.72543 12 6.664324 44.7887 12.7 5.470859 44.81293 12.7 6.664324 44.7887 12.7 7.228057 44.99877 12 7.228057 44.99877 12.7 8.506488 46.92565 12 8.381787 46.33712 12 8.506488 46.92565 12.7 8.381787 46.33712 12.7 7.721839 45.34243 12 7.721839 45.34243 12 8.114643 45.79809 12.7 8.480908 47.52671 12 8.480908 47.52671 12.7 8.114643 45.79809 12.7 8.306655 48.10252 12 8.306655 48.10252 12.7 7.994678 48.61691 12 7.994678 48.61691 12.7 7.56458 49.03755 12 7.56458 49.03755 12.7 7.043386 49.33801 12 7.043386 49.33801 12 6.463844 49.49942 12.7 6.463844 49.49942 12.7 5.862368 49.51163 12 5.862368 49.51163 12 5.276752 49.37388 12.7 5.276752 49.37388 12 4.743793 49.09481 12.7 4.743793 49.09481 12.7 4.296977 48.69198 12 4.296977 48.69198 12 3.96438 48.19068 12.7 3.96438 48.19068 12.7 3.7669 47.62241 12 3.7669 47.62241 12 3.716946 47.02289 12.7 3.716946 47.02289 12 3.817657 46.42978 12.7 3.817657 46.42978 12 4.062704 45.88035 12.7 4.062704 45.88035 12 4.43669 45.40912 12.7 4.43669 45.40912 12.7 4.916116 45.04571 12 4.916116 45.04571 13.5 6.064031 44.62545 13.5 5.444029 44.7166 12.7 6.064031 44.62545 13.5 6.687222 44.69136 12.7 6.687222 44.69136 12.7 7.274444 44.91018 13.5 8.606142 46.91735 12.7 8.476246 46.3043 12.7 8.606142 46.91735 13.5 7.274444 44.91018 13.5 8.476246 46.3043 13.5 7.7888 45.26816 12.7 7.7888 45.26816 12.7 8.19797 45.7428 13.5 8.579496 47.54345 12.7 8.579496 47.54345 13.5 8.19797 45.7428 13.5 8.397983 48.14325 12.7 8.397983 48.14325 13.5 8.073007 48.67907 12.7 8.073007 48.67907 13.5 7.624989 49.11724 12.7 7.624989 49.11724 12.7 7.082078 49.43022 13.5 7.082078 49.43022 13.5 6.478388 49.59836 12.7 6.478388 49.59836 13.5 5.851851 49.61108 12.7 5.851851 49.61108 13.5 5.241835 49.46758 12.7 5.241835 49.46758 12.7 4.686668 49.17689 13.5 4.686668 49.17689 13.5 4.221235 48.75727 12.7 4.221235 48.75727 12.7 3.87478 48.23508 13.5 3.87478 48.23508 12.7 3.669072 47.64314 13.5 3.669072 47.64314 13.5 3.617037 47.01864 12.7 3.617037 47.01864 12.7 3.721943 46.40082 13.5 3.721943 46.40082 13.5 3.977201 45.82849 12.7 3.977201 45.82849 13.5 4.36677 45.33763 12.7 4.36677 45.33763 13.5 4.866172 44.95907 12.7 4.866172 44.95907 12.7 5.444029 44.7166 12.7 -0.7725425 -2.377641 13.5 -0.7725425 -2.377641 13.5 -1.339567 -2.11082 12.7 -0.1569763 -2.495067 12.7 -1.339567 -2.11082 12.7 -1.822422 -1.711368 13.5 -1.822422 -1.711368 13.5 -2.190767 -1.204384 12.7 -2.421458 0.6217247 13.5 -2.5 -5.551115e-15 13.5 -2.421458 0.6217247 13.5 -2.190767 1.204384 12.7 -2.5 -5.551115e-15 12.7 -2.190767 -1.204384 13.5 -2.421458 -0.6217247 12.7 -2.190767 1.204384 12.7 -2.421458 -0.6217247 12.7 -1.822422 1.711368 13.5 -1.822422 1.711368 13.5 -1.339567 2.11082 12.7 -1.339567 2.11082 12.7 -0.7725425 2.377641 13.5 -0.7725425 2.377641 13.5 -0.1569763 2.495067 12.7 -0.1569763 2.495067 12.7 0.4684533 2.455718 13.5 0.4684533 2.455718 12.7 1.064448 2.262068 13.5 1.064448 2.262068 12.7 1.59356 1.926283 13.5 1.59356 1.926283 12.7 2.022542 1.469463 13.5 2.022542 1.469463 13.5 2.324441 0.9203114 12.7 2.324441 0.9203114 12.7 2.480287 0.3133331 13.5 2.480287 0.3133331 12.7 2.480287 -0.3133331 13.5 2.480287 -0.3133331 12.7 2.324441 -0.9203114 13.5 2.324441 -0.9203114 12.7 2.022542 -1.469463 13.5 2.022542 -1.469463 13.5 1.59356 -1.926283 12.7 1.59356 -1.926283 12.7 1.064448 -2.262068 13.5 1.064448 -2.262068 13.5 0.4684533 -2.455718 12.7 0.4684533 -2.455718 13.5 -0.1569763 -2.495067 12 -0.1506972 -2.395264 12.7 0.4497152 -2.357489 12.7 -0.1506972 -2.395264 12 0.4497152 -2.357489 12 -0.7416408 -2.282536 12.7 -0.7416408 -2.282536 12 -1.285984 -2.026387 12.7 -1.285984 -2.026387 12 -2.3246 0.5968557 12.7 -2.4 -5.551115e-15 12.7 -2.3246 0.5968557 12 -2.4 -6.661338e-15 12 -1.749525 -1.642913 12.7 -1.749525 -1.642913 12 -2.103136 1.156209 12.7 -2.103136 1.156209 12 -2.103136 -1.156209 12.7 -2.103136 -1.156209 12 -1.749525 1.642913 12.7 -1.749525 1.642913 12 -2.3246 -0.5968557 12.7 -2.3246 -0.5968557 12 -1.285984 2.026387 12.7 -1.285984 2.026387 12 -0.7416408 2.282536 12.7 -0.7416408 2.282536 12 -0.1506972 2.395264 12.7 -0.1506972 2.395264 12 0.4497152 2.357489 12.7 0.4497152 2.357489 12 1.02187 2.171585 12.7 1.02187 2.171585 12 1.529818 1.849232 12.7 1.529818 1.849232 12 1.941641 1.410685 12.7 1.941641 1.410685 12 2.231464 0.8834989 12.7 2.231464 0.8834989 12 2.381075 0.3007998 12.7 2.381075 0.3007998 12 2.381075 -0.3007998 12.7 2.381075 -0.3007998 12 2.231464 -0.8834989 12.7 2.231464 -0.8834989 12 1.941641 -1.410685 12.7 1.941641 -1.410685 12 1.529818 -1.849232 12.7 1.529818 -1.849232 12 1.02187 -2.171585 12.7 1.02187 -2.171585 12 -0.4684533 2.455718 12 2.5 -5.551115e-15 12 2.421458 -0.6217247 12 0.1569763 2.495067 12 -1.59356 -1.926283 12 -1.064448 -2.262068 12 -2.022542 -1.469463 12 -2.324441 -0.9203114 12 2.421458 0.6217247 12 -0.4684533 -2.455718 12 0.7725425 2.377641 12 -2.480287 -0.3133331 12 2.190767 1.204384 12 1.339567 2.11082 12 0.1569763 -2.495067 12 1.822422 1.711368 12 -2.480287 0.3133331 12 0.7725425 -2.377641 12 -2.324441 0.9203114 12 1.339567 -2.11082 12 -2.022542 1.469463 12 1.822422 -1.711368 12 -1.59356 1.926283 12 2.190767 -1.204384 12 -1.064448 2.262068 12 8.225595 45.78537 12 3.737134 46.3524 12 4.003956 45.78537 12 8.492417 46.3524 12 7.035087 49.44938 12 6.428109 49.60523 12 3.619709 46.96796 12 4.403408 45.30252 12 8.609842 46.96796 12 7.584239 49.14748 12 3.659058 47.59339 12 4.910391 44.93417 12 8.570494 47.59339 12 5.493051 44.70348 12 8.041059 48.7185 12 3.852708 48.18939 12 8.376843 48.18939 12 6.114776 44.62494 12 4.188493 48.7185 12 6.7365 44.70348 12 4.645313 49.14748 12 7.31916 44.93417 12 5.194464 49.44938 12 7.826143 45.30252 12 5.801443 49.60523 6.570064 -2.160562 29.97717 4.891814 -3.936727 16.28874 7.074631 -2.075948 30.62927 -5 -4.042468 15.47382 -12 0.164657 47.89701 -7.5 -1.871671 32.20357 -7.5 0.164657 47.89701 7.5 0.164657 47.89701 7.5 -1.871671 32.20357 12 0.164657 47.89701 7.391814 -1.977413 31.38865 5 -4.042468 15.47382 -4.891814 -3.936727 16.28874 -4.574631 -3.838192 17.04812 -6.570064 -2.160562 29.97717 -4.070064 -3.753578 17.70022 -5.9125 -2.225488 29.4768 -7.074631 -2.075948 30.62927 -3.4125 -3.688651 18.20059 -5.14675 -2.266303 29.16225 -7.391814 -1.977413 31.38865 -2.64675 -3.647837 18.51514 -4.325 -2.280224 29.05496 -1.825 -3.633916 18.62242 1.825 -3.633916 18.62242 4.325 -2.280224 29.05496 2.64675 -3.647837 18.51514 3.4125 -3.688651 18.20059 4.070064 -3.753578 17.70022 5.14675 -2.266303 29.16225 4.574631 -3.838192 17.04812 5.9125 -2.225488 29.4768 4.070064 8.146659 16.15608 5.9125 9.674749 27.93266 4.574631 8.062045 15.50399 6.570064 9.739676 28.43303 4.891814 7.96351 14.7446 7.074631 9.82429 29.08513 -12 12.06489 46.35287 -7.5 12.06489 46.35287 -7.5 10.02857 30.65943 -5 7.857769 13.92968 5 7.857769 13.92968 7.5 10.02857 30.65943 12 12.06489 46.35287 7.391814 9.922825 29.84452 7.5 12.06489 46.35287 -5.9125 9.674749 27.93266 -5.14675 9.633935 27.61812 -4.070064 8.146659 16.15608 -6.570064 9.739676 28.43303 -4.574631 8.062045 15.50399 -4.325 9.620013 27.51083 -3.4125 8.211586 16.65646 -2.64675 8.2524 16.971 -7.074631 9.82429 29.08513 -4.891814 7.96351 14.7446 4.325 9.620013 27.51083 -1.825 8.266322 17.07829 1.825 8.266322 17.07829 2.64675 8.2524 16.971 5.14675 9.633935 27.61812 3.4125 8.211586 16.65646 -7.391814 9.922825 29.84452 -12 9.934158 51.75228 -7.5 9.934158 51.75228 -7.5 10.42824 51.29555 -7.5 9.392044 52.15082 -12 9.392044 52.15082 -7.5 0.2885143 48.55835 -12 10.42824 51.29555 -12 0.2885143 48.55835 -7.5 0.4856401 49.20168 -12 10.86808 50.78637 -7.5 10.86808 50.78637 -7.5 11.24814 50.23115 -12 0.4856401 49.20168 -12 11.24814 50.23115 -12 0.7535556 49.81888 -7.5 0.7535556 49.81888 -7.5 1.088892 50.40221 -12 11.56365 49.63687 -7.5 11.56365 49.63687 -12 1.088892 50.40221 -12 11.81063 49.01099 -7.5 11.81063 49.01099 -12 1.487431 50.94432 -7.5 1.487431 50.94432 -7.5 1.944162 51.4384 -12 11.98599 48.3614 -7.5 11.98599 48.3614 -12 1.944162 51.4384 -7.5 2.453341 51.87824 -12 12.08751 47.69626 -7.5 12.08751 47.69626 -7.5 12.11393 47.02393 -12 12.11393 47.02393 -12 2.453341 51.87824 -7.5 3.008564 52.25831 -12 3.008564 52.25831 -7.5 3.60285 52.57381 -12 3.60285 52.57381 -7.5 4.228725 52.8208 -12 4.228725 52.8208 -12 4.878318 52.99616 -7.5 4.878318 52.99616 -12 5.54346 53.09768 -7.5 5.54346 53.09768 -7.5 6.215787 53.12409 -12 6.215787 53.12409 -12 6.886843 53.07506 -7.5 6.886843 53.07506 -7.5 7.548191 52.9512 -12 7.548191 52.9512 -12 8.191512 52.75407 -7.5 8.191512 52.75407 -12 8.808717 52.48616 -7.5 8.808717 52.48616 7.5 9.392044 52.15082 12 9.392044 52.15082 12 9.934158 51.75228 12 8.808717 52.48616 7.5 9.934158 51.75228 12 0.2885143 48.55835 7.5 10.42824 51.29555 12 10.42824 51.29555 12 10.86808 50.78637 7.5 0.2885143 48.55835 7.5 10.86808 50.78637 12 11.24814 50.23115 7.5 0.4856401 49.20168 12 0.4856401 49.20168 12 0.7535556 49.81888 7.5 11.24814 50.23115 12 11.56365 49.63687 7.5 0.7535556 49.81888 7.5 11.56365 49.63687 12 11.81063 49.01099 7.5 1.088892 50.40221 12 1.088892 50.40221 7.5 11.81063 49.01099 12 11.98599 48.3614 7.5 1.487431 50.94432 12 1.487431 50.94432 12 1.944162 51.4384 7.5 11.98599 48.3614 7.5 12.08751 47.69626 12 12.08751 47.69626 7.5 1.944162 51.4384 7.5 12.11393 47.02393 12 12.11393 47.02393 7.5 2.453341 51.87824 12 2.453341 51.87824 7.5 3.008564 52.25831 12 3.008564 52.25831 12 3.60285 52.57381 7.5 3.60285 52.57381 12 4.228725 52.8208 7.5 4.228725 52.8208 12 4.878318 52.99616 7.5 4.878318 52.99616 7.5 5.54346 53.09768 12 5.54346 53.09768 12 6.215787 53.12409 7.5 6.215787 53.12409 12 6.886843 53.07506 7.5 6.886843 53.07506 12 7.548191 52.9512 7.5 7.548191 52.9512 12 8.191512 52.75407 7.5 8.191512 52.75407 7.5 8.808717 52.48616 -12 1.711368 -1.822422 -12 1.204384 -2.190767 -12 2.11082 -1.339567 -12 0.6217247 -2.421458 -12 2.377641 -0.7725425 -12 0 -2.5 -12 2.495067 -0.1569763 -12 -0.6217247 -2.421458 -12 2.455718 0.4684533 -12 -1.204384 -2.190767 -12 2.262068 1.064448 -12 -1.711368 -1.822422 -12 1.926283 1.59356 -12 -2.11082 -1.339567 -12 1.469463 2.022542 -12 -2.377641 -0.7725425 -12 -2.495067 -0.1569763 -12 -2.455718 0.4684533 -12 -2.262068 1.064448 -12 -1.926283 1.59356 -12 -1.469463 2.022542 -12 -0.9203114 2.324441 -12 7.542883 45.07299 -12 8.008316 45.49261 -12 6.987717 44.7823 -12 0.9203114 2.324441 -12 8.354771 46.0148 -12 6.3777 44.6388 -12 0.3133331 2.480287 -12 8.560479 46.60674 -12 5.751163 44.65152 -12 -0.3133331 2.480287 -12 8.612515 47.23124 -12 5.147473 44.81966 -12 8.507608 47.84906 -12 4.604562 45.13264 -12 8.252351 48.42139 -12 7.862782 48.91225 -12 7.363379 49.29081 -12 6.785522 49.53328 -12 3.623409 47.33253 -12 3.650055 46.70643 -12 3.831568 46.10663 -12 4.156544 45.57081 -12 6.16552 49.62442 -12 3.753305 47.94558 -12 5.542329 49.55852 -12 4.031581 48.50708 -12 4.955107 49.3397 -12 4.440751 48.98172 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 4 1 5 1 6 2 2 2 7 2 6 3 7 3 8 3 6 4 0 4 2 4 9 5 5 5 10 5 9 6 3 6 5 6 11 7 6 7 8 7 12 8 8 8 13 8 14 9 10 9 15 9 14 10 9 10 10 10 12 11 11 11 8 11 3 12 13 12 4 12 3 13 12 13 13 13 16 14 15 14 17 14 16 15 14 15 15 15 18 16 17 16 19 16 18 17 16 17 17 17 20 18 19 18 21 18 20 19 18 19 19 19 22 20 21 20 23 20 22 21 20 21 21 21 24 22 23 22 25 22 24 23 22 23 23 23 26 24 24 24 25 24 27 25 25 25 28 25 27 26 28 26 29 26 27 27 26 27 25 27 30 28 29 28 31 28 30 29 27 29 29 29 32 30 30 30 31 30 32 31 31 31 33 31 34 32 32 32 33 32 35 33 34 33 33 33 35 34 33 34 36 34 35 35 36 35 37 35 38 36 35 36 37 36 39 37 38 37 37 37 39 38 37 38 40 38 39 39 40 39 41 39 42 40 39 40 41 40 43 41 41 41 44 41 43 42 44 42 45 42 43 43 42 43 41 43 46 44 45 44 47 44 46 45 43 45 45 45 48 46 46 46 47 46 1 47 47 47 49 47 1 48 49 48 2 48 1 49 48 49 47 49 50 50 51 50 52 50 50 51 53 51 51 51 54 52 52 52 55 52 54 53 50 53 52 53 56 54 55 54 57 54 58 55 59 55 60 55 56 56 54 56 55 56 58 57 61 57 59 57 62 58 57 58 63 58 64 59 60 59 65 59 62 60 56 60 57 60 64 61 58 61 60 61 66 62 63 62 67 62 66 63 67 63 68 63 66 64 62 64 63 64 69 65 65 65 70 65 69 66 64 66 65 66 71 67 66 67 68 67 72 68 70 68 73 68 61 69 68 69 59 69 72 70 69 70 70 70 61 71 71 71 68 71 74 72 73 72 75 72 74 73 72 73 73 73 76 74 75 74 77 74 76 75 74 75 75 75 78 76 77 76 79 76 78 77 76 77 77 77 80 78 79 78 81 78 80 79 78 79 79 79 82 80 81 80 83 80 82 81 80 81 81 81 84 82 83 82 85 82 84 83 82 83 83 83 86 84 85 84 87 84 86 85 84 85 85 85 88 86 86 86 87 86 88 87 87 87 89 87 90 88 88 88 89 88 90 89 89 89 91 89 92 90 90 90 91 90 92 91 91 91 93 91 94 92 93 92 95 92 94 93 92 93 93 93 96 94 95 94 97 94 96 95 94 95 95 95 98 96 97 96 99 96 98 97 96 97 97 97 53 98 99 98 51 98 53 99 98 99 99 99 100 100 101 100 102 100 100 101 103 101 101 101 104 102 105 102 106 102 107 103 102 103 108 103 107 104 100 104 102 104 109 105 106 105 110 105 109 106 104 106 106 106 111 107 108 107 105 107 111 108 107 108 108 108 104 109 111 109 105 109 112 110 110 110 113 110 112 111 109 111 110 111 114 112 113 112 115 112 114 113 112 113 113 113 116 114 115 114 117 114 116 115 114 115 115 115 118 116 117 116 119 116 118 117 116 117 117 117 120 118 119 118 121 118 120 119 118 119 119 119 122 120 121 120 123 120 122 121 120 121 121 121 124 122 123 122 125 122 124 123 122 123 123 123 126 124 125 124 127 124 126 125 124 125 125 125 128 126 127 126 129 126 128 127 126 127 127 127 130 128 128 128 129 128 130 129 129 129 131 129 132 130 130 130 131 130 132 131 131 131 133 131 134 132 132 132 133 132 134 133 133 133 135 133 136 134 134 134 135 134 136 135 135 135 137 135 138 136 136 136 137 136 138 137 137 137 139 137 140 138 139 138 141 138 140 139 138 139 139 139 142 140 141 140 143 140 142 141 140 141 141 141 144 142 143 142 145 142 144 143 142 143 143 143 146 144 145 144 147 144 146 145 144 145 145 145 148 146 147 146 149 146 148 147 146 147 147 147 103 148 149 148 101 148 103 149 148 149 149 149 150 150 151 150 152 150 150 151 153 151 151 151 154 152 152 152 155 152 154 153 150 153 152 153 156 154 155 154 157 154 156 155 154 155 155 155 158 156 159 156 160 156 158 157 161 157 159 157 162 158 157 158 163 158 162 159 156 159 157 159 164 160 160 160 165 160 164 161 158 161 160 161 166 162 163 162 167 162 166 163 162 163 163 163 168 164 165 164 169 164 168 165 164 165 165 165 170 166 167 166 171 166 170 167 166 167 167 167 172 168 169 168 173 168 161 169 171 169 159 169 172 170 168 170 169 170 161 171 170 171 171 171 174 172 173 172 175 172 174 173 172 173 173 173 176 174 175 174 177 174 176 175 174 175 175 175 178 176 177 176 179 176 178 177 176 177 177 177 180 178 179 178 181 178 180 179 178 179 179 179 182 180 181 180 183 180 182 181 180 181 181 181 184 182 183 182 185 182 184 183 182 183 183 183 186 184 185 184 187 184 186 185 184 185 185 185 188 186 186 186 187 186 188 187 187 187 189 187 190 188 188 188 189 188 190 189 189 189 191 189 192 190 191 190 193 190 192 191 190 191 191 191 194 192 193 192 195 192 194 193 192 193 193 193 196 194 195 194 197 194 196 195 194 195 195 195 198 196 197 196 199 196 198 197 196 197 197 197 153 198 199 198 151 198 153 199 198 199 199 199 200 200 201 200 202 200 203 201 202 201 204 201 203 202 200 202 202 202 205 203 204 203 206 203 205 204 206 204 207 204 208 205 209 205 210 205 205 206 203 206 204 206 208 207 210 207 211 207 208 208 212 208 209 208 213 209 205 209 207 209 214 210 208 210 211 210 215 211 207 211 216 211 215 212 213 212 207 212 217 213 211 213 218 213 217 214 214 214 211 214 212 215 216 215 209 215 212 216 215 216 216 216 219 217 218 217 220 217 219 218 220 218 221 218 219 219 217 219 218 219 222 220 221 220 223 220 222 221 219 221 221 221 224 222 222 222 223 222 225 223 223 223 226 223 225 224 226 224 227 224 225 225 224 225 223 225 228 226 227 226 229 226 228 227 225 227 227 227 230 228 229 228 231 228 230 229 228 229 229 229 232 230 231 230 233 230 232 231 230 231 231 231 234 232 232 232 233 232 235 233 234 233 233 233 235 234 233 234 236 234 237 235 235 235 236 235 237 236 236 236 238 236 237 237 238 237 239 237 240 238 237 238 239 238 241 239 240 239 239 239 241 240 239 240 242 240 241 241 242 241 243 241 244 242 241 242 243 242 245 243 243 243 246 243 245 244 244 244 243 244 247 245 246 245 248 245 247 246 245 246 246 246 201 247 248 247 249 247 201 248 249 248 202 248 201 249 247 249 248 249 250 250 251 250 252 250 253 251 252 251 254 251 253 252 250 252 252 252 255 253 254 253 256 253 257 254 258 254 259 254 257 255 259 255 260 255 255 256 253 256 254 256 257 257 261 257 258 257 262 258 256 258 263 258 262 259 263 259 264 259 262 260 255 260 256 260 265 261 257 261 260 261 266 262 264 262 258 262 266 263 262 263 264 263 267 264 260 264 268 264 267 265 268 265 269 265 267 266 265 266 260 266 261 267 266 267 258 267 270 268 267 268 269 268 271 269 269 269 272 269 271 270 272 270 273 270 271 271 270 271 269 271 274 272 271 272 273 272 275 273 273 273 276 273 275 274 274 274 273 274 277 275 276 275 278 275 277 276 275 276 276 276 279 277 278 277 280 277 279 278 277 278 278 278 281 279 280 279 282 279 281 280 282 280 283 280 281 281 279 281 280 281 284 282 281 282 283 282 285 283 283 283 286 283 285 284 284 284 283 284 287 285 285 285 286 285 287 286 286 286 288 286 289 287 287 287 288 287 289 288 288 288 290 288 291 289 290 289 292 289 291 290 292 290 293 290 291 291 289 291 290 291 294 292 291 292 293 292 295 293 293 293 296 293 295 294 296 294 297 294 295 295 294 295 293 295 298 296 295 296 297 296 251 297 297 297 299 297 251 298 299 298 252 298 251 299 298 299 297 299 300 300 301 300 302 300 300 301 303 301 301 301 304 302 302 302 305 302 304 303 300 303 302 303 306 304 307 304 308 304 306 305 309 305 307 305 310 306 305 306 311 306 310 307 304 307 305 307 312 308 308 308 313 308 312 309 306 309 308 309 314 310 311 310 315 310 314 311 310 311 311 311 316 312 313 312 317 312 316 313 312 313 313 313 318 314 315 314 319 314 318 315 314 315 315 315 320 316 317 316 321 316 320 317 316 317 317 317 322 318 319 318 323 318 322 319 318 319 319 319 324 320 321 320 325 320 324 321 320 321 321 321 326 322 323 322 327 322 326 323 322 323 323 323 328 324 325 324 329 324 328 325 324 325 325 325 330 326 327 326 331 326 330 327 326 327 327 327 332 328 329 328 333 328 334 329 331 329 335 329 332 330 328 330 329 330 334 331 330 331 331 331 336 332 335 332 337 332 336 333 334 333 335 333 338 334 333 334 339 334 340 335 337 335 341 335 338 336 332 336 333 336 340 337 336 337 337 337 342 338 339 338 343 338 342 339 338 339 339 339 344 340 342 340 343 340 344 341 343 341 345 341 346 342 344 342 345 342 346 343 345 343 347 343 348 344 346 344 347 344 348 345 347 345 349 345 350 346 349 346 351 346 350 347 348 347 349 347 352 348 351 348 353 348 352 349 350 349 351 349 354 350 352 350 353 350 354 351 353 351 355 351 356 352 355 352 357 352 356 353 354 353 355 353 303 354 357 354 301 354 303 355 356 355 357 355 358 356 359 356 360 356 358 357 361 357 359 357 362 358 360 358 363 358 362 359 358 359 360 359 364 360 365 360 366 360 364 361 367 361 365 361 368 362 363 362 369 362 368 363 362 363 363 363 370 364 366 364 371 364 370 365 364 365 366 365 372 366 373 366 374 366 372 367 369 367 373 367 372 368 368 368 369 368 375 369 371 369 376 369 375 370 370 370 371 370 377 371 374 371 378 371 377 372 372 372 374 372 379 373 376 373 380 373 379 374 375 374 376 374 381 375 378 375 382 375 381 376 377 376 378 376 383 377 382 377 384 377 385 378 380 378 386 378 383 379 381 379 382 379 385 380 379 380 380 380 387 381 384 381 388 381 387 382 383 382 384 382 389 383 386 383 390 383 389 384 385 384 386 384 391 385 388 385 392 385 391 386 387 386 388 386 393 387 390 387 394 387 395 388 392 388 396 388 393 389 389 389 390 389 395 390 391 390 392 390 397 391 395 391 396 391 398 392 394 392 399 392 398 393 393 393 394 393 400 394 399 394 401 394 400 395 398 395 399 395 402 396 400 396 401 396 402 397 401 397 403 397 404 398 402 398 403 398 404 399 403 399 405 399 406 400 404 400 405 400 406 401 405 401 407 401 408 402 407 402 409 402 408 403 406 403 407 403 410 404 409 404 411 404 410 405 408 405 409 405 412 406 410 406 411 406 412 407 411 407 413 407 414 408 413 408 415 408 414 409 412 409 413 409 361 410 415 410 359 410 361 411 414 411 415 411 416 412 417 412 418 412 416 413 418 413 419 413 416 414 420 414 417 414 421 415 416 415 419 415 422 416 419 416 423 416 424 417 425 417 426 417 422 418 421 418 419 418 424 419 427 419 425 419 428 420 423 420 429 420 428 421 429 421 430 421 428 422 422 422 423 422 431 423 426 423 432 423 431 424 424 424 426 424 433 425 428 425 430 425 434 426 432 426 435 426 427 427 430 427 425 427 434 428 431 428 432 428 427 429 433 429 430 429 436 430 435 430 437 430 436 431 434 431 435 431 438 432 437 432 439 432 438 433 436 433 437 433 440 434 439 434 441 434 440 435 441 435 442 435 440 436 438 436 439 436 443 437 440 437 442 437 444 438 442 438 445 438 444 439 445 439 446 439 444 440 443 440 442 440 447 441 446 441 448 441 447 442 444 442 446 442 449 443 447 443 448 443 450 444 448 444 451 444 450 445 451 445 452 445 450 446 449 446 448 446 453 447 450 447 452 447 454 448 453 448 452 448 454 449 452 449 455 449 454 450 455 450 456 450 457 451 454 451 456 451 457 452 456 452 458 452 459 453 458 453 460 453 459 454 457 454 458 454 461 455 460 455 462 455 461 456 459 456 460 456 463 457 461 457 462 457 464 458 462 458 465 458 464 459 465 459 417 459 464 460 463 460 462 460 420 461 464 461 417 461 466 462 467 462 468 462 469 463 468 463 470 463 469 464 470 464 471 464 469 465 466 465 468 465 472 466 473 466 474 466 475 467 469 467 471 467 472 468 476 468 473 468 477 469 471 469 478 469 477 470 478 470 479 470 480 471 474 471 481 471 477 472 475 472 471 472 480 473 472 473 474 473 482 474 479 474 473 474 482 475 477 475 479 475 483 476 481 476 484 476 483 477 480 477 481 477 476 478 482 478 473 478 485 479 484 479 486 479 485 480 483 480 484 480 487 481 486 481 488 481 487 482 488 482 489 482 487 483 485 483 486 483 490 484 487 484 489 484 491 485 489 485 492 485 491 486 490 486 489 486 493 487 492 487 494 487 493 488 491 488 492 488 495 489 494 489 496 489 495 490 496 490 497 490 495 491 493 491 494 491 498 492 495 492 497 492 499 493 497 493 500 493 499 494 500 494 501 494 499 495 498 495 497 495 502 496 501 496 503 496 502 497 499 497 501 497 504 498 502 498 503 498 505 499 504 499 503 499 505 500 503 500 506 500 505 501 506 501 507 501 508 502 505 502 507 502 509 503 507 503 510 503 509 504 508 504 507 504 511 505 510 505 512 505 511 506 509 506 510 506 513 507 512 507 514 507 513 508 511 508 512 508 467 509 514 509 515 509 467 510 515 510 468 510 467 511 513 511 514 511 516 512 517 512 518 512 516 513 519 513 517 513 520 514 516 514 518 514 521 515 518 515 522 515 521 516 522 516 523 516 521 517 520 517 518 517 524 518 525 518 526 518 524 519 526 519 527 519 524 520 528 520 525 520 529 521 523 521 530 521 529 522 521 522 523 522 531 523 524 523 527 523 532 524 530 524 525 524 532 525 529 525 530 525 533 526 527 526 534 526 528 527 532 527 525 527 533 528 534 528 535 528 533 529 531 529 527 529 536 530 533 530 535 530 537 531 535 531 538 531 537 532 538 532 539 532 537 533 536 533 535 533 540 534 537 534 539 534 541 535 539 535 542 535 541 536 540 536 539 536 543 537 542 537 544 537 543 538 541 538 542 538 545 539 544 539 546 539 545 540 543 540 544 540 547 541 546 541 548 541 547 542 548 542 549 542 547 543 545 543 546 543 550 544 547 544 549 544 551 545 549 545 552 545 551 546 550 546 549 546 553 547 551 547 552 547 553 548 552 548 554 548 555 549 553 549 554 549 555 550 554 550 556 550 557 551 556 551 558 551 557 552 558 552 559 552 557 553 555 553 556 553 560 554 557 554 559 554 561 555 559 555 562 555 561 556 562 556 563 556 561 557 560 557 559 557 564 558 563 558 565 558 564 559 561 559 563 559 519 560 565 560 517 560 519 561 564 561 565 561 566 562 567 562 568 562 566 563 569 563 567 563 570 564 568 564 571 564 570 565 566 565 568 565 572 566 571 566 573 566 574 567 575 567 576 567 572 568 570 568 571 568 574 569 577 569 575 569 578 570 573 570 579 570 580 571 576 571 581 571 578 572 572 572 573 572 580 573 574 573 576 573 582 574 579 574 583 574 582 575 578 575 579 575 584 576 581 576 585 576 584 577 580 577 581 577 586 578 583 578 587 578 586 579 582 579 583 579 588 580 585 580 589 580 588 581 584 581 585 581 577 582 587 582 575 582 577 583 586 583 587 583 590 584 589 584 591 584 590 585 588 585 589 585 592 586 591 586 593 586 592 587 590 587 591 587 594 588 593 588 595 588 594 589 592 589 593 589 596 590 595 590 597 590 596 591 594 591 595 591 598 592 597 592 599 592 598 593 596 593 597 593 600 594 599 594 601 594 600 595 598 595 599 595 602 596 601 596 603 596 602 597 600 597 601 597 604 598 602 598 603 598 604 599 603 599 605 599 606 600 604 600 605 600 606 601 605 601 607 601 608 602 606 602 607 602 608 603 607 603 609 603 610 604 609 604 611 604 610 605 608 605 609 605 612 606 611 606 613 606 612 607 610 607 611 607 614 608 613 608 615 608 614 609 612 609 613 609 569 610 615 610 567 610 569 611 614 611 615 611 592 612 616 612 590 612 617 613 606 613 618 613 619 614 616 614 592 614 572 615 620 615 621 615 604 616 606 616 617 616 582 617 622 617 620 617 594 618 619 618 592 618 623 619 622 619 582 619 624 620 604 620 617 620 570 621 572 621 621 621 602 622 604 622 624 622 625 623 570 623 621 623 626 624 619 624 594 624 586 625 623 625 582 625 596 626 626 626 594 626 627 627 623 627 586 627 566 628 570 628 625 628 628 629 602 629 624 629 628 630 600 630 602 630 577 631 627 631 586 631 629 632 596 632 598 632 629 633 626 633 596 633 630 634 566 634 625 634 631 635 598 635 600 635 631 636 600 636 628 636 631 637 629 637 598 637 632 638 627 638 577 638 572 639 578 639 620 639 620 640 578 640 582 640 569 641 566 641 630 641 574 642 632 642 577 642 633 643 569 643 630 643 634 644 632 644 574 644 614 645 569 645 633 645 580 646 634 646 574 646 635 647 614 647 633 647 636 648 634 648 580 648 612 649 614 649 635 649 584 650 636 650 580 650 637 651 612 651 635 651 638 652 636 652 584 652 610 653 612 653 637 653 588 654 638 654 584 654 639 655 610 655 637 655 640 656 638 656 588 656 608 657 610 657 639 657 590 658 640 658 588 658 618 659 608 659 639 659 616 660 640 660 590 660 606 661 608 661 618 661 528 662 575 662 532 662 593 663 541 663 595 663 613 664 557 664 560 664 540 665 541 665 593 665 611 666 557 666 613 666 561 667 613 667 560 667 615 668 613 668 561 668 609 669 555 669 557 669 609 670 557 670 611 670 524 671 576 671 575 671 524 672 575 672 528 672 564 673 615 673 561 673 537 674 593 674 591 674 537 675 540 675 593 675 567 676 615 676 564 676 553 677 555 677 609 677 607 678 553 678 609 678 531 679 581 679 576 679 531 680 585 680 581 680 531 681 576 681 524 681 568 682 564 682 519 682 536 683 591 683 589 683 536 684 537 684 591 684 533 685 589 685 585 685 568 686 567 686 564 686 533 687 585 687 531 687 533 688 536 688 589 688 551 689 553 689 607 689 605 690 551 690 607 690 516 691 568 691 519 691 571 692 568 692 516 692 603 693 550 693 551 693 603 694 551 694 605 694 573 695 516 695 520 695 573 696 571 696 516 696 547 697 550 697 603 697 601 698 547 698 603 698 521 699 579 699 573 699 521 700 573 700 520 700 545 701 547 701 601 701 545 702 601 702 599 702 529 703 579 703 521 703 529 704 583 704 579 704 597 705 545 705 599 705 543 706 545 706 597 706 532 707 583 707 529 707 532 708 587 708 583 708 541 709 543 709 597 709 541 710 597 710 595 710 575 711 587 711 532 711 517 712 522 712 518 712 530 713 523 713 522 713 563 714 517 714 565 714 563 715 522 715 517 715 526 716 525 716 530 716 562 717 522 717 563 717 558 718 562 718 559 718 538 719 527 719 526 719 538 720 534 720 527 720 538 721 535 721 534 721 554 722 558 722 556 722 554 723 526 723 530 723 554 724 530 724 522 724 554 725 522 725 562 725 554 726 562 726 558 726 542 727 539 727 538 727 549 728 554 728 552 728 546 729 544 729 542 729 546 730 549 730 548 730 546 731 526 731 554 731 546 732 538 732 526 732 546 733 554 733 549 733 546 734 542 734 538 734 511 735 508 735 509 735 504 736 505 736 508 736 466 737 511 737 513 737 466 738 513 738 467 738 499 739 502 739 504 739 475 740 466 740 469 740 475 741 508 741 511 741 475 742 504 742 508 742 475 743 499 743 504 743 475 744 511 744 466 744 495 745 498 745 499 745 495 746 499 746 475 746 482 747 475 747 477 747 482 748 495 748 475 748 491 749 493 749 495 749 472 750 482 750 476 750 472 751 495 751 482 751 487 752 490 752 491 752 487 753 491 753 495 753 487 754 495 754 472 754 480 755 487 755 472 755 483 756 485 756 487 756 483 757 487 757 480 757 489 758 488 758 440 758 422 759 471 759 470 759 421 760 422 760 470 760 501 761 454 761 503 761 501 762 453 762 454 762 428 763 478 763 471 763 428 764 471 764 422 764 443 765 489 765 440 765 468 766 421 766 470 766 492 767 489 767 443 767 416 768 421 768 468 768 444 769 492 769 443 769 433 770 479 770 478 770 433 771 478 771 428 771 500 772 453 772 501 772 500 773 450 773 453 773 494 774 492 774 444 774 515 775 416 775 468 775 420 776 416 776 515 776 473 777 479 777 433 777 447 778 494 778 444 778 427 779 473 779 433 779 497 780 449 780 450 780 514 781 420 781 515 781 497 782 450 782 500 782 496 783 494 783 447 783 496 784 447 784 449 784 496 785 449 785 497 785 464 786 420 786 514 786 474 787 473 787 427 787 424 788 474 788 427 788 512 789 464 789 514 789 463 790 464 790 512 790 431 791 481 791 474 791 431 792 474 792 424 792 510 793 463 793 512 793 461 794 463 794 510 794 434 795 484 795 481 795 434 796 481 796 431 796 507 797 461 797 510 797 507 798 459 798 461 798 436 799 484 799 434 799 486 800 484 800 436 800 506 801 459 801 507 801 506 802 457 802 459 802 438 803 486 803 436 803 488 804 486 804 438 804 503 805 457 805 506 805 503 806 454 806 457 806 440 807 488 807 438 807 425 808 430 808 641 808 460 809 642 809 643 809 644 810 425 810 641 810 645 811 646 811 442 811 458 812 642 812 460 812 645 813 442 813 441 813 647 814 642 814 458 814 462 815 643 815 648 815 462 816 460 816 643 816 426 817 425 817 644 817 456 818 647 818 458 818 649 819 426 819 644 819 650 820 441 820 439 820 651 821 647 821 456 821 650 822 645 822 441 822 465 823 648 823 652 823 465 824 462 824 648 824 432 825 426 825 649 825 455 826 651 826 456 826 653 827 435 827 432 827 417 828 652 828 654 828 653 829 432 829 649 829 417 830 465 830 652 830 655 831 439 831 437 831 655 832 650 832 439 832 656 833 651 833 455 833 657 834 437 834 435 834 657 835 435 835 653 835 657 836 655 836 437 836 452 837 656 837 455 837 418 838 417 838 654 838 658 839 418 839 654 839 659 840 656 840 452 840 451 841 659 841 452 841 419 842 418 842 658 842 660 843 419 843 658 843 661 844 659 844 451 844 448 845 661 845 451 845 423 846 419 846 660 846 662 847 423 847 660 847 663 848 661 848 448 848 446 849 663 849 448 849 429 850 423 850 662 850 664 851 429 851 662 851 665 852 663 852 446 852 445 853 665 853 446 853 430 854 429 854 664 854 641 855 430 855 664 855 646 856 665 856 445 856 646 857 445 857 442 857 666 858 667 858 668 858 397 859 396 859 669 859 670 860 671 860 672 860 673 861 674 861 675 861 674 862 341 862 675 862 676 863 341 863 674 863 668 864 341 864 676 864 667 865 341 865 668 865 677 866 341 866 667 866 340 867 341 867 677 867 678 868 679 868 680 868 679 869 681 869 682 869 680 870 679 870 682 870 669 871 678 871 683 871 397 872 669 872 683 872 678 873 680 873 683 873 681 874 684 874 685 874 682 875 681 875 685 875 397 876 683 876 686 876 397 877 686 877 671 877 684 878 687 878 688 878 687 879 689 879 688 879 685 880 684 880 688 880 689 881 690 881 691 881 690 882 692 882 691 882 692 883 693 883 691 883 688 884 689 884 691 884 693 885 694 885 695 885 691 886 693 886 695 886 694 887 696 887 697 887 695 888 694 888 697 888 397 889 671 889 670 889 696 890 667 890 666 890 697 891 696 891 666 891 698 892 699 892 700 892 700 893 701 893 702 893 701 894 703 894 702 894 704 895 705 895 706 895 367 896 707 896 365 896 309 897 708 897 307 897 709 898 710 898 307 898 711 899 709 899 307 899 703 900 711 900 307 900 702 901 703 901 307 901 708 902 702 902 307 902 712 903 710 903 709 903 713 904 714 904 715 904 716 905 713 905 717 905 713 906 715 906 717 906 714 907 718 907 719 907 715 908 714 908 719 908 719 909 718 909 720 909 721 910 716 910 722 910 716 911 717 911 722 911 718 912 723 912 724 912 720 913 718 913 724 913 721 914 722 914 707 914 724 915 723 915 725 915 725 916 723 916 726 916 723 917 727 917 728 917 726 918 723 918 728 918 727 919 699 919 698 919 728 920 727 920 698 920 706 921 729 921 367 921 729 922 721 922 367 922 704 923 706 923 367 923 721 924 707 924 367 924 699 925 701 925 700 925 730 926 731 926 732 926 730 927 733 927 731 927 730 928 734 928 733 928 670 929 672 929 735 929 736 930 730 930 732 930 737 931 735 931 738 931 737 932 670 932 735 932 739 933 740 933 741 933 739 934 732 934 740 934 739 935 736 935 732 935 742 936 737 936 738 936 743 937 739 937 741 937 744 938 745 938 746 938 744 939 738 939 745 939 744 940 742 940 738 940 747 941 741 941 748 941 747 942 743 942 741 942 749 943 744 943 746 943 750 944 748 944 751 944 750 945 747 945 748 945 752 946 753 946 754 946 752 947 746 947 753 947 752 948 749 948 746 948 755 949 751 949 756 949 755 950 750 950 751 950 757 951 754 951 758 951 757 952 752 952 754 952 759 953 760 953 761 953 759 954 756 954 760 954 759 955 755 955 756 955 762 956 759 956 761 956 763 957 758 957 764 957 763 958 757 958 758 958 704 959 761 959 705 959 704 960 762 960 761 960 765 961 764 961 766 961 765 962 763 962 764 962 767 963 766 963 768 963 767 964 765 964 766 964 769 965 767 965 768 965 770 966 769 966 768 966 770 967 768 967 771 967 772 968 770 968 771 968 772 969 773 969 774 969 772 970 771 970 773 970 775 971 772 971 774 971 776 972 777 972 778 972 776 973 774 973 777 973 776 974 775 974 774 974 779 975 776 975 778 975 780 976 778 976 781 976 780 977 779 977 778 977 782 978 780 978 781 978 782 979 783 979 733 979 782 980 781 980 783 980 734 981 782 981 733 981 784 982 785 982 786 982 784 983 787 983 785 983 788 984 784 984 786 984 673 985 675 985 789 985 790 986 791 986 792 986 790 987 786 987 791 987 790 988 788 988 786 988 793 989 673 989 789 989 794 990 792 990 795 990 794 991 790 991 792 991 796 992 797 992 798 992 796 993 789 993 797 993 796 994 793 994 789 994 799 995 795 995 800 995 799 996 794 996 795 996 801 997 796 997 798 997 802 998 800 998 803 998 802 999 799 999 800 999 804 1000 798 1000 805 1000 806 1001 803 1001 807 1001 804 1002 801 1002 798 1002 806 1003 802 1003 803 1003 808 1004 809 1004 810 1004 811 1005 806 1005 807 1005 808 1006 805 1006 809 1006 808 1007 804 1007 805 1007 812 1008 807 1008 813 1008 812 1009 811 1009 807 1009 814 1010 808 1010 810 1010 815 1011 816 1011 710 1011 815 1012 813 1012 816 1012 815 1013 812 1013 813 1013 712 1014 815 1014 710 1014 817 1015 810 1015 818 1015 817 1016 814 1016 810 1016 819 1017 820 1017 821 1017 819 1018 818 1018 820 1018 819 1019 817 1019 818 1019 822 1020 821 1020 823 1020 822 1021 819 1021 821 1021 824 1022 823 1022 825 1022 824 1023 822 1023 823 1023 826 1024 824 1024 825 1024 827 1025 826 1025 825 1025 827 1026 828 1026 829 1026 827 1027 825 1027 828 1027 830 1028 827 1028 829 1028 830 1029 829 1029 831 1029 832 1030 830 1030 831 1030 832 1031 831 1031 833 1031 834 1032 832 1032 833 1032 834 1033 833 1033 835 1033 836 1034 834 1034 835 1034 837 1035 836 1035 835 1035 837 1036 835 1036 787 1036 784 1037 837 1037 787 1037 635 1038 343 1038 339 1038 635 1039 339 1039 333 1039 637 1040 635 1040 333 1040 637 1041 333 1041 329 1041 637 1042 329 1042 325 1042 637 1043 325 1043 321 1043 633 1044 343 1044 635 1044 633 1045 347 1045 345 1045 633 1046 345 1046 343 1046 639 1047 637 1047 321 1047 639 1048 321 1048 317 1048 639 1049 317 1049 313 1049 630 1050 347 1050 633 1050 630 1051 351 1051 349 1051 630 1052 349 1052 347 1052 618 1053 639 1053 313 1053 618 1054 313 1054 308 1054 618 1055 308 1055 307 1055 625 1056 351 1056 630 1056 625 1057 357 1057 355 1057 625 1058 355 1058 353 1058 625 1059 353 1059 351 1059 617 1060 618 1060 307 1060 621 1061 357 1061 625 1061 621 1062 302 1062 301 1062 621 1063 301 1063 357 1063 624 1064 617 1064 307 1064 620 1065 311 1065 305 1065 620 1066 305 1066 302 1066 620 1067 302 1067 621 1067 628 1068 624 1068 307 1068 622 1069 315 1069 311 1069 622 1070 311 1070 620 1070 631 1071 628 1071 307 1071 319 1072 315 1072 622 1072 623 1073 319 1073 622 1073 629 1074 631 1074 307 1074 323 1075 319 1075 623 1075 327 1076 323 1076 623 1076 331 1077 623 1077 627 1077 331 1078 327 1078 623 1078 335 1079 331 1079 627 1079 337 1080 335 1080 627 1080 337 1081 627 1081 632 1081 341 1082 632 1082 634 1082 341 1083 634 1083 636 1083 341 1084 636 1084 638 1084 341 1085 638 1085 640 1085 341 1086 337 1086 632 1086 710 1087 629 1087 307 1087 662 1088 629 1088 710 1088 662 1089 710 1089 664 1089 641 1090 664 1090 710 1090 660 1091 629 1091 662 1091 660 1092 626 1092 629 1092 644 1093 641 1093 710 1093 658 1094 626 1094 660 1094 658 1095 619 1095 626 1095 649 1096 710 1096 816 1096 649 1097 816 1097 813 1097 649 1098 644 1098 710 1098 654 1099 619 1099 658 1099 654 1100 616 1100 619 1100 653 1101 813 1101 807 1101 653 1102 807 1102 803 1102 653 1103 649 1103 813 1103 652 1104 616 1104 654 1104 652 1105 640 1105 616 1105 657 1106 803 1106 800 1106 657 1107 800 1107 795 1107 657 1108 653 1108 803 1108 648 1109 640 1109 652 1109 655 1110 795 1110 792 1110 655 1111 657 1111 795 1111 791 1112 655 1112 792 1112 650 1113 655 1113 791 1113 786 1114 650 1114 791 1114 785 1115 650 1115 786 1115 787 1116 650 1116 785 1116 787 1117 645 1117 650 1117 835 1118 645 1118 787 1118 833 1119 645 1119 835 1119 833 1120 646 1120 645 1120 675 1121 341 1121 640 1121 675 1122 640 1122 648 1122 675 1123 648 1123 643 1123 675 1124 643 1124 642 1124 675 1125 642 1125 647 1125 675 1126 647 1126 651 1126 831 1127 646 1127 833 1127 789 1128 675 1128 651 1128 829 1129 665 1129 646 1129 829 1130 646 1130 831 1130 797 1131 651 1131 656 1131 797 1132 789 1132 651 1132 828 1133 665 1133 829 1133 798 1134 797 1134 656 1134 825 1135 665 1135 828 1135 825 1136 663 1136 665 1136 805 1137 798 1137 656 1137 805 1138 656 1138 659 1138 823 1139 663 1139 825 1139 809 1140 805 1140 659 1140 821 1141 663 1141 823 1141 810 1142 809 1142 659 1142 810 1143 659 1143 661 1143 820 1144 663 1144 821 1144 820 1145 661 1145 663 1145 818 1146 810 1146 661 1146 818 1147 661 1147 820 1147 389 1148 393 1148 838 1148 385 1149 389 1149 838 1149 838 1150 393 1150 839 1150 398 1151 400 1151 839 1151 393 1152 398 1152 839 1152 385 1153 838 1153 840 1153 379 1154 385 1154 840 1154 375 1155 379 1155 840 1155 404 1156 406 1156 841 1156 402 1157 404 1157 841 1157 400 1158 402 1158 841 1158 839 1159 400 1159 841 1159 375 1160 840 1160 842 1160 370 1161 375 1161 842 1161 364 1162 370 1162 842 1162 841 1163 406 1163 843 1163 408 1164 410 1164 843 1164 406 1165 408 1165 843 1165 364 1166 842 1166 844 1166 367 1167 364 1167 844 1167 843 1168 410 1168 845 1168 412 1169 414 1169 845 1169 410 1170 412 1170 845 1170 367 1171 844 1171 846 1171 361 1172 358 1172 847 1172 414 1173 361 1173 847 1173 845 1174 414 1174 847 1174 367 1175 846 1175 848 1175 362 1176 368 1176 849 1176 358 1177 362 1177 849 1177 847 1178 358 1178 849 1178 849 1179 368 1179 372 1179 367 1180 848 1180 850 1180 849 1181 372 1181 851 1181 851 1182 372 1182 377 1182 367 1183 850 1183 852 1183 853 1184 851 1184 381 1184 851 1185 377 1185 381 1185 853 1186 381 1186 383 1186 854 1187 853 1187 387 1187 853 1188 383 1188 387 1188 854 1189 387 1189 391 1189 854 1190 391 1190 395 1190 855 1191 854 1191 395 1191 856 1192 855 1192 397 1192 857 1193 856 1193 397 1193 858 1194 857 1194 397 1194 859 1195 858 1195 397 1195 855 1196 395 1196 397 1196 367 1197 852 1197 704 1197 704 1198 860 1198 861 1198 860 1199 704 1199 862 1199 704 1200 852 1200 862 1200 852 1201 863 1201 862 1201 704 1202 861 1202 864 1202 862 1203 863 1203 865 1203 863 1204 866 1204 865 1204 704 1205 864 1205 867 1205 865 1206 866 1206 868 1206 866 1207 869 1207 868 1207 762 1208 704 1208 870 1208 759 1209 762 1209 870 1209 755 1210 759 1210 870 1210 704 1211 867 1211 870 1211 868 1212 869 1212 871 1212 869 1213 859 1213 871 1213 750 1214 755 1214 872 1214 747 1215 750 1215 872 1215 755 1216 870 1216 872 1216 859 1217 397 1217 873 1217 871 1218 859 1218 873 1218 743 1219 747 1219 874 1219 747 1220 872 1220 874 1220 743 1221 874 1221 739 1221 739 1222 874 1222 875 1222 739 1223 875 1223 736 1223 875 1224 876 1224 730 1224 736 1225 875 1225 730 1225 730 1226 876 1226 734 1226 734 1227 876 1227 782 1227 876 1228 877 1228 780 1228 782 1229 876 1229 780 1229 780 1230 877 1230 779 1230 873 1231 397 1231 670 1231 878 1232 879 1232 670 1232 879 1233 880 1233 670 1233 880 1234 881 1234 670 1234 881 1235 873 1235 670 1235 877 1236 882 1236 776 1236 779 1237 877 1237 776 1237 878 1238 670 1238 737 1238 883 1239 878 1239 737 1239 776 1240 882 1240 775 1240 883 1241 737 1241 742 1241 882 1242 884 1242 772 1242 775 1243 882 1243 772 1243 883 1244 742 1244 744 1244 885 1245 883 1245 744 1245 772 1246 884 1246 770 1246 885 1247 744 1247 749 1247 884 1248 886 1248 769 1248 770 1249 884 1249 769 1249 887 1250 885 1250 752 1250 885 1251 749 1251 752 1251 769 1252 886 1252 767 1252 887 1253 752 1253 757 1253 767 1254 886 1254 765 1254 886 1255 887 1255 763 1255 765 1256 886 1256 763 1256 887 1257 757 1257 763 1257 35 1258 38 1258 366 1258 1 1259 359 1259 415 1259 1 1260 415 1260 413 1260 1 1261 413 1261 48 1261 34 1262 35 1262 365 1262 0 1263 359 1263 1 1263 0 1264 363 1264 360 1264 0 1265 360 1265 359 1265 32 1266 34 1266 365 1266 6 1267 363 1267 0 1267 6 1268 369 1268 363 1268 30 1269 32 1269 365 1269 373 1270 369 1270 6 1270 11 1271 373 1271 6 1271 374 1272 373 1272 11 1272 378 1273 374 1273 11 1273 378 1274 11 1274 12 1274 382 1275 378 1275 12 1275 42 1276 399 1276 394 1276 42 1277 394 1277 390 1277 43 1278 403 1278 401 1278 43 1279 401 1279 399 1279 43 1280 399 1280 42 1280 384 1281 382 1281 12 1281 39 1282 390 1282 386 1282 39 1283 386 1283 380 1283 39 1284 380 1284 376 1284 388 1285 12 1285 3 1285 39 1286 42 1286 390 1286 388 1287 384 1287 12 1287 392 1288 388 1288 3 1288 46 1289 407 1289 405 1289 46 1290 405 1290 403 1290 396 1291 3 1291 9 1291 46 1292 403 1292 43 1292 396 1293 9 1293 14 1293 396 1294 14 1294 16 1294 396 1295 16 1295 18 1295 38 1296 376 1296 371 1296 396 1297 392 1297 3 1297 38 1298 371 1298 366 1298 707 1299 30 1299 365 1299 38 1300 39 1300 376 1300 707 1301 24 1301 26 1301 707 1302 26 1302 27 1302 707 1303 27 1303 30 1303 669 1304 18 1304 20 1304 669 1305 20 1305 22 1305 669 1306 22 1306 24 1306 669 1307 24 1307 707 1307 48 1308 413 1308 411 1308 669 1309 396 1309 18 1309 48 1310 411 1310 409 1310 48 1311 409 1311 407 1311 48 1312 407 1312 46 1312 35 1313 366 1313 365 1313 306 1314 37 1314 36 1314 356 1315 303 1315 49 1315 354 1316 356 1316 49 1316 47 1317 354 1317 49 1317 309 1318 36 1318 33 1318 49 1319 303 1319 2 1319 300 1320 304 1320 2 1320 303 1321 300 1321 2 1321 309 1322 33 1322 31 1322 2 1323 304 1323 7 1323 304 1324 310 1324 7 1324 309 1325 31 1325 29 1325 7 1326 310 1326 314 1326 7 1327 314 1327 8 1327 8 1328 314 1328 318 1328 8 1329 318 1329 322 1329 13 1330 8 1330 322 1330 13 1331 322 1331 326 1331 332 1332 338 1332 41 1332 328 1333 332 1333 41 1333 13 1334 326 1334 330 1334 342 1335 344 1335 44 1335 338 1336 342 1336 44 1336 41 1337 338 1337 44 1337 4 1338 13 1338 334 1338 324 1339 328 1339 40 1339 320 1340 324 1340 40 1340 13 1341 330 1341 334 1341 316 1342 320 1342 40 1342 4 1343 334 1343 336 1343 328 1344 41 1344 40 1344 5 1345 4 1345 340 1345 10 1346 5 1346 340 1346 15 1347 10 1347 340 1347 17 1348 15 1348 340 1348 346 1349 348 1349 45 1349 4 1350 336 1350 340 1350 344 1351 346 1351 45 1351 44 1352 344 1352 45 1352 309 1353 29 1353 708 1353 25 1354 23 1354 708 1354 312 1355 316 1355 37 1355 28 1356 25 1356 708 1356 306 1357 312 1357 37 1357 29 1358 28 1358 708 1358 316 1359 40 1359 37 1359 19 1360 17 1360 677 1360 21 1361 19 1361 677 1361 23 1362 21 1362 677 1362 708 1363 23 1363 677 1363 17 1364 340 1364 677 1364 352 1365 354 1365 47 1365 350 1366 352 1366 47 1366 348 1367 350 1367 47 1367 45 1368 348 1368 47 1368 309 1369 306 1369 36 1369 724 1370 725 1370 689 1370 725 1371 690 1371 689 1371 783 1372 177 1372 733 1372 163 1373 706 1373 705 1373 781 1374 177 1374 783 1374 163 1375 705 1375 167 1375 778 1376 177 1376 781 1376 171 1377 167 1377 705 1377 778 1378 179 1378 177 1378 672 1379 199 1379 197 1379 157 1380 706 1380 163 1380 672 1381 197 1381 195 1381 672 1382 195 1382 193 1382 672 1383 193 1383 191 1383 159 1384 171 1384 705 1384 672 1385 671 1385 199 1385 777 1386 179 1386 778 1386 155 1387 671 1387 706 1387 735 1388 672 1388 191 1388 155 1389 706 1389 157 1389 160 1390 705 1390 761 1390 160 1391 761 1391 760 1391 774 1392 179 1392 777 1392 160 1393 159 1393 705 1393 774 1394 181 1394 179 1394 738 1395 735 1395 191 1395 152 1396 671 1396 155 1396 738 1397 191 1397 189 1397 165 1398 760 1398 756 1398 165 1399 756 1399 751 1399 773 1400 181 1400 774 1400 165 1401 160 1401 760 1401 745 1402 738 1402 189 1402 151 1403 671 1403 152 1403 771 1404 183 1404 181 1404 771 1405 181 1405 773 1405 746 1406 189 1406 187 1406 746 1407 745 1407 189 1407 169 1408 751 1408 748 1408 169 1409 748 1409 741 1409 169 1410 165 1410 751 1410 768 1411 183 1411 771 1411 199 1412 671 1412 151 1412 753 1413 746 1413 187 1413 766 1414 185 1414 183 1414 766 1415 183 1415 768 1415 173 1416 741 1416 740 1416 754 1417 187 1417 185 1417 173 1418 169 1418 741 1418 754 1419 753 1419 187 1419 764 1420 185 1420 766 1420 758 1421 754 1421 185 1421 758 1422 185 1422 764 1422 732 1423 173 1423 740 1423 732 1424 175 1424 173 1424 731 1425 175 1425 732 1425 733 1426 175 1426 731 1426 733 1427 177 1427 175 1427 784 1428 176 1428 837 1428 837 1429 176 1429 836 1429 712 1430 709 1430 162 1430 836 1431 176 1431 834 1431 166 1432 712 1432 162 1432 176 1433 178 1433 834 1433 712 1434 166 1434 170 1434 196 1435 198 1435 673 1435 194 1436 196 1436 673 1436 192 1437 194 1437 673 1437 190 1438 192 1438 673 1438 162 1439 709 1439 156 1439 198 1440 674 1440 673 1440 834 1441 178 1441 832 1441 712 1442 170 1442 161 1442 709 1443 674 1443 154 1443 190 1444 673 1444 793 1444 156 1445 709 1445 154 1445 832 1446 178 1446 830 1446 815 1447 712 1447 158 1447 812 1448 815 1448 158 1448 178 1449 180 1449 830 1449 712 1450 161 1450 158 1450 190 1451 793 1451 796 1451 188 1452 190 1452 796 1452 154 1453 674 1453 150 1453 830 1454 180 1454 827 1454 811 1455 812 1455 164 1455 806 1456 811 1456 164 1456 188 1457 796 1457 801 1457 812 1458 158 1458 164 1458 180 1459 182 1459 826 1459 827 1460 180 1460 826 1460 150 1461 674 1461 153 1461 186 1462 188 1462 804 1462 188 1463 801 1463 804 1463 802 1464 806 1464 168 1464 799 1465 802 1465 168 1465 826 1466 182 1466 824 1466 806 1467 164 1467 168 1467 186 1468 804 1468 808 1468 824 1469 182 1469 822 1469 182 1470 184 1470 822 1470 153 1471 674 1471 198 1471 184 1472 186 1472 814 1472 186 1473 808 1473 814 1473 794 1474 799 1474 172 1474 822 1475 184 1475 819 1475 799 1476 168 1476 172 1476 184 1477 814 1477 817 1477 819 1478 184 1478 817 1478 172 1479 174 1479 790 1479 794 1480 172 1480 790 1480 790 1481 174 1481 788 1481 788 1482 174 1482 784 1482 174 1483 176 1483 784 1483 723 1484 718 1484 691 1484 718 1485 688 1485 691 1485 685 1486 688 1486 718 1486 682 1487 685 1487 714 1487 685 1488 718 1488 714 1488 680 1489 682 1489 713 1489 682 1490 714 1490 713 1490 683 1491 680 1491 716 1491 680 1492 713 1492 716 1492 683 1493 716 1493 721 1493 686 1494 683 1494 729 1494 671 1495 686 1495 729 1495 683 1496 721 1496 729 1496 671 1497 729 1497 706 1497 723 1498 691 1498 695 1498 727 1499 723 1499 695 1499 699 1500 727 1500 697 1500 727 1501 695 1501 697 1501 701 1502 699 1502 666 1502 699 1503 697 1503 666 1503 703 1504 701 1504 668 1504 701 1505 666 1505 668 1505 711 1506 703 1506 676 1506 703 1507 668 1507 676 1507 709 1508 711 1508 674 1508 711 1509 676 1509 674 1509 692 1510 690 1510 725 1510 692 1511 725 1511 726 1511 693 1512 692 1512 728 1512 692 1513 726 1513 728 1513 694 1514 693 1514 698 1514 693 1515 728 1515 698 1515 696 1516 694 1516 700 1516 694 1517 698 1517 700 1517 667 1518 696 1518 702 1518 696 1519 700 1519 702 1519 677 1520 667 1520 708 1520 667 1521 702 1521 708 1521 724 1522 689 1522 687 1522 720 1523 724 1523 687 1523 719 1524 720 1524 684 1524 720 1525 687 1525 684 1525 715 1526 719 1526 681 1526 719 1527 684 1527 681 1527 717 1528 715 1528 679 1528 715 1529 681 1529 679 1529 722 1530 717 1530 678 1530 707 1531 722 1531 678 1531 717 1532 679 1532 678 1532 707 1533 678 1533 669 1533 252 1534 256 1534 254 1534 264 1535 263 1535 256 1535 259 1536 258 1536 264 1536 296 1537 299 1537 297 1537 296 1538 252 1538 299 1538 292 1539 296 1539 293 1539 272 1540 260 1540 259 1540 272 1541 268 1541 260 1541 272 1542 269 1542 268 1542 288 1543 292 1543 290 1543 288 1544 296 1544 292 1544 276 1545 273 1545 272 1545 282 1546 278 1546 276 1546 282 1547 286 1547 283 1547 282 1548 288 1548 286 1548 282 1549 256 1549 252 1549 282 1550 259 1550 264 1550 282 1551 264 1551 256 1551 282 1552 252 1552 296 1552 282 1553 272 1553 259 1553 282 1554 296 1554 288 1554 282 1555 276 1555 272 1555 280 1556 278 1556 282 1556 261 1557 216 1557 266 1557 261 1558 209 1558 216 1558 243 1559 291 1559 294 1559 242 1560 291 1560 243 1560 274 1561 275 1561 226 1561 274 1562 226 1562 223 1562 289 1563 291 1563 242 1563 246 1564 294 1564 295 1564 246 1565 243 1565 294 1565 239 1566 289 1566 242 1566 248 1567 295 1567 298 1567 257 1568 210 1568 209 1568 248 1569 246 1569 295 1569 257 1570 209 1570 261 1570 271 1571 223 1571 221 1571 287 1572 289 1572 239 1572 271 1573 274 1573 223 1573 211 1574 210 1574 257 1574 238 1575 287 1575 239 1575 249 1576 298 1576 251 1576 249 1577 248 1577 298 1577 265 1578 211 1578 257 1578 265 1579 218 1579 211 1579 285 1580 287 1580 238 1580 270 1581 221 1581 220 1581 270 1582 271 1582 221 1582 267 1583 270 1583 220 1583 267 1584 218 1584 265 1584 236 1585 285 1585 238 1585 267 1586 220 1586 218 1586 202 1587 251 1587 250 1587 202 1588 249 1588 251 1588 284 1589 285 1589 236 1589 233 1590 284 1590 236 1590 204 1591 250 1591 253 1591 204 1592 202 1592 250 1592 281 1593 284 1593 233 1593 231 1594 281 1594 233 1594 206 1595 204 1595 253 1595 255 1596 206 1596 253 1596 279 1597 281 1597 231 1597 279 1598 231 1598 229 1598 207 1599 206 1599 255 1599 262 1600 207 1600 255 1600 277 1601 279 1601 229 1601 277 1602 229 1602 227 1602 216 1603 207 1603 262 1603 266 1604 216 1604 262 1604 275 1605 277 1605 227 1605 275 1606 227 1606 226 1606 224 1607 876 1607 222 1607 883 1608 237 1608 878 1608 877 1609 876 1609 224 1609 203 1610 862 1610 865 1610 213 1611 860 1611 862 1611 235 1612 237 1612 883 1612 861 1613 860 1613 213 1613 225 1614 877 1614 224 1614 200 1615 203 1615 865 1615 885 1616 235 1616 883 1616 868 1617 200 1617 865 1617 234 1618 235 1618 885 1618 215 1619 861 1619 213 1619 882 1620 877 1620 225 1620 864 1621 861 1621 215 1621 228 1622 882 1622 225 1622 201 1623 200 1623 868 1623 212 1624 864 1624 215 1624 887 1625 234 1625 885 1625 887 1626 232 1626 234 1626 871 1627 201 1627 868 1627 884 1628 228 1628 230 1628 884 1629 882 1629 228 1629 867 1630 864 1630 212 1630 886 1631 232 1631 887 1631 886 1632 230 1632 232 1632 886 1633 884 1633 230 1633 203 1634 205 1634 862 1634 862 1635 205 1635 213 1635 247 1636 201 1636 871 1636 208 1637 867 1637 212 1637 873 1638 247 1638 871 1638 870 1639 867 1639 208 1639 245 1640 247 1640 873 1640 214 1641 870 1641 208 1641 881 1642 245 1642 873 1642 872 1643 870 1643 214 1643 244 1644 245 1644 881 1644 217 1645 872 1645 214 1645 880 1646 244 1646 881 1646 874 1647 872 1647 217 1647 241 1648 244 1648 880 1648 219 1649 874 1649 217 1649 879 1650 241 1650 880 1650 875 1651 874 1651 219 1651 240 1652 241 1652 879 1652 222 1653 875 1653 219 1653 878 1654 240 1654 879 1654 876 1655 875 1655 222 1655 237 1656 240 1656 878 1656 142 1657 138 1657 140 1657 134 1658 136 1658 138 1658 148 1659 142 1659 144 1659 148 1660 144 1660 146 1660 130 1661 132 1661 134 1661 100 1662 148 1662 103 1662 100 1663 138 1663 142 1663 100 1664 134 1664 138 1664 100 1665 130 1665 134 1665 100 1666 142 1666 148 1666 126 1667 128 1667 130 1667 126 1668 130 1668 100 1668 111 1669 100 1669 107 1669 111 1670 126 1670 100 1670 122 1671 124 1671 126 1671 109 1672 111 1672 104 1672 109 1673 126 1673 111 1673 118 1674 120 1674 122 1674 118 1675 122 1675 126 1675 118 1676 126 1676 109 1676 112 1677 118 1677 109 1677 114 1678 116 1678 118 1678 114 1679 118 1679 112 1679 133 1680 90 1680 92 1680 76 1681 117 1681 74 1681 119 1682 117 1682 76 1682 88 1683 90 1683 133 1683 56 1684 101 1684 149 1684 131 1685 88 1685 133 1685 56 1686 62 1686 101 1686 66 1687 102 1687 101 1687 66 1688 101 1688 62 1688 78 1689 119 1689 76 1689 121 1690 119 1690 78 1690 54 1691 149 1691 147 1691 86 1692 88 1692 131 1692 54 1693 56 1693 149 1693 71 1694 108 1694 102 1694 80 1695 121 1695 78 1695 71 1696 102 1696 66 1696 129 1697 86 1697 131 1697 145 1698 54 1698 147 1698 123 1699 121 1699 80 1699 84 1700 86 1700 129 1700 50 1701 54 1701 145 1701 61 1702 105 1702 108 1702 127 1703 84 1703 129 1703 61 1704 108 1704 71 1704 125 1705 80 1705 82 1705 125 1706 82 1706 84 1706 125 1707 84 1707 127 1707 125 1708 123 1708 80 1708 53 1709 145 1709 143 1709 53 1710 50 1710 145 1710 106 1711 105 1711 61 1711 58 1712 106 1712 61 1712 141 1713 53 1713 143 1713 98 1714 53 1714 141 1714 110 1715 106 1715 58 1715 64 1716 110 1716 58 1716 139 1717 98 1717 141 1717 96 1718 98 1718 139 1718 113 1719 110 1719 64 1719 69 1720 113 1720 64 1720 137 1721 94 1721 96 1721 137 1722 96 1722 139 1722 72 1723 113 1723 69 1723 115 1724 113 1724 72 1724 92 1725 94 1725 137 1725 135 1726 92 1726 137 1726 74 1727 115 1727 72 1727 117 1728 115 1728 74 1728 133 1729 92 1729 135 1729 866 1730 863 1730 79 1730 854 1731 68 1731 853 1731 59 1732 68 1732 854 1732 97 1733 838 1733 839 1733 95 1734 840 1734 838 1734 77 1735 866 1735 79 1735 95 1736 838 1736 97 1736 869 1737 866 1737 77 1737 99 1738 97 1738 839 1738 93 1739 842 1739 840 1739 93 1740 840 1740 95 1740 855 1741 59 1741 854 1741 855 1742 60 1742 59 1742 841 1743 99 1743 839 1743 75 1744 869 1744 77 1744 859 1745 869 1745 75 1745 51 1746 99 1746 841 1746 91 1747 842 1747 93 1747 844 1748 842 1748 91 1748 73 1749 859 1749 75 1749 843 1750 51 1750 841 1750 856 1751 65 1751 60 1751 856 1752 60 1752 855 1752 52 1753 51 1753 843 1753 857 1754 70 1754 65 1754 857 1755 73 1755 70 1755 857 1756 65 1756 856 1756 89 1757 844 1757 91 1757 857 1758 858 1758 73 1758 73 1759 858 1759 859 1759 846 1760 844 1760 89 1760 845 1761 52 1761 843 1761 55 1762 52 1762 845 1762 87 1763 846 1763 89 1763 848 1764 846 1764 87 1764 847 1765 55 1765 845 1765 57 1766 55 1766 847 1766 85 1767 848 1767 87 1767 850 1768 848 1768 85 1768 849 1769 57 1769 847 1769 63 1770 57 1770 849 1770 83 1771 850 1771 85 1771 852 1772 850 1772 83 1772 851 1773 63 1773 849 1773 67 1774 63 1774 851 1774 81 1775 852 1775 83 1775 863 1776 852 1776 81 1776 853 1777 67 1777 851 1777 68 1778 67 1778 853 1778 79 1779 863 1779 81 1779

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae new file mode 100644 index 0000000..41abc83 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_outer_knuckle.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + lun lug 18 06:13:31 2016 + lun lug 18 06:13:31 2016 + + + + + + + + + 4.5 26.6297 5.11588 11.5 26.6297 5.11588 11.5 26.1146 4.71048 4.5 26.1146 4.71048 11.5 25.5118 4.45291 4.5 25.5118 4.45291 11.5 24.8628 4.36087 4.5 24.8628 4.36087 11.5 24.2122 4.4407 4.5 24.2122 4.4407 11.5 23.6047 4.68691 4.5 23.6047 4.68691 11.5 23.0821 5.08257 4.5 23.0821 5.08257 11.5 22.6802 5.60048 4.5 22.6802 5.60048 11.5 22.4269 6.20503 4.5 22.4269 6.20503 11.5 22.3393 6.85466 4.5 22.3393 6.85466 11.5 22.4237 7.50471 4.5 22.4237 7.50471 11.5 22.6741 8.11049 4.5 22.6741 8.11049 11.5 23.0734 8.63035 4.5 23.0734 8.63035 11.5 23.5941 9.02856 4.5 23.5941 9.02856 11.5 24.2004 9.27773 4.5 24.2004 9.27773 4.5 24.8506 9.36074 11.5 24.8506 9.36074 4.5 25.5 9.27188 11.5 25.5 9.27188 4.5 26.1041 9.01725 11.5 26.1041 9.01725 4.5 26.6211 8.61438 11.5 26.6211 8.61438 4.5 27.0157 8.09094 11.5 27.0157 8.09094 12 26.4613 8.03087 12 26.7014 7.59074 11.7922 26.943 7.5307 11.7922 26.7024 5.67612 12 26.6964 6.11825 12 26.4534 5.67974 12 26.8244 7.10474 11.95 26.8806 7.04967 12 26.109 5.31545 12 26.8227 6.60341 11.95 26.7648 6.15715 12 25.6848 5.04825 12 25.2075 4.89494 12 24.707 4.86515 12 24.2149 4.96074 12 23.762 5.17573 12 23.3768 5.49659 12 23.0835 5.90317 12 22.9005 6.36992 12 22.8393 6.86751 12 22.9039 7.36467 12 23.09 7.83017 12 23.386 8.23477 12 23.7734 8.55302 12 24.2277 8.76495 12 24.7205 8.85723 12 25.2207 8.82406 12 25.697 8.66754 12 26.1194 8.39748 4.5 34.0722 0.1937 5 33.5579 0.465001 5 34.0722 0.1937 4.5 33.5579 0.465001 4.5 34.5515 -0.135469 5 34.5515 -0.135469 4.5 34.9893 -0.518057 5 34.9893 -0.518057 4.5 35.3798 -0.948888 5 35.3798 -0.948888 5 35.7176 -1.42214 4.5 35.7176 -1.42214 5 35.9982 -1.9314 4.5 35.9982 -1.9314 5 36.2178 -2.4698 4.5 36.2178 -2.4698 4.5 36.3734 -3.03005 5 36.3734 -3.03005 4.5 36.4629 -3.60457 5 36.4629 -3.60457 5 36.485 -4.18559 4.5 36.485 -4.18559 4.5 36.4396 -4.76527 5 36.4396 -4.76527 5 36.3272 -5.33574 4.5 36.3272 -5.33574 4.5 36.1493 -5.88932 5 36.1493 -5.88932 4.5 35.9084 -6.4185 5 35.9084 -6.4185 4.5 35.6077 -6.91613 5 35.6077 -6.91613 5 35.2512 -7.37548 4.5 35.2512 -7.37548 5 34.8438 -7.79034 4.5 34.8438 -7.79034 5 34.391 -8.1551 4.5 34.391 -8.1551 4.5 33.8989 -8.46482 5 33.8989 -8.46482 4.5 33.3742 -8.71532 5 33.3742 -8.71532 5 32.8239 -8.90321 4.5 32.8239 -8.90321 4.5 32.2556 -9.02595 5 32.2556 -9.02595 5 31.6768 -9.08188 4.5 31.6768 -9.08188 5 31.0955 -9.07025 4.5 31.0955 -9.07025 4.5 30.5194 -8.9912 5 30.5194 -8.9912 5 29.9564 -8.84581 4.5 29.9564 -8.84581 4.5 29.4142 -8.63605 5 29.4142 -8.63605 5 28.8999 -8.36475 4.5 28.8999 -8.36475 5 28.4206 -8.03558 4.5 28.4206 -8.03558 4.5 27.9827 -7.65299 5 27.9827 -7.65299 5 27.5923 -7.22216 4.5 27.5923 -7.22216 5 27.2544 -6.74891 4.5 27.2544 -6.74891 4.5 26.9739 -6.23965 5 26.9739 -6.23965 5 26.7543 -5.70125 4.5 26.7543 -5.70125 5 26.5987 -5.141 4.5 26.5987 -5.141 4.5 26.5092 -4.56648 5 26.5092 -4.56648 4.5 26.487 -3.98546 5 26.487 -3.98546 5 26.5325 -3.40578 4.5 26.5325 -3.40578 5 26.6449 -2.8353 4.5 26.6449 -2.8353 4.5 26.8228 -2.28173 5 26.8228 -2.28173 5 27.0637 -1.75255 4.5 27.0637 -1.75255 5 27.3644 -1.25492 4.5 27.3644 -1.25492 5 27.7209 -0.795573 4.5 27.7209 -0.795573 4.5 28.1283 -0.380713 5 28.1283 -0.380713 5 28.5811 -0.0159545 4.5 28.5811 -0.0159545 5 29.0732 0.29377 4.5 29.0732 0.29377 5 29.5979 0.544272 4.5 29.5979 0.544272 5 30.1482 0.732164 4.5 30.1482 0.732164 4.5 30.7165 0.854905 5 30.7165 0.854905 5 31.2953 0.910835 4.5 31.2953 0.910835 5 31.8766 0.899198 4.5 31.8766 0.899198 5 32.4527 0.820151 4.5 32.4527 0.820151 4.5 33.0156 0.674763 5 33.0156 0.674763 -4.5 33.5579 0.465001 -5 33.5579 0.465001 -5 33.0156 0.674763 -4.5 33.0156 0.674763 -5 32.4527 0.820151 -4.5 32.4527 0.820151 -5 31.8766 0.899198 -4.5 31.8766 0.899198 -5 31.2953 0.910835 -4.5 31.2953 0.910835 -5 30.7165 0.854905 -4.5 30.7165 0.854905 -5 30.1482 0.732164 -4.5 30.1482 0.732164 -5 29.5979 0.544272 -4.5 29.5979 0.544272 -5 29.0732 0.29377 -4.5 29.0732 0.29377 -5 28.5811 -0.0159545 -4.5 28.5811 -0.0159545 -5 28.1283 -0.380713 -4.5 28.1283 -0.380713 -5 27.7209 -0.795573 -4.5 27.7209 -0.795573 -5 27.3644 -1.25492 -4.5 27.3644 -1.25492 -5 27.0637 -1.75255 -4.5 27.0637 -1.75255 -5 26.8228 -2.28173 -4.5 26.8228 -2.28173 -5 26.6449 -2.8353 -4.5 26.6449 -2.8353 -5 26.5325 -3.40578 -4.5 26.5325 -3.40578 -5 26.487 -3.98546 -4.5 26.487 -3.98546 -5 26.5092 -4.56648 -4.5 26.5092 -4.56648 -5 26.5987 -5.141 -4.5 26.5987 -5.141 -5 26.7543 -5.70125 -4.5 26.7543 -5.70125 -5 26.9739 -6.23965 -4.5 26.9739 -6.23965 -5 27.2544 -6.74891 -4.5 27.2544 -6.74891 -5 27.5923 -7.22216 -4.5 27.5923 -7.22216 -5 27.9827 -7.65299 -4.5 27.9827 -7.65299 -5 28.4206 -8.03558 -4.5 28.4206 -8.03558 -5 28.8999 -8.36475 -4.5 28.8999 -8.36475 -5 29.4142 -8.63605 -4.5 29.4142 -8.63605 -5 29.9564 -8.84581 -4.5 29.9564 -8.84581 -5 30.5194 -8.9912 -4.5 30.5194 -8.9912 -5 31.0955 -9.07025 -4.5 31.0955 -9.07025 -5 31.6768 -9.08188 -4.5 31.6768 -9.08188 -5 32.2556 -9.02595 -4.5 32.2556 -9.02595 -5 32.8239 -8.90321 -4.5 32.8239 -8.90321 -5 33.3742 -8.71532 -4.5 33.3742 -8.71532 -5 33.8989 -8.46482 -4.5 33.8989 -8.46482 -5 34.391 -8.1551 -4.5 34.391 -8.1551 -5 34.8438 -7.79034 -4.5 34.8438 -7.79034 -5 35.2512 -7.37548 -4.5 35.2512 -7.37548 -5 35.6077 -6.91613 -4.5 35.6077 -6.91613 -5 35.9084 -6.4185 -4.5 35.9084 -6.4185 -5 36.1493 -5.88932 -4.5 36.1493 -5.88932 -5 36.3272 -5.33574 -4.5 36.3272 -5.33574 -5 36.4396 -4.76527 -4.5 36.4396 -4.76527 -5 36.485 -4.18559 -4.5 36.485 -4.18559 -5 36.4629 -3.60457 -4.5 36.4629 -3.60457 -5 36.3734 -3.03005 -4.5 36.3734 -3.03005 -5 36.2178 -2.4698 -4.5 36.2178 -2.4698 -5 35.9982 -1.9314 -4.5 35.9982 -1.9314 -5 35.7176 -1.42214 -4.5 35.7176 -1.42214 -5 35.3798 -0.948888 -4.5 35.3798 -0.948888 -5 34.9893 -0.518057 -4.5 34.9893 -0.518057 -5 34.5515 -0.135469 -4.5 34.5515 -0.135469 -5 34.0722 0.1937 -4.5 34.0722 0.1937 -5.5 -7.46308 0.743246 5.5 -7.49982 0.0514696 5.5 -7.46308 0.743246 -5.5 -7.49982 0.0514696 -5.5 -7.36267 1.42868 5.5 -7.36267 1.42868 -5.5 -7.19944 2.10193 5.5 -7.19944 2.10193 -5.5 -6.97478 2.75724 5.5 -6.97478 2.75724 -5.5 -6.69063 3.38903 5.5 -6.69063 3.38903 -5.5 -6.34938 3.99191 5.5 -6.34938 3.99191 -5.5 -5.95397 4.56073 5.5 -5.95397 4.56073 -5.5 -5.50776 5.09063 5.5 -5.50776 5.09063 -5.5 -5.01456 5.57711 5.5 -5.01456 5.57711 -5.5 -4.47858 6.01601 5.5 -4.47858 6.01601 -5.5 -3.90439 6.40357 5.5 -3.90439 6.40357 -5.5 -3.29689 6.73651 5.5 -3.29689 6.73651 -5.5 -2.66125 7.01197 5.5 -2.66125 7.01197 -5.5 -2.00292 7.22761 5.5 -2.00292 7.22761 -5.5 -1.3275 7.38158 5.5 -1.3275 7.38158 -5.5 -0.640746 7.47258 5.5 -0.640746 7.47258 -5.5 0.0514696 7.49982 5.5 0.0514696 7.49982 -5.5 0.743246 7.46308 5.5 0.743246 7.46308 -5.5 1.42868 7.36267 5.5 1.42868 7.36267 -5.5 2.10193 7.19944 5.5 2.10193 7.19944 -5.5 2.75724 6.97478 5.5 2.75724 6.97478 -5.5 3.38903 6.69063 5.5 3.38903 6.69063 -5.5 3.99191 6.34938 5.5 3.99191 6.34938 -5.5 4.56073 5.95397 5.5 4.56073 5.95397 5.5 6.01601 4.47858 4.5 5.85892 4.68221 5.5 5.57711 5.01456 -5.5 5.09063 5.50776 5.5 5.09063 5.50776 4.5 6.29875 4.07133 5.5 6.40357 3.90439 -5.5 5.57711 5.01456 4.5 6.67513 3.41944 5.5 6.73651 3.29689 -4.5 5.85892 4.68221 -5.5 6.01601 4.47858 4.5 6.98428 2.73311 5.5 7.01197 2.66125 -4.5 6.29875 4.07133 -5.5 6.40357 3.90439 4.5 7.22306 2.01924 5.5 7.22761 2.00292 -4.5 6.67513 3.41944 -5.5 6.73651 3.29689 5.5 7.38158 1.3275 4.5 7.38909 1.28504 -4.5 6.98428 2.73311 -5.5 7.01197 2.66125 5.5 7.47258 0.640746 4.5 7.48069 0.537889 -4.5 7.22306 2.01924 -5.5 7.22761 2.00292 5.5 7.49982 -0.0514696 4.5 7.49693 -0.214679 -5.5 7.38158 1.3275 -4.5 7.38909 1.28504 5.5 7.46308 -0.743246 4.5 7.43765 -0.965084 -5.5 7.47258 0.640746 -4.5 7.48069 0.537889 5.5 7.36267 -1.42868 4.5 7.30345 -1.70577 -5.5 7.49982 -0.0514696 -4.5 7.49693 -0.214679 5.5 7.19944 -2.10193 4.5 7.09568 -2.42927 -5.5 7.46308 -0.743246 -4.5 7.43765 -0.965084 5.5 6.97478 -2.75724 -5.5 7.36267 -1.42868 4.5 6.81643 -3.1283 -4.5 7.30345 -1.70577 5.5 6.69063 -3.38903 -5.5 7.19944 -2.10193 4.5 6.46852 -3.79582 5.5 6.34938 -3.99191 -4.5 7.09568 -2.42927 -5.5 6.97478 -2.75724 4.5 6.05545 -4.4251 5.5 5.95397 -4.56073 -4.5 6.81643 -3.1283 -5.5 6.69063 -3.38903 4.5 5.58138 -5.00981 5.5 5.50776 -5.09063 -4.5 6.46852 -3.79582 -5.5 6.34938 -3.99191 4.5 5.05109 -5.54405 5.5 5.01456 -5.57711 -4.5 6.05545 -4.4251 -5.5 5.95397 -4.56073 4.5 4.46992 -6.02244 5.5 4.47858 -6.01601 -4.5 5.58138 -5.00981 -5.5 5.50776 -5.09063 5.5 3.90439 -6.40357 -4.5 5.05109 -5.54405 -5.5 5.01456 -5.57711 -4.5 4.46992 -6.02244 -5.5 4.47858 -6.01601 -5.5 3.90439 -6.40357 -5.5 3.29689 -6.73651 5.5 3.29689 -6.73651 -5.5 2.66125 -7.01197 5.5 2.66125 -7.01197 -5.5 2.00292 -7.22761 5.5 2.00292 -7.22761 -5.5 1.3275 -7.38158 5.5 1.3275 -7.38158 -5.5 0.640746 -7.47258 5.5 0.640746 -7.47258 -5.5 -0.0514696 -7.49982 5.5 -0.0514696 -7.49982 -5.5 -0.743246 -7.46308 5.5 -0.743246 -7.46308 -5.5 -1.42868 -7.36267 5.5 -1.42868 -7.36267 -5.5 -2.10193 -7.19944 5.5 -2.10193 -7.19944 -5.5 -2.75724 -6.97478 5.5 -2.75724 -6.97478 -5.5 -3.38903 -6.69063 5.5 -3.38903 -6.69063 -5.5 -3.99191 -6.34938 5.5 -3.99191 -6.34938 -5.5 -4.56073 -5.95397 5.5 -4.56073 -5.95397 -5.5 -5.09063 -5.50776 5.5 -5.09063 -5.50776 -5.5 -5.57711 -5.01456 5.5 -5.57711 -5.01456 -5.5 -6.01601 -4.47858 5.5 -6.01601 -4.47858 -5.5 -6.40357 -3.90439 5.5 -6.40357 -3.90439 -5.5 -6.73651 -3.29689 5.5 -6.73651 -3.29689 -5.5 -7.01197 -2.66125 5.5 -7.01197 -2.66125 -5.5 -7.22761 -2.00292 5.5 -7.22761 -2.00292 -5.5 -7.38158 -1.3275 5.5 -7.38158 -1.3275 -5.5 -7.47258 -0.640746 5.5 -7.47258 -0.640746 -11.5 26.6297 5.11588 -12 26.109 5.31545 -12 26.4534 5.67974 -11.5 26.1146 4.71048 -11.7922 26.7024 5.67612 -11.7922 26.943 7.5307 -12 26.8244 7.10474 -12 26.7014 7.59074 -12 26.6964 6.11825 -11.95 26.7648 6.15715 -11.5 27.0157 8.09094 -12 26.4613 8.03087 -12 26.8227 6.60341 -11.95 26.8806 7.04967 -11.5 26.6211 8.61438 -12 26.1194 8.39748 -11.5 26.1041 9.01725 -12 25.697 8.66754 -11.5 25.5 9.27188 -12 25.2207 8.82406 -11.5 24.8506 9.36074 -12 24.7205 8.85723 -11.5 24.2004 9.27773 -12 24.2277 8.76495 -11.5 23.5941 9.02856 -12 23.7734 8.55302 -11.5 23.0734 8.63035 -12 23.386 8.23477 -11.5 22.6741 8.11049 -12 23.09 7.83017 -11.5 22.4237 7.50471 -12 22.9039 7.36467 -12 22.8393 6.86751 -11.5 22.3393 6.85466 -12 22.9005 6.36992 -11.5 22.4269 6.20503 -12 23.0835 5.90317 -11.5 22.6802 5.60048 -12 23.3768 5.49659 -11.5 23.0821 5.08257 -12 23.762 5.17573 -11.5 23.6047 4.68691 -12 24.2149 4.96074 -11.5 24.2122 4.4407 -12 24.707 4.86515 -11.5 24.8628 4.36087 -12 25.2075 4.89494 -11.5 25.5118 4.45291 -12 25.6848 5.04825 -4.5 26.6297 5.11588 -4.5 26.1146 4.71048 -4.5 25.5118 4.45291 -4.5 24.8628 4.36087 -4.5 24.2122 4.4407 -4.5 23.6047 4.68691 -4.5 23.0821 5.08257 -4.5 22.6802 5.60048 -4.5 22.4269 6.20503 -4.5 22.3393 6.85466 -4.5 22.4237 7.50471 -4.5 22.6741 8.11049 -4.5 23.0734 8.63035 -4.5 23.5941 9.02856 -4.5 24.2004 9.27773 -4.5 24.8506 9.36074 -4.5 25.5 9.27188 -4.5 26.1041 9.01725 -4.5 26.6211 8.61438 -4.5 27.0157 8.09094 -4.5 21.886 12.0836 -4.5 22.4622 12.3698 -4.5 13.2728 2.96231 -4.5 6.78885 -5.41862 -4.5 19.9807 10.3812 -4.5 19.6317 9.84077 -4.5 21.3437 11.7373 -4.5 20.3856 10.8812 -4.5 20.8417 11.335 -4.5 12.5923 2.9406 -4.5 11.9133 2.99189 -4.5 35.7767 -8.27955 -4.5 35.302 -8.71568 -4.5 36.202 -7.795 -4.5 34.7832 -9.09836 -4.5 7.94695 3.50655 -4.5 36.5727 -7.26763 -4.5 34.2264 -9.42318 -4.5 7.15729 3.71405 -4.5 36.8848 -6.70353 -4.5 33.6379 -9.68637 -4.5 6.44584 4.11463 -4.5 37.1345 -6.1092 -4.5 33.0246 -9.88491 -4.5 37.319 -5.49151 -4.5 32.3935 -10.0165 -4.5 31.7519 -10.0796 -4.5 37.4362 -4.85759 -4.5 31.1073 -10.0736 -4.5 30.4671 -9.99836 -4.5 29.8386 -9.85491 -4.5 29.2291 -9.64485 -4.5 28.6457 -9.37062 -4.5 28.095 -9.03537 -4.5 27.5835 -8.64299 -4.5 27.0786 -8.28885 -4.5 26.5151 -8.03817 -4.5 25.914 -7.90024 -4.5 38.7229 5.05927 -4.5 38.772 5.73033 -4.5 38.7456 6.40266 -4.5 38.644 7.0678 -4.5 38.4687 7.71739 -4.5 38.2217 8.34326 -4.5 37.9062 8.93755 -4.5 37.5261 9.49277 -4.5 37.0863 10.002 -4.5 36.5922 10.4587 -4.5 36.0501 10.8572 -4.5 35.4668 11.1926 -4.5 34.8496 11.4605 -4.5 34.2062 11.6576 -4.5 33.5449 11.7815 -4.5 25.6114 12.8109 -4.5 16.9613 4.55387 -4.5 17.444 5.0341 -4.5 16.4299 4.12808 -4.5 17.8725 5.56326 -4.5 15.856 3.76163 -4.5 18.2418 6.13526 -4.5 24.9699 12.8593 -4.5 15.2462 3.45873 -4.5 18.5479 6.74352 -4.5 14.6075 3.22287 -4.5 24.3268 12.8388 -4.5 18.787 7.38105 -4.5 13.9472 3.05676 -4.5 18.9565 8.04052 -4.5 23.6897 12.7496 -4.5 5.18226 -5.62345 -4.5 5.97238 -5.41771 -4.5 19.1166 8.66364 -4.5 23.0657 12.5926 -4.5 19.3425 9.26603 4.5 6.78885 -5.41862 4.5 19.3425 9.26603 4.5 19.1166 8.66364 4.5 23.0657 12.5926 4.5 22.4622 12.3698 4.5 19.6317 9.84077 4.5 21.886 12.0836 4.5 13.2728 2.96231 4.5 19.9807 10.3812 4.5 21.3437 11.7373 4.5 20.3856 10.8812 4.5 35.302 -8.71568 4.5 35.7767 -8.27955 4.5 20.8417 11.335 4.5 36.202 -7.795 4.5 12.5923 2.9406 4.5 34.7832 -9.09836 4.5 36.5727 -7.26763 4.5 11.9133 2.99189 4.5 34.2264 -9.42318 4.5 36.8848 -6.70353 4.5 33.6379 -9.68637 4.5 7.94695 3.50655 4.5 37.1345 -6.1092 4.5 7.15729 3.71405 4.5 33.0246 -9.88491 4.5 37.319 -5.49151 4.5 31.7519 -10.0796 4.5 32.3935 -10.0165 4.5 6.44584 4.11463 4.5 37.4362 -4.85759 4.5 31.1073 -10.0736 4.5 30.4671 -9.99836 4.5 29.8386 -9.85491 4.5 29.2291 -9.64485 4.5 28.6457 -9.37062 4.5 28.095 -9.03537 4.5 27.5835 -8.64299 4.5 27.0786 -8.28885 4.5 26.5151 -8.03817 4.5 25.914 -7.90024 4.5 38.7229 5.05927 4.5 38.772 5.73033 4.5 38.7456 6.40266 4.5 38.644 7.0678 4.5 38.4687 7.71739 4.5 38.2217 8.34326 4.5 37.9062 8.93755 4.5 37.5261 9.49277 4.5 37.0863 10.002 4.5 36.5922 10.4587 4.5 36.0501 10.8572 4.5 35.4668 11.1926 4.5 34.8496 11.4605 4.5 34.2062 11.6576 4.5 33.5449 11.7815 4.5 25.6114 12.8109 4.5 16.9613 4.55387 4.5 17.444 5.0341 4.5 16.4299 4.12808 4.5 17.8725 5.56326 4.5 15.856 3.76163 4.5 18.2418 6.13526 4.5 24.9699 12.8593 4.5 15.2462 3.45873 4.5 18.5479 6.74352 4.5 14.6075 3.22287 4.5 24.3268 12.8388 4.5 18.787 7.38105 4.5 13.9472 3.05676 4.5 18.9565 8.04052 4.5 23.6897 12.7496 4.5 5.18226 -5.62345 4.5 5.97238 -5.41771 + + + + + + + + + + 0 0.618462 -0.785815 0 0.392934 -0.919567 0 0.618462 -0.785815 0 0.140402 -0.990095 0 0.392934 -0.919567 0 -0.121787 -0.992556 0 0.140402 -0.990095 0 -0.375605 -0.92678 0 -0.121787 -0.992556 0 -0.603593 -0.797293 0 -0.375605 -0.92678 0 -0.790095 -0.612984 0 -0.603593 -0.797293 0 -0.922271 -0.386543 0 -0.790095 -0.612984 0 -0.991046 -0.133518 0 -0.922271 -0.386543 0 -0.991686 0.128681 0 -0.991046 -0.133518 0 -0.92415 0.382029 0 -0.991686 0.128681 0 -0.793078 0.60912 0 -0.92415 0.382029 0 -0.607486 0.79433 0 -0.793078 0.60912 0 -0.380124 0.924936 0 -0.607486 0.79433 0 -0.380124 0.924936 0 -0.126635 0.991949 0 -0.126635 0.991949 0 0.135561 0.990769 0 0.135561 0.990769 0 0.388445 0.921472 0 0.388445 0.921472 0 0.614611 0.788831 0 0.614611 0.788831 0 0.798532 0.601953 0 0.798532 0.601953 0.717802 0.611252 0.333364 0.691676 0.576706 0.434735 0.69396 0.665159 0.275652 0.726279 0.601253 -0.333187 0.726278 0.666377 0.168705 0.675774 0.726005 0.127462 0.717804 0.505935 -0.478317 0.693963 0.572782 -0.436275 0.748256 0.663406 -0.00223624 0.748286 0.641973 -0.167149 0.675803 0.669397 -0.308542 0.717394 0.371303 -0.589474 0.691677 0.446658 -0.567521 0.716749 0.213252 -0.663924 0.692148 0.283602 -0.663702 0.715876 0.0414908 -0.696994 0.692817 0.101246 -0.71397 0.714768 -0.133363 -0.686529 0.69369 -0.0877201 -0.714912 0.713421 -0.300494 -0.633035 0.69476 -0.270151 -0.666579 0.711836 -0.449516 -0.539652 0.696024 -0.433391 -0.572471 0.710001 -0.571102 -0.411997 0.697484 -0.566183 -0.439265 0.707916 -0.65757 -0.257791 0.699127 -0.659422 -0.276378 0.702962 -0.705314 0.091519 0.70557 -0.703348 -0.0864493 0.700957 -0.706818 -0.0952252 0.702961 -0.705316 0.0915218 0.705568 -0.657993 0.263095 0.700956 -0.659109 0.272465 0.707916 -0.570004 0.417075 0.71 -0.447043 0.544108 0.699125 -0.56705 0.43552 0.711835 -0.296899 0.636508 0.697481 -0.435327 0.569219 0.713421 -0.128985 0.688762 0.696024 -0.272936 0.664121 0.714767 0.0462662 0.697831 0.694758 -0.0910814 0.713453 0.715876 0.218003 0.663323 0.693689 0.0976412 0.713626 0.716747 0.375634 0.587514 0.692817 0.280113 0.664486 0.717391 0.509457 0.475189 0.692145 0.4436 0.569345 0 0.466592 0.884473 0 0.466592 0.884473 0 0.56612 0.824323 0 0.56612 0.824323 0 0.657996 0.753022 0 0.657996 0.753022 0 0.74096 0.671549 0 0.81391 0.580991 0 0.74096 0.671549 0 0.875866 0.482555 0 0.81391 0.580991 0 0.925958 0.377626 0 0.875866 0.482555 0 0.925958 0.377626 0 0.963536 0.267577 0 0.963536 0.267577 0 0.988085 0.153907 0 0.999272 0.0381438 0 0.988085 0.153907 0 0.999272 0.0381438 0 0.996945 -0.0781115 0 0.981138 -0.193311 0 0.996945 -0.0781115 0 0.981138 -0.193311 0 0.952056 -0.305924 0 0.952056 -0.305924 0 0.910104 -0.414379 0 0.910104 -0.414379 0 0.855846 -0.517231 0 0.790013 -0.61309 0 0.855846 -0.517231 0 0.713494 -0.700662 0 0.790013 -0.61309 0 0.627323 -0.778759 0 0.713494 -0.700662 0 0.627323 -0.778759 0 0.532678 -0.846318 0 0.532678 -0.846318 0 0.430824 -0.902436 0 0.323146 -0.946349 0 0.430824 -0.902436 0 0.323146 -0.946349 0 0.211096 -0.977465 0 0.096191 -0.995363 0 0.211096 -0.977465 0 0.096191 -0.995363 0 -0.0200151 -0.9998 0 -0.0200151 -0.9998 0 -0.135947 -0.990716 0 -0.135947 -0.990716 0 -0.250045 -0.968234 0 -0.250045 -0.968234 0 -0.360759 -0.932659 0 -0.360759 -0.932659 0 -0.466591 -0.884473 0 -0.466591 -0.884473 0 -0.566121 -0.824322 0 -0.566121 -0.824322 0 -0.657996 -0.753021 0 -0.740961 -0.671548 0 -0.657996 -0.753021 0 -0.813908 -0.580993 0 -0.740961 -0.671548 0 -0.813908 -0.580993 0 -0.875857 -0.482571 0 -0.925964 -0.377612 0 -0.875857 -0.482571 0 -0.963538 -0.267571 0 -0.925964 -0.377612 0 -0.963538 -0.267571 0 -0.988085 -0.15391 0 -0.988085 -0.15391 0 -0.999272 -0.0381471 0 -0.996946 0.0780984 0 -0.999272 -0.0381471 0 -0.981134 0.19333 0 -0.996946 0.0780984 0 -0.981134 0.19333 0 -0.952056 0.305924 0 -0.910104 0.414379 0 -0.952056 0.305924 0 -0.855849 0.517226 0 -0.910104 0.414379 0 -0.790013 0.613091 0 -0.855849 0.517226 0 -0.790013 0.613091 0 -0.713492 0.700663 0 -0.627324 0.778758 0 -0.713492 0.700663 0 -0.532678 0.846318 0 -0.627324 0.778758 0 -0.430823 0.902436 0 -0.532678 0.846318 0 -0.430823 0.902436 0 -0.323147 0.946349 0 -0.323147 0.946349 0 -0.211094 0.977466 0 -0.211094 0.977466 0 -0.0961915 0.995363 0 -0.0961915 0.995363 0 0.0200142 0.9998 0 0.0200142 0.9998 0 0.135948 0.990716 0 0.135948 0.990716 0 0.250043 0.968235 0 0.250043 0.968235 0 0.360761 0.932658 0 0.360761 0.932658 0 0.360761 0.932658 0 0.250043 0.968235 0 0.360761 0.932658 0 0.135948 0.990716 0 0.250043 0.968235 0 0.0200142 0.9998 0 0.135948 0.990716 0 -0.0961915 0.995363 0 0.0200142 0.9998 0 -0.211094 0.977466 0 -0.0961915 0.995363 0 -0.323147 0.946349 0 -0.211094 0.977466 0 -0.430823 0.902436 0 -0.323147 0.946349 0 -0.532678 0.846318 0 -0.430823 0.902436 0 -0.627324 0.778758 0 -0.532678 0.846318 0 -0.713492 0.700663 0 -0.627324 0.778758 0 -0.790013 0.613091 0 -0.713492 0.700663 0 -0.855849 0.517226 0 -0.790013 0.613091 0 -0.910104 0.414379 0 -0.855849 0.517226 0 -0.952056 0.305924 0 -0.910104 0.414379 0 -0.981134 0.19333 0 -0.952056 0.305924 0 -0.996946 0.0780984 0 -0.981134 0.19333 0 -0.999272 -0.0381471 0 -0.996946 0.0780984 0 -0.988085 -0.15391 0 -0.999272 -0.0381471 0 -0.963538 -0.267571 0 -0.988085 -0.15391 0 -0.925964 -0.377612 0 -0.963538 -0.267571 0 -0.875857 -0.482571 0 -0.925964 -0.377612 0 -0.875857 -0.482571 0 -0.813908 -0.580993 0 -0.813908 -0.580993 0 -0.740961 -0.671548 0 -0.740961 -0.671548 0 -0.657996 -0.753021 0 -0.657996 -0.753021 0 -0.566121 -0.824322 0 -0.566121 -0.824322 0 -0.466591 -0.884473 0 -0.466591 -0.884473 0 -0.360759 -0.932659 0 -0.360759 -0.932659 0 -0.250045 -0.968234 0 -0.135947 -0.990716 0 -0.250045 -0.968234 0 -0.0200151 -0.9998 0 -0.135947 -0.990716 0 0.096191 -0.995363 0 -0.0200151 -0.9998 0 0.211096 -0.977465 0 0.096191 -0.995363 0 0.323146 -0.946349 0 0.211096 -0.977465 0 0.430824 -0.902436 0 0.323146 -0.946349 0 0.532678 -0.846318 0 0.430824 -0.902436 0 0.627323 -0.778759 0 0.532678 -0.846318 0 0.713494 -0.700662 0 0.627323 -0.778759 0 0.790013 -0.61309 0 0.713494 -0.700662 0 0.855846 -0.517231 0 0.790013 -0.61309 0 0.910104 -0.414379 0 0.855846 -0.517231 0 0.952056 -0.305924 0 0.910104 -0.414379 0 0.981138 -0.193311 0 0.952056 -0.305924 0 0.996945 -0.0781115 0 0.981138 -0.193311 0 0.999272 0.0381438 0 0.996945 -0.0781115 0 0.988085 0.153907 0 0.999272 0.0381438 0 0.963536 0.267577 0 0.988085 0.153907 0 0.963536 0.267577 0 0.925958 0.377626 0 0.925958 0.377626 0 0.875866 0.482555 0 0.875866 0.482555 0 0.81391 0.580991 0 0.81391 0.580991 0 0.74096 0.671549 0 0.74096 0.671549 0 0.657996 0.753022 0 0.657996 0.753022 0 0.56612 0.824323 0 0.56612 0.824323 0 0.466592 0.884473 0 0.466592 0.884473 0 -0.998592 0.053038 0 -0.998592 0.053038 0 -0.989439 0.144949 0 -0.989439 0.144949 0 -0.971844 0.235625 0 -0.971844 0.235625 0 -0.945957 0.324291 0 -0.945957 0.324291 0 -0.912001 0.410188 0 -0.912001 0.410188 0 -0.870262 0.492589 0 -0.870262 0.492589 0 -0.8211 0.570785 0 -0.8211 0.570785 0 -0.764931 0.644112 0 -0.764931 0.644112 0 -0.702238 0.711942 0 -0.702238 0.711942 0 -0.633553 0.773699 0 -0.633553 0.773699 0 -0.559461 0.828857 0 -0.559461 0.828857 0 -0.480597 0.876941 0 -0.480597 0.876941 0 -0.397634 0.917544 0 -0.397634 0.917544 0 -0.311277 0.950319 0 -0.311277 0.950319 0 -0.222264 0.974987 0 -0.222264 0.974987 0 -0.131356 0.991335 0 -0.131356 0.991335 0 -0.0393273 0.999226 0 -0.0393273 0.999226 0 0.053038 0.998592 0 0.053038 0.998592 0 0.144949 0.989439 0 0.144949 0.989439 0 0.235625 0.971844 0 0.235625 0.971844 0 0.324291 0.945957 0 0.324291 0.945957 0 0.410188 0.912001 0 0.410188 0.912001 0 0.492589 0.870262 0 0.492589 0.870262 0 0.570785 0.8211 0 0.570785 0.8211 0.00747078 0.773678 0.633535 0 0.644112 0.764931 0 0.644112 0.764931 -0.00850037 0.811505 0.584284 0.00651448 0.828839 0.559449 0 0.711942 0.702238 0 0.762723 0.646725 0 0.711942 0.702238 0.00507812 0.87693 0.480591 -0.00730469 0.865994 0.500002 0 0.762723 0.646725 -0.00747078 0.773678 0.633535 0.00316129 0.91754 0.397632 -0.00562766 0.911761 0.410682 0.00850037 0.811505 0.584284 -0.00651448 0.828839 0.559449 -0.00346969 0.948345 0.317222 0.000763403 0.950319 0.311277 0.00730469 0.865994 0.500002 -0.00507812 0.87693 0.480591 -0.000801919 0.974986 0.222264 -0.00203926 0.975371 0.220563 0.00562766 0.911761 0.410682 -0.00316129 0.91754 0.397632 0.00186811 0.991334 0.131356 -0.00446788 0.992559 0.121681 0.00346969 0.948345 0.317222 -0.000763403 0.950319 0.311277 0.00405675 0.999218 0.039327 -0.00641657 0.999747 0.0215735 0.000801919 0.974986 0.222264 0.00203926 0.975371 0.220563 0.00576397 0.998576 -0.0530372 -0.00788397 0.996863 -0.0787481 -0.00186811 0.991334 0.131356 0.00446788 0.992559 0.121681 0.0069906 0.989415 -0.144946 -0.00887059 0.983941 -0.178274 -0.00405675 0.999218 0.039327 0.00641657 0.999747 0.0215735 0.00773696 0.971815 -0.235618 -0.00937621 0.96111 -0.276005 -0.00576397 0.998576 -0.0530372 0.00788397 0.996863 -0.0787481 0.00800164 0.945927 -0.324281 -0.0069906 0.989415 -0.144946 -0.00940089 0.928603 -0.370956 0.00887059 0.983941 -0.178274 0.0077855 0.911973 -0.410176 -0.00773696 0.971815 -0.235618 -0.00894541 0.886745 -0.462172 0.00708865 0.87024 -0.492577 0.00937621 0.96111 -0.276005 -0.00800164 0.945927 -0.324281 0.0059109 0.821085 -0.570775 -0.0080078 0.835958 -0.548735 0.00940089 0.928603 -0.370956 -0.0077855 0.911973 -0.410176 0.00425333 0.764924 -0.644106 -0.00658986 0.776751 -0.629773 0.00894541 0.886745 -0.462172 -0.00708865 0.87024 -0.492577 0.00211285 0.702236 -0.711941 -0.00469021 0.709717 -0.704471 0.0080078 0.835958 -0.548735 -0.00591089 0.821085 -0.570775 -0.000507071 0.633553 -0.773699 -0.00231159 0.635534 -0.77207 0.00658986 0.776751 -0.629773 -0.00425332 0.764924 -0.644106 0.000489806 0.559461 -0.828856 0.00469021 0.709717 -0.704471 -0.00211285 0.702236 -0.711941 0.00231159 0.635534 -0.77207 0.000507071 0.633553 -0.773699 0 0.558866 -0.829258 -0.000489806 0.559461 -0.828856 0 0.558866 -0.829258 0 0.480597 -0.876941 0 0.480597 -0.876941 0 0.397634 -0.917544 0 0.397634 -0.917544 0 0.311277 -0.950319 0 0.311277 -0.950319 0 0.222264 -0.974987 0 0.222264 -0.974987 0 0.131356 -0.991335 0 0.131356 -0.991335 0 0.0393273 -0.999226 0 0.0393273 -0.999226 0 -0.053038 -0.998592 0 -0.053038 -0.998592 0 -0.144949 -0.989439 0 -0.144949 -0.989439 0 -0.235625 -0.971844 0 -0.235625 -0.971844 0 -0.324291 -0.945957 0 -0.324291 -0.945957 0 -0.410188 -0.912001 0 -0.410188 -0.912001 0 -0.492589 -0.870262 0 -0.492589 -0.870262 0 -0.570785 -0.8211 0 -0.570785 -0.8211 0 -0.644112 -0.764931 0 -0.644112 -0.764931 0 -0.711942 -0.702238 0 -0.711942 -0.702238 0 -0.773699 -0.633553 0 -0.773699 -0.633553 0 -0.828857 -0.559461 0 -0.828857 -0.559461 0 -0.876941 -0.480597 0 -0.876941 -0.480597 0 -0.917544 -0.397634 0 -0.917544 -0.397634 0 -0.950319 -0.311277 0 -0.950319 -0.311277 0 -0.974987 -0.222264 0 -0.974987 -0.222264 0 -0.991335 -0.131356 0 -0.991335 -0.131356 0 -0.999226 -0.0393273 0 -0.999226 -0.0393273 -0.717804 0.505935 -0.478317 -0.691677 0.446658 -0.567521 -0.693963 0.572782 -0.436275 -0.726278 0.666377 0.168705 -0.726279 0.601253 -0.333188 -0.675803 0.669397 -0.308542 -0.717802 0.611252 0.333364 -0.69396 0.665159 0.275652 -0.748286 0.641973 -0.167149 -0.748256 0.663406 -0.00223624 -0.675774 0.726005 0.127462 -0.717391 0.509457 0.475189 -0.691676 0.576706 0.434735 -0.716747 0.375634 0.587514 -0.692145 0.4436 0.569345 -0.715876 0.218003 0.663323 -0.692817 0.280113 0.664486 -0.714767 0.0462662 0.697831 -0.693689 0.0976412 0.713626 -0.713421 -0.128985 0.688762 -0.694758 -0.0910814 0.713453 -0.711835 -0.296899 0.636508 -0.696024 -0.272936 0.664121 -0.71 -0.447043 0.544108 -0.697481 -0.435327 0.569219 -0.707916 -0.570004 0.417075 -0.699125 -0.56705 0.43552 -0.70296 -0.705316 0.0915192 -0.705568 -0.657993 0.263095 -0.700956 -0.659109 0.272465 -0.702962 -0.705314 0.0915216 -0.70557 -0.703348 -0.0864493 -0.700957 -0.706818 -0.0952252 -0.707916 -0.65757 -0.257791 -0.710001 -0.571102 -0.411997 -0.699127 -0.659422 -0.276378 -0.711836 -0.449516 -0.539652 -0.697484 -0.566183 -0.439265 -0.713421 -0.300494 -0.633035 -0.696024 -0.433391 -0.572471 -0.714768 -0.133363 -0.686529 -0.69476 -0.270151 -0.666579 -0.715876 0.0414908 -0.696994 -0.69369 -0.0877201 -0.714912 -0.716749 0.213252 -0.663924 -0.692817 0.101246 -0.71397 -0.717394 0.371303 -0.589474 -0.692148 0.283602 -0.663702 0 0.618462 -0.785815 0 0.392934 -0.919567 0 0.618462 -0.785815 0 0.140402 -0.990095 0 0.392934 -0.919567 0 -0.121787 -0.992556 0 0.140402 -0.990095 0 -0.375605 -0.92678 0 -0.121787 -0.992556 0 -0.603593 -0.797293 0 -0.375605 -0.92678 0 -0.790095 -0.612984 0 -0.603593 -0.797293 0 -0.922271 -0.386543 0 -0.790095 -0.612984 0 -0.991046 -0.133518 0 -0.922271 -0.386543 0 -0.991686 0.128681 0 -0.991046 -0.133518 0 -0.92415 0.382029 0 -0.991686 0.128681 0 -0.793078 0.60912 0 -0.92415 0.382029 0 -0.607486 0.79433 0 -0.793078 0.60912 0 -0.380124 0.924936 0 -0.607486 0.79433 0 -0.126635 0.991949 0 -0.380124 0.924936 0 -0.126635 0.991949 0 0.135561 0.990769 0 0.135561 0.990769 0 0.388445 0.921472 0 0.388445 0.921472 0 0.614611 0.788831 0 0.614611 0.788831 0 0.798532 0.601953 0 0.798532 0.601953 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.991687 -0.128677 0.000114697 0.991686 -0.128678 -1.56083e-05 0.991686 -0.128678 1.81605e-05 0.991686 -0.128681 7.5241e-06 0.991686 -0.128681 0 0.991687 -0.128677 -1.65903e-05 0.991687 -0.128677 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.128678 -0.991686 0 -0.128678 -0.991686 0 -0.425395 -0.905008 0 -0.425395 -0.905008 0 -0.520028 -0.854149 0 -0.520028 -0.854149 0 -0.608676 -0.793419 0 -0.608676 -0.793419 0 0.983343 -0.181759 0 0.958163 -0.286224 0 0.983343 -0.181759 0 0.921924 -0.38737 0 0.958163 -0.286224 0 0.875044 -0.484043 0 0.921924 -0.38737 0 0.818065 -0.575125 0 0.875044 -0.484043 0 0.751636 -0.659578 0 0.818065 -0.575125 0 0.676538 -0.736408 0 0.751636 -0.659578 0 0.676538 -0.736408 0 0.593616 -0.804749 0 0.593616 -0.804749 0 0.503853 -0.863789 0 0.503853 -0.863789 0 0.408275 -0.912859 0 0.408275 -0.912859 0 0.307978 -0.951393 0 0.307978 -0.951393 0 0.204131 -0.978944 0 0.204131 -0.978944 0 0.0979123 -0.995195 0 0.0979123 -0.995195 0 -0.00941604 -0.999956 0 -0.00941604 -0.999956 0 -0.11665 -0.993173 0 -0.11665 -0.993173 0 -0.222526 -0.974927 0 -0.222526 -0.974927 0 -0.325845 -0.945423 0 -0.325845 -0.945423 0 0.991686 -0.128678 0 0.991686 -0.128678 0 0.184082 0.982911 0 0.292968 0.956122 0 0.184082 0.982911 0 0.292968 0.956122 0 0.498394 0.866951 0 0.398185 0.917305 0 0.398185 0.917305 0 0.592317 0.805705 0 0.498394 0.866951 0 0.592317 0.805705 0 0.75675 0.653705 0 0.678807 0.734317 0 0.678807 0.734317 0 0.825191 0.564854 0 0.75675 0.653705 0 0.825191 0.564854 0 0.883242 0.468918 0 0.883242 0.468918 0 0.965441 0.260621 0 0.930192 0.367073 0 0.930192 0.367073 0 0.965441 0.260621 0 0.988552 0.150882 0 0.988552 0.150882 0 0.997341 -0.07287 0 0.999229 0.03925 0 0.999229 0.03925 0 0.997341 -0.07287 0 0.128678 0.991687 0 0.128678 0.991687 0 -0.968527 0.248907 0 -0.968527 0.248907 0 -0.936307 0.351183 0 -0.936307 0.351183 0 -0.893317 0.449426 0 -0.893317 0.449426 0 -0.840063 0.542489 0 -0.840063 0.542489 0 -0.777149 0.629317 0 -0.777149 0.629317 0 -0.705301 0.708908 0 -0.705301 0.708908 0 -0.625332 0.780359 0 -0.625332 0.780359 0 -0.538194 0.842821 0 -0.538194 0.842821 0 -0.444843 0.895609 0 -0.444843 0.895609 0 -0.346387 0.938092 0 -0.346387 0.938092 0 -0.24396 0.969785 0 -0.24396 0.969785 0 -0.138707 0.990333 0 -0.138707 0.990333 0 0.0753224 0.997159 0 -0.0318787 0.999492 0 -0.0318787 0.999492 0 0.0753224 0.997159 0 -0.968527 0.248908 0 -0.936307 0.351184 0 -0.968527 0.248908 0 -0.893321 0.449419 0 -0.936307 0.351184 0 -0.840064 0.542487 0 -0.893321 0.449419 0 -0.777149 0.629317 0 -0.840064 0.542487 0 -0.705295 0.708914 0 -0.777149 0.629317 0 -0.625332 0.780359 0 -0.705295 0.708914 0 -0.538185 0.842827 0 -0.625332 0.780359 0 -0.444852 0.895604 0 -0.538185 0.842827 0 -0.346391 0.93809 0 -0.444852 0.895604 0 -0.243954 0.969787 0 -0.346391 0.93809 0 -0.243954 0.969787 0 -0.138716 0.990332 0 -0.0318783 0.999492 0 -0.138716 0.990332 0 0.0753246 0.997159 0 -0.0318783 0.999492 0 0.0753246 0.997159 0 0.128678 0.991686 0 0.128678 0.991686 0 0.488678 -0.872464 0 0.488678 -0.872464 0 0.251985 -0.967731 0 0.251985 -0.967731 0 -0.00111432 -0.999999 0 -0.00111432 -0.999999 0 0.25414 0.967167 0 0.49062 0.871373 0 0.25414 0.967167 0 0.695163 0.718852 0 0.49062 0.871373 0 0.695163 0.718852 0 -0.223643 -0.974671 0 -0.406467 -0.913666 0 -0.223643 -0.974671 0 -0.574195 -0.818718 0 -0.406467 -0.913666 0 -0.574195 -0.818718 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.000114739 0.991686 -0.128678 7.5241e-06 0.991686 -0.128681 -1.56345e-05 0.991686 -0.128678 -1.0131e-05 0.991687 -0.128677 2.46503e-05 0.991686 -0.128681 0 0.991687 -0.128677 0 0.991687 -0.128677 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 2 1 4 1 3 2 0 2 2 2 5 3 4 3 6 3 5 4 3 4 4 4 7 5 6 5 8 5 7 6 5 6 6 6 9 7 8 7 10 7 9 8 7 8 8 8 11 9 10 9 12 9 11 10 9 10 10 10 13 11 12 11 14 11 13 12 11 12 12 12 15 13 14 13 16 13 15 14 13 14 14 14 17 15 16 15 18 15 17 16 15 16 16 16 19 17 18 17 20 17 19 18 17 18 18 18 21 19 20 19 22 19 21 20 19 20 20 20 23 21 22 21 24 21 23 22 21 22 22 22 25 23 24 23 26 23 25 24 23 24 24 24 27 25 26 25 28 25 27 26 25 26 26 26 29 27 27 27 28 27 30 28 29 28 28 28 30 29 28 29 31 29 32 30 30 30 31 30 32 31 31 31 33 31 34 32 32 32 33 32 34 33 33 33 35 33 36 34 34 34 35 34 36 35 35 35 37 35 38 36 36 36 37 36 38 37 37 37 39 37 39 38 40 38 41 38 39 39 37 39 40 39 42 40 39 40 41 40 43 41 44 41 45 41 46 42 42 42 41 42 47 43 42 43 46 43 1 44 45 44 48 44 1 45 43 45 45 45 49 46 47 46 46 46 50 47 49 47 44 47 50 48 44 48 43 48 2 49 48 49 51 49 2 50 1 50 48 50 4 51 51 51 52 51 4 52 2 52 51 52 6 53 52 53 53 53 6 54 4 54 52 54 8 55 53 55 54 55 8 56 6 56 53 56 10 57 54 57 55 57 10 58 8 58 54 58 12 59 55 59 56 59 12 60 10 60 55 60 14 61 56 61 57 61 14 62 12 62 56 62 16 63 57 63 58 63 16 64 14 64 57 64 18 65 59 65 60 65 18 66 58 66 59 66 18 67 16 67 58 67 20 68 18 68 60 68 20 69 60 69 61 69 22 70 20 70 61 70 22 71 61 71 62 71 24 72 62 72 63 72 24 73 22 73 62 73 26 74 63 74 64 74 26 75 24 75 63 75 28 76 64 76 65 76 28 77 26 77 64 77 31 78 65 78 66 78 31 79 28 79 65 79 33 80 66 80 67 80 33 81 31 81 66 81 35 82 67 82 68 82 35 83 33 83 67 83 37 84 68 84 40 84 37 85 35 85 68 85 69 86 70 86 71 86 69 87 72 87 70 87 73 88 71 88 74 88 73 89 69 89 71 89 75 90 74 90 76 90 75 91 73 91 74 91 77 92 76 92 78 92 77 93 78 93 79 93 77 94 75 94 76 94 80 95 79 95 81 95 80 96 77 96 79 96 82 97 81 97 83 97 82 98 80 98 81 98 84 99 82 99 83 99 85 100 83 100 86 100 85 101 84 101 83 101 87 102 86 102 88 102 87 103 88 103 89 103 87 104 85 104 86 104 90 105 87 105 89 105 91 106 89 106 92 106 91 107 92 107 93 107 91 108 90 108 89 108 94 109 91 109 93 109 95 110 93 110 96 110 95 111 94 111 93 111 97 112 96 112 98 112 97 113 95 113 96 113 99 114 98 114 100 114 99 115 100 115 101 115 99 116 97 116 98 116 102 117 101 117 103 117 102 118 99 118 101 118 104 119 103 119 105 119 104 120 102 120 103 120 106 121 104 121 105 121 107 122 105 122 108 122 107 123 106 123 105 123 109 124 108 124 110 124 109 125 110 125 111 125 109 126 107 126 108 126 112 127 109 127 111 127 113 128 111 128 114 128 113 129 114 129 115 129 113 130 112 130 111 130 116 131 113 131 115 131 116 132 115 132 117 132 118 133 116 133 117 133 119 134 118 134 117 134 119 135 117 135 120 135 119 136 120 136 121 136 122 137 119 137 121 137 123 138 122 138 121 138 123 139 121 139 124 139 123 140 124 140 125 140 126 141 123 141 125 141 126 142 125 142 127 142 128 143 126 143 127 143 129 144 127 144 130 144 129 145 130 145 131 145 129 146 128 146 127 146 132 147 131 147 133 147 132 148 129 148 131 148 134 149 132 149 133 149 135 150 133 150 136 150 135 151 136 151 137 151 135 152 134 152 133 152 138 153 137 153 139 153 138 154 135 154 137 154 140 155 138 155 139 155 141 156 139 156 142 156 141 157 140 157 139 157 143 158 142 158 144 158 143 159 144 159 145 159 143 160 141 160 142 160 146 161 145 161 147 161 146 162 143 162 145 162 148 163 146 163 147 163 149 164 147 164 150 164 149 165 150 165 151 165 149 166 148 166 147 166 152 167 151 167 153 167 152 168 149 168 151 168 154 169 153 169 155 169 154 170 152 170 153 170 156 171 154 171 155 171 157 172 155 172 158 172 157 173 158 173 159 173 157 174 156 174 155 174 160 175 159 175 161 175 160 176 157 176 159 176 162 177 161 177 163 177 162 178 160 178 161 178 164 179 162 179 163 179 164 180 163 180 165 180 166 181 164 181 165 181 167 182 166 182 165 182 167 183 165 183 168 183 167 184 168 184 169 184 170 185 167 185 169 185 170 186 169 186 171 186 172 187 170 187 171 187 172 188 171 188 173 188 174 189 172 189 173 189 175 190 174 190 173 190 175 191 173 191 176 191 175 192 176 192 70 192 72 193 175 193 70 193 177 194 178 194 179 194 180 195 179 195 181 195 180 196 177 196 179 196 182 197 181 197 183 197 182 198 180 198 181 198 184 199 183 199 185 199 184 200 182 200 183 200 186 201 185 201 187 201 186 202 184 202 185 202 188 203 187 203 189 203 188 204 186 204 187 204 190 205 189 205 191 205 190 206 188 206 189 206 192 207 191 207 193 207 192 208 190 208 191 208 194 209 193 209 195 209 194 210 192 210 193 210 196 211 195 211 197 211 196 212 194 212 195 212 198 213 197 213 199 213 198 214 196 214 197 214 200 215 199 215 201 215 200 216 198 216 199 216 202 217 201 217 203 217 202 218 200 218 201 218 204 219 203 219 205 219 204 220 202 220 203 220 206 221 205 221 207 221 206 222 204 222 205 222 208 223 207 223 209 223 208 224 206 224 207 224 210 225 209 225 211 225 210 226 208 226 209 226 212 227 211 227 213 227 212 228 210 228 211 228 214 229 213 229 215 229 214 230 212 230 213 230 216 231 215 231 217 231 216 232 214 232 215 232 218 233 217 233 219 233 218 234 216 234 217 234 220 235 219 235 221 235 220 236 218 236 219 236 222 237 220 237 221 237 222 238 221 238 223 238 224 239 222 239 223 239 224 240 223 240 225 240 226 241 224 241 225 241 226 242 225 242 227 242 228 243 226 243 227 243 228 244 227 244 229 244 230 245 228 245 229 245 230 246 229 246 231 246 232 247 230 247 231 247 232 248 231 248 233 248 234 249 232 249 233 249 234 250 233 250 235 250 236 251 235 251 237 251 236 252 234 252 235 252 238 253 237 253 239 253 238 254 236 254 237 254 240 255 239 255 241 255 240 256 238 256 239 256 242 257 241 257 243 257 242 258 240 258 241 258 244 259 243 259 245 259 244 260 242 260 243 260 246 261 245 261 247 261 246 262 244 262 245 262 248 263 247 263 249 263 248 264 246 264 247 264 250 265 249 265 251 265 250 266 248 266 249 266 252 267 251 267 253 267 252 268 250 268 251 268 254 269 253 269 255 269 254 270 252 270 253 270 256 271 255 271 257 271 256 272 254 272 255 272 258 273 257 273 259 273 258 274 256 274 257 274 260 275 259 275 261 275 260 276 258 276 259 276 262 277 261 277 263 277 262 278 260 278 261 278 264 279 263 279 265 279 264 280 262 280 263 280 266 281 265 281 267 281 266 282 264 282 265 282 268 283 267 283 269 283 268 284 266 284 267 284 270 285 269 285 271 285 270 286 268 286 269 286 272 287 270 287 271 287 272 288 271 288 273 288 274 289 272 289 273 289 274 290 273 290 275 290 276 291 274 291 275 291 276 292 275 292 277 292 278 293 276 293 277 293 278 294 277 294 279 294 280 295 278 295 279 295 280 296 279 296 281 296 282 297 280 297 281 297 282 298 281 298 283 298 284 299 282 299 283 299 284 300 283 300 178 300 177 301 284 301 178 301 285 302 286 302 287 302 285 303 288 303 286 303 289 304 287 304 290 304 289 305 285 305 287 305 291 306 290 306 292 306 291 307 289 307 290 307 293 308 292 308 294 308 293 309 291 309 292 309 295 310 294 310 296 310 295 311 293 311 294 311 297 312 296 312 298 312 297 313 295 313 296 313 299 314 298 314 300 314 299 315 297 315 298 315 301 316 299 316 300 316 301 317 300 317 302 317 303 318 302 318 304 318 303 319 301 319 302 319 305 320 304 320 306 320 305 321 303 321 304 321 307 322 305 322 306 322 307 323 306 323 308 323 309 324 308 324 310 324 309 325 307 325 308 325 311 326 310 326 312 326 311 327 309 327 310 327 313 328 312 328 314 328 313 329 311 329 312 329 315 330 314 330 316 330 315 331 313 331 314 331 317 332 316 332 318 332 317 333 315 333 316 333 319 334 318 334 320 334 319 335 317 335 318 335 321 336 320 336 322 336 321 337 319 337 320 337 323 338 322 338 324 338 323 339 321 339 322 339 325 340 324 340 326 340 325 341 323 341 324 341 327 342 326 342 328 342 327 343 325 343 326 343 329 344 328 344 330 344 329 345 327 345 328 345 331 346 330 346 332 346 331 347 329 347 330 347 333 348 332 348 334 348 333 349 331 349 332 349 335 350 336 350 337 350 338 351 334 351 339 351 338 352 333 352 334 352 340 353 336 353 335 353 341 354 340 354 335 354 342 355 339 355 337 355 342 356 337 356 336 356 342 357 338 357 339 357 343 358 341 358 344 358 343 359 340 359 341 359 345 360 342 360 336 360 346 361 342 361 345 361 347 362 344 362 348 362 347 363 343 363 344 363 349 364 346 364 345 364 350 365 346 365 349 365 351 366 347 366 348 366 351 367 348 367 352 367 353 368 350 368 349 368 354 369 350 369 353 369 355 370 351 370 352 370 356 371 351 371 355 371 357 372 354 372 353 372 358 373 354 373 357 373 359 374 356 374 355 374 360 375 356 375 359 375 361 376 358 376 357 376 362 377 358 377 361 377 363 378 360 378 359 378 364 379 360 379 363 379 365 380 362 380 361 380 365 381 361 381 366 381 367 382 364 382 363 382 368 383 364 383 367 383 369 384 365 384 366 384 369 385 366 385 370 385 371 386 368 386 367 386 372 387 368 387 371 387 373 388 369 388 370 388 373 389 370 389 374 389 375 390 372 390 371 390 376 391 372 391 375 391 377 392 373 392 374 392 378 393 377 393 374 393 379 394 376 394 375 394 380 395 377 395 378 395 381 396 376 396 379 396 382 397 380 397 378 397 383 398 381 398 379 398 384 399 380 399 382 399 385 400 381 400 383 400 386 401 385 401 383 401 387 402 384 402 382 402 388 403 384 403 387 403 389 404 386 404 390 404 389 405 385 405 386 405 391 406 388 406 387 406 392 407 388 407 391 407 393 408 390 408 394 408 393 409 389 409 390 409 395 410 392 410 391 410 396 411 392 411 395 411 397 412 394 412 398 412 397 413 393 413 394 413 399 414 396 414 395 414 400 415 396 415 399 415 401 416 398 416 402 416 401 417 397 417 398 417 403 418 400 418 399 418 404 419 400 419 403 419 405 420 401 420 402 420 406 421 404 421 403 421 407 422 404 422 406 422 408 423 407 423 406 423 409 424 407 424 408 424 410 425 401 425 405 425 410 426 409 426 408 426 410 427 408 427 401 427 411 428 410 428 405 428 411 429 405 429 412 429 413 430 411 430 412 430 413 431 412 431 414 431 415 432 413 432 414 432 415 433 414 433 416 433 417 434 415 434 416 434 417 435 416 435 418 435 419 436 417 436 418 436 419 437 418 437 420 437 421 438 419 438 420 438 421 439 420 439 422 439 423 440 421 440 422 440 423 441 422 441 424 441 425 442 423 442 424 442 425 443 424 443 426 443 427 444 426 444 428 444 427 445 425 445 426 445 429 446 428 446 430 446 429 447 427 447 428 447 431 448 430 448 432 448 431 449 429 449 430 449 433 450 432 450 434 450 433 451 431 451 432 451 435 452 434 452 436 452 435 453 433 453 434 453 437 454 436 454 438 454 437 455 435 455 436 455 439 456 438 456 440 456 439 457 437 457 438 457 441 458 440 458 442 458 441 459 439 459 440 459 443 460 442 460 444 460 443 461 441 461 442 461 445 462 444 462 446 462 445 463 443 463 444 463 447 464 446 464 448 464 447 465 445 465 446 465 449 466 447 466 448 466 449 467 448 467 450 467 451 468 449 468 450 468 451 469 450 469 452 469 453 470 451 470 452 470 453 471 452 471 454 471 288 472 453 472 454 472 288 473 454 473 286 473 455 474 456 474 457 474 455 475 458 475 456 475 459 476 455 476 457 476 460 477 461 477 462 477 463 478 459 478 457 478 464 479 459 479 463 479 465 480 462 480 466 480 465 481 460 481 462 481 467 482 464 482 463 482 468 483 467 483 461 483 468 484 461 484 460 484 469 485 466 485 470 485 469 486 465 486 466 486 471 487 470 487 472 487 471 488 469 488 470 488 473 489 472 489 474 489 473 490 471 490 472 490 475 491 474 491 476 491 475 492 473 492 474 492 477 493 476 493 478 493 477 494 475 494 476 494 479 495 478 495 480 495 479 496 477 496 478 496 481 497 480 497 482 497 481 498 479 498 480 498 483 499 482 499 484 499 483 500 481 500 482 500 485 501 486 501 487 501 485 502 484 502 486 502 485 503 483 503 484 503 488 504 485 504 487 504 488 505 487 505 489 505 490 506 488 506 489 506 490 507 489 507 491 507 492 508 491 508 493 508 492 509 490 509 491 509 494 510 493 510 495 510 494 511 492 511 493 511 496 512 495 512 497 512 496 513 494 513 495 513 498 514 497 514 499 514 498 515 496 515 497 515 500 516 499 516 501 516 500 517 498 517 499 517 502 518 501 518 503 518 502 519 500 519 501 519 458 520 503 520 456 520 458 521 502 521 503 521 455 522 504 522 505 522 458 523 505 523 506 523 458 524 455 524 505 524 502 525 506 525 507 525 502 526 458 526 506 526 500 527 507 527 508 527 500 528 502 528 507 528 498 529 508 529 509 529 498 530 500 530 508 530 496 531 509 531 510 531 496 532 498 532 509 532 494 533 510 533 511 533 494 534 496 534 510 534 492 535 511 535 512 535 492 536 494 536 511 536 490 537 512 537 513 537 490 538 492 538 512 538 488 539 513 539 514 539 488 540 490 540 513 540 485 541 514 541 515 541 485 542 488 542 514 542 483 543 515 543 516 543 483 544 485 544 515 544 481 545 516 545 517 545 481 546 483 546 516 546 479 547 517 547 518 547 479 548 481 548 517 548 477 549 518 549 519 549 477 550 479 550 518 550 475 551 477 551 519 551 475 552 519 552 520 552 473 553 475 553 520 553 473 554 520 554 521 554 471 555 473 555 521 555 471 556 521 556 522 556 469 557 471 557 522 557 465 558 522 558 523 558 465 559 469 559 522 559 482 560 480 560 478 560 474 561 472 561 470 561 491 562 489 562 493 562 489 563 487 563 467 563 487 564 486 564 467 564 486 565 484 565 467 565 484 566 482 566 467 566 478 567 476 567 467 567 476 568 474 568 467 568 470 569 466 569 467 569 466 570 462 570 467 570 462 571 461 571 467 571 482 572 478 572 467 572 474 573 470 573 467 573 493 574 489 574 467 574 497 575 495 575 499 575 495 576 493 576 499 576 493 577 467 577 499 577 467 578 463 578 457 578 501 579 499 579 503 579 499 580 467 580 503 580 467 581 457 581 456 581 503 582 467 582 456 582 523 583 504 583 465 583 467 584 468 584 464 584 468 585 460 585 464 585 460 586 465 586 459 586 464 587 460 587 459 587 465 588 504 588 455 588 459 589 465 589 455 589 524 590 525 590 517 590 387 591 526 591 527 591 387 592 527 592 391 592 528 593 516 593 515 593 528 594 515 594 529 594 530 595 517 595 516 595 530 596 524 596 517 596 531 597 516 597 528 597 532 598 530 598 516 598 532 599 516 599 531 599 382 600 533 600 526 600 382 601 526 601 387 601 378 602 533 602 382 602 378 603 534 603 533 603 374 604 534 604 378 604 252 605 535 605 536 605 370 606 534 606 374 606 254 607 537 607 535 607 254 608 535 608 252 608 366 609 534 609 370 609 250 610 536 610 538 610 250 611 252 611 536 611 539 612 366 612 361 612 256 613 540 613 537 613 256 614 537 614 254 614 539 615 534 615 366 615 357 616 539 616 361 616 248 617 538 617 541 617 248 618 250 618 538 618 542 619 539 619 357 619 258 620 543 620 540 620 353 621 542 621 357 621 258 622 540 622 256 622 246 623 541 623 544 623 246 624 248 624 541 624 545 625 542 625 353 625 260 626 543 626 258 626 260 627 546 627 543 627 349 628 545 628 353 628 244 629 246 629 544 629 345 630 545 630 349 630 244 631 544 631 547 631 262 632 546 632 260 632 262 633 548 633 546 633 242 634 244 634 547 634 242 635 549 635 550 635 242 636 547 636 549 636 264 637 548 637 262 637 264 638 551 638 548 638 240 639 242 639 550 639 240 640 550 640 552 640 266 641 551 641 264 641 238 642 240 642 552 642 238 643 552 643 553 643 268 644 551 644 266 644 236 645 238 645 553 645 236 646 553 646 554 646 270 647 551 647 268 647 234 648 236 648 554 648 234 649 554 649 555 649 272 650 551 650 270 650 232 651 234 651 555 651 556 652 232 652 555 652 230 653 232 653 556 653 557 654 230 654 556 654 228 655 230 655 557 655 558 656 228 656 557 656 226 657 228 657 558 657 559 658 226 658 558 658 224 659 226 659 559 659 560 660 224 660 559 660 222 661 224 661 560 661 561 662 222 662 560 662 562 663 282 663 284 663 562 664 280 664 282 664 562 665 278 665 280 665 562 666 276 666 278 666 562 667 274 667 276 667 562 668 272 668 274 668 562 669 551 669 272 669 220 670 222 670 561 670 177 671 562 671 284 671 218 672 220 672 561 672 180 673 562 673 177 673 216 674 218 674 561 674 182 675 563 675 562 675 182 676 564 676 563 676 182 677 562 677 180 677 565 678 564 678 182 678 214 679 216 679 561 679 566 680 565 680 182 680 567 681 566 681 182 681 568 682 567 682 182 682 569 683 568 683 182 683 570 684 569 684 182 684 571 685 570 685 182 685 572 686 571 686 182 686 573 687 572 687 182 687 574 688 573 688 182 688 575 689 574 689 182 689 575 690 182 690 184 690 576 691 575 691 184 691 504 692 192 692 194 692 504 693 190 693 192 693 504 694 188 694 190 694 504 695 186 695 188 695 505 696 504 696 194 696 505 697 194 697 196 697 506 698 198 698 200 698 506 699 196 699 198 699 506 700 505 700 196 700 507 701 506 701 200 701 507 702 200 702 202 702 508 703 204 703 206 703 508 704 202 704 204 704 508 705 507 705 202 705 509 706 508 706 206 706 509 707 206 707 208 707 523 708 576 708 184 708 523 709 186 709 504 709 523 710 184 710 186 710 522 711 576 711 523 711 577 712 520 712 519 712 577 713 521 713 520 713 577 714 522 714 521 714 577 715 576 715 522 715 578 716 510 716 509 716 579 717 510 717 578 717 580 718 208 718 210 718 580 719 509 719 208 719 580 720 578 720 509 720 581 721 510 721 579 721 581 722 511 722 510 722 582 723 210 723 212 723 582 724 580 724 210 724 583 725 511 725 581 725 583 726 512 726 511 726 584 727 577 727 519 727 585 728 212 728 214 728 585 729 582 729 212 729 586 730 512 730 583 730 586 731 513 731 512 731 587 732 585 732 214 732 587 733 214 733 561 733 588 734 519 734 518 734 588 735 584 735 519 735 589 736 513 736 586 736 590 737 587 737 561 737 590 738 561 738 527 738 591 739 514 739 513 739 591 740 513 740 589 740 592 741 588 741 518 741 403 742 593 742 406 742 403 743 594 743 593 743 408 744 406 744 593 744 399 745 594 745 403 745 399 746 527 746 594 746 595 747 514 747 591 747 395 748 527 748 399 748 596 749 592 749 518 749 526 750 590 750 527 750 391 751 527 751 395 751 597 752 515 752 514 752 597 753 514 753 595 753 525 754 518 754 517 754 525 755 596 755 518 755 529 756 515 756 597 756 385 757 598 757 381 757 21 758 23 758 599 758 600 759 21 759 599 759 29 760 601 760 602 760 27 761 29 761 602 761 599 762 23 762 603 762 27 763 602 763 604 763 598 764 605 764 376 764 381 765 598 765 376 765 603 766 23 766 606 766 23 767 25 767 606 767 27 768 604 768 607 768 25 769 27 769 607 769 606 770 25 770 608 770 609 771 610 771 104 771 25 772 607 772 611 772 608 773 25 773 611 773 610 774 612 774 102 774 376 775 605 775 372 775 605 776 613 776 372 776 104 777 610 777 102 777 614 778 609 778 106 778 609 779 104 779 106 779 372 780 613 780 368 780 612 781 615 781 99 781 613 782 616 782 368 782 102 783 612 783 99 783 368 784 616 784 364 784 617 785 614 785 107 785 614 786 106 786 107 786 364 787 616 787 360 787 615 788 618 788 97 788 360 789 616 789 356 789 99 790 615 790 97 790 619 791 617 791 109 791 617 792 107 792 109 792 351 793 356 793 620 793 356 794 616 794 620 794 618 795 621 795 95 795 97 796 618 796 95 796 351 797 620 797 347 797 347 798 620 798 622 798 623 799 619 799 112 799 619 800 109 800 112 800 95 801 621 801 94 801 621 802 624 802 94 802 347 803 622 803 343 803 625 804 626 804 113 804 626 805 623 805 113 805 623 806 112 806 113 806 343 807 622 807 627 807 343 808 627 808 340 808 94 809 624 809 91 809 624 810 628 810 91 810 629 811 625 811 116 811 625 812 113 812 116 812 340 813 627 813 336 813 91 814 628 814 90 814 629 815 116 815 118 815 630 816 629 816 118 816 90 817 628 817 87 817 630 818 118 818 119 818 631 819 630 819 119 819 87 820 628 820 85 820 632 821 631 821 122 821 631 822 119 822 122 822 85 823 628 823 84 823 632 824 122 824 123 824 632 825 123 825 633 825 633 826 123 826 126 826 633 827 126 827 634 827 634 828 126 828 128 828 634 829 128 829 635 829 635 830 128 830 129 830 635 831 129 831 636 831 636 832 129 832 132 832 636 833 132 833 637 833 637 834 132 834 134 834 637 835 134 835 638 835 84 836 628 836 639 836 69 837 73 837 639 837 73 838 75 838 639 838 75 839 77 839 639 839 77 840 80 840 639 840 80 841 82 841 639 841 82 842 84 842 639 842 638 843 134 843 135 843 69 844 639 844 72 844 638 845 135 845 138 845 72 846 639 846 175 846 638 847 138 847 140 847 639 848 640 848 174 848 640 849 641 849 174 849 175 850 639 850 174 850 174 851 641 851 642 851 638 852 140 852 141 852 174 853 642 853 643 853 174 854 643 854 644 854 174 855 644 855 645 855 174 856 645 856 646 856 174 857 646 857 647 857 174 858 647 858 648 858 174 859 648 859 649 859 174 860 649 860 650 860 174 861 650 861 651 861 174 862 651 862 652 862 172 863 174 863 652 863 172 864 652 864 653 864 162 865 164 865 0 865 164 866 166 866 0 866 166 867 167 867 0 867 167 868 170 868 0 868 160 869 162 869 3 869 162 870 0 870 3 870 160 871 3 871 5 871 156 872 157 872 5 872 157 873 160 873 5 873 154 874 156 874 7 874 156 875 5 875 7 875 149 876 152 876 9 876 152 877 154 877 9 877 154 878 7 878 9 878 148 879 149 879 11 879 149 880 9 880 11 880 0 881 170 881 38 881 170 882 172 882 38 882 172 883 653 883 38 883 38 884 653 884 36 884 36 885 653 885 654 885 30 886 32 886 654 886 32 887 34 887 654 887 34 888 36 888 654 888 11 889 13 889 655 889 655 890 13 890 656 890 146 891 148 891 657 891 148 892 11 892 657 892 11 893 655 893 657 893 13 894 15 894 658 894 656 895 13 895 658 895 143 896 146 896 659 896 146 897 657 897 659 897 15 898 17 898 660 898 658 899 15 899 660 899 30 900 654 900 661 900 141 901 143 901 662 901 143 902 659 902 662 902 17 903 19 903 663 903 660 904 17 904 663 904 141 905 662 905 664 905 638 906 141 906 664 906 30 907 661 907 665 907 29 908 30 908 665 908 663 909 19 909 666 909 638 910 664 910 667 910 598 911 638 911 667 911 19 912 21 912 668 912 666 913 19 913 668 913 29 914 665 914 669 914 670 915 671 915 393 915 397 916 670 916 393 916 670 917 397 917 401 917 393 918 671 918 389 918 671 919 598 919 389 919 668 920 21 920 600 920 389 921 598 921 385 921 29 922 669 922 601 922 598 923 667 923 605 923 561 924 638 924 527 924 527 925 638 925 598 925 556 926 632 926 633 926 556 927 555 927 632 927 557 928 633 928 634 928 557 929 556 929 633 929 558 930 634 930 635 930 558 931 557 931 634 931 551 932 628 932 624 932 548 933 624 933 621 933 548 934 551 934 624 934 546 935 621 935 618 935 546 936 548 936 621 936 543 937 618 937 615 937 543 938 546 938 618 938 540 939 615 939 612 939 540 940 543 940 615 940 537 941 612 941 610 941 537 942 540 942 612 942 535 943 610 943 609 943 535 944 537 944 610 944 536 945 535 945 609 945 538 946 609 946 614 946 538 947 536 947 609 947 541 948 614 948 617 948 541 949 538 949 614 949 544 950 617 950 619 950 544 951 541 951 617 951 547 952 619 952 623 952 547 953 544 953 619 953 549 954 623 954 626 954 549 955 547 955 623 955 550 956 626 956 625 956 550 957 549 957 626 957 552 958 550 958 625 958 552 959 625 959 629 959 553 960 629 960 630 960 553 961 552 961 629 961 554 962 630 962 631 962 554 963 553 963 630 963 555 964 631 964 632 964 555 965 554 965 631 965 562 966 639 966 551 966 551 967 639 967 628 967 576 968 653 968 652 968 575 969 652 969 651 969 575 970 576 970 652 970 574 971 575 971 651 971 573 972 650 972 649 972 573 973 651 973 650 973 573 974 574 974 651 974 572 975 649 975 648 975 572 976 573 976 649 976 571 977 572 977 648 977 570 978 647 978 646 978 570 979 648 979 647 979 570 980 571 980 648 980 569 981 646 981 645 981 569 982 570 982 646 982 568 983 569 983 645 983 567 984 645 984 644 984 567 985 568 985 645 985 566 986 643 986 642 986 566 987 644 987 643 987 566 988 567 988 644 988 565 989 566 989 642 989 564 990 642 990 641 990 564 991 565 991 642 991 563 992 640 992 639 992 563 993 641 993 640 993 563 994 564 994 641 994 562 995 563 995 639 995 576 996 577 996 653 996 577 997 654 997 653 997 595 998 591 998 668 998 595 999 668 999 600 999 597 1000 600 1000 599 1000 597 1001 595 1001 600 1001 529 1002 599 1002 603 1002 529 1003 597 1003 599 1003 528 1004 603 1004 606 1004 528 1005 529 1005 603 1005 531 1006 606 1006 608 1006 531 1007 528 1007 606 1007 532 1008 608 1008 611 1008 532 1009 531 1009 608 1009 530 1010 611 1010 607 1010 530 1011 532 1011 611 1011 524 1012 607 1012 604 1012 524 1013 530 1013 607 1013 525 1014 604 1014 602 1014 525 1015 524 1015 604 1015 596 1016 602 1016 601 1016 596 1017 525 1017 602 1017 592 1018 601 1018 669 1018 592 1019 596 1019 601 1019 588 1020 669 1020 665 1020 588 1021 592 1021 669 1021 584 1022 661 1022 654 1022 584 1023 665 1023 661 1023 584 1024 588 1024 665 1024 577 1025 584 1025 654 1025 666 1026 668 1026 591 1026 663 1027 666 1027 589 1027 666 1028 591 1028 589 1028 660 1029 663 1029 586 1029 663 1030 589 1030 586 1030 658 1031 660 1031 583 1031 660 1032 586 1032 583 1032 656 1033 658 1033 581 1033 658 1034 583 1034 581 1034 655 1035 656 1035 579 1035 656 1036 581 1036 579 1036 657 1037 655 1037 578 1037 655 1038 579 1038 578 1038 659 1039 657 1039 580 1039 657 1040 578 1040 580 1040 662 1041 659 1041 582 1041 659 1042 580 1042 582 1042 664 1043 662 1043 585 1043 662 1044 582 1044 585 1044 667 1045 664 1045 587 1045 664 1046 585 1046 587 1046 667 1047 587 1047 590 1047 605 1048 667 1048 526 1048 613 1049 605 1049 526 1049 667 1050 590 1050 526 1050 616 1051 613 1051 533 1051 613 1052 526 1052 533 1052 616 1053 533 1053 534 1053 534 1054 539 1054 620 1054 534 1055 620 1055 616 1055 670 1056 401 1056 408 1056 670 1057 408 1057 593 1057 671 1058 670 1058 594 1058 670 1059 593 1059 594 1059 598 1060 671 1060 527 1060 671 1061 594 1061 527 1061 622 1062 620 1062 539 1062 627 1063 622 1063 542 1063 622 1064 539 1064 542 1064 336 1065 627 1065 545 1065 627 1066 542 1066 545 1066 336 1067 545 1067 345 1067 637 1068 638 1068 561 1068 636 1069 637 1069 560 1069 637 1070 561 1070 560 1070 635 1071 636 1071 559 1071 636 1072 560 1072 559 1072 635 1073 559 1073 558 1073 197 1074 195 1074 193 1074 237 1075 247 1075 243 1075 237 1076 243 1076 239 1076 267 1077 271 1077 269 1077 267 1078 273 1078 271 1078 267 1079 275 1079 273 1079 233 1080 255 1080 247 1080 277 1081 275 1081 267 1081 233 1082 247 1082 237 1082 233 1083 237 1083 235 1083 203 1084 199 1084 197 1084 203 1085 193 1085 255 1085 203 1086 201 1086 199 1086 203 1087 197 1087 193 1087 203 1088 255 1088 233 1088 281 1089 279 1089 277 1089 227 1090 231 1090 229 1090 227 1091 233 1091 231 1091 209 1092 205 1092 203 1092 209 1093 207 1093 205 1093 209 1094 203 1094 233 1094 223 1095 227 1095 225 1095 223 1096 233 1096 227 1096 179 1097 283 1097 281 1097 179 1098 178 1098 283 1098 213 1099 211 1099 209 1099 255 1100 259 1100 257 1100 255 1101 261 1101 259 1101 255 1102 263 1102 261 1102 215 1103 209 1103 233 1103 215 1104 213 1104 209 1104 219 1105 223 1105 221 1105 219 1106 233 1106 223 1106 219 1107 215 1107 233 1107 217 1108 215 1108 219 1108 251 1109 255 1109 253 1109 185 1110 183 1110 181 1110 187 1111 185 1111 181 1111 247 1112 251 1112 249 1112 247 1113 255 1113 251 1113 189 1114 181 1114 179 1114 189 1115 187 1115 181 1115 189 1116 267 1116 265 1116 189 1117 277 1117 267 1117 189 1118 281 1118 277 1118 189 1119 179 1119 281 1119 243 1120 247 1120 245 1120 193 1121 191 1121 189 1121 193 1122 265 1122 263 1122 193 1123 263 1123 255 1123 193 1124 189 1124 265 1124 239 1125 243 1125 241 1125 127 1126 137 1126 133 1126 161 1127 165 1127 163 1127 127 1128 131 1128 130 1128 127 1129 133 1129 131 1129 127 1130 139 1130 137 1130 93 1131 86 1131 83 1131 93 1132 92 1132 89 1132 93 1133 89 1133 86 1133 159 1134 165 1134 161 1134 93 1135 155 1135 150 1135 93 1136 83 1136 155 1136 169 1137 168 1137 165 1137 169 1138 165 1138 159 1138 124 1139 127 1139 125 1139 155 1140 159 1140 158 1140 173 1141 171 1141 169 1141 121 1142 139 1142 127 1142 121 1143 127 1143 124 1143 173 1144 169 1144 159 1144 100 1145 144 1145 139 1145 100 1146 96 1146 93 1146 100 1147 98 1147 96 1147 100 1148 93 1148 150 1148 100 1149 139 1149 121 1149 100 1150 150 1150 144 1150 150 1151 153 1151 151 1151 150 1152 155 1152 153 1152 115 1153 120 1153 117 1153 105 1154 101 1154 100 1154 71 1155 176 1155 173 1155 105 1156 103 1156 101 1156 71 1157 70 1157 176 1157 114 1158 121 1158 120 1158 114 1159 100 1159 121 1159 114 1160 120 1160 115 1160 114 1161 105 1161 100 1161 111 1162 105 1162 114 1162 110 1163 108 1163 105 1163 110 1164 105 1164 111 1164 144 1165 147 1165 145 1165 144 1166 150 1166 147 1166 139 1167 144 1167 142 1167 83 1168 74 1168 71 1168 83 1169 76 1169 74 1169 83 1170 78 1170 76 1170 83 1171 79 1171 78 1171 83 1172 81 1172 79 1172 83 1173 159 1173 155 1173 83 1174 173 1174 159 1174 83 1175 71 1175 173 1175 133 1176 137 1176 136 1176 89 1177 88 1177 86 1177 428 1178 426 1178 424 1178 375 1179 371 1179 367 1179 428 1180 432 1180 430 1180 428 1181 424 1181 432 1181 292 1182 296 1182 294 1182 379 1183 367 1183 359 1183 379 1184 375 1184 367 1184 332 1185 326 1185 324 1185 332 1186 328 1186 326 1186 332 1187 330 1187 328 1187 287 1188 292 1188 290 1188 320 1189 324 1189 322 1189 386 1190 383 1190 379 1190 339 1191 334 1191 332 1191 454 1192 287 1192 286 1192 316 1193 320 1193 318 1193 454 1194 292 1194 287 1194 394 1195 390 1195 386 1195 394 1196 386 1196 379 1196 452 1197 296 1197 292 1197 452 1198 292 1198 454 1198 335 1199 337 1199 339 1199 335 1200 324 1200 320 1200 335 1201 332 1201 324 1201 335 1202 339 1202 332 1202 312 1203 316 1203 314 1203 448 1204 452 1204 450 1204 344 1205 341 1205 335 1205 405 1206 394 1206 379 1206 405 1207 398 1207 394 1207 405 1208 402 1208 398 1208 446 1209 452 1209 448 1209 446 1210 296 1210 452 1210 306 1211 310 1211 308 1211 306 1212 312 1212 310 1212 306 1213 316 1213 312 1213 352 1214 348 1214 344 1214 444 1215 355 1215 335 1215 444 1216 335 1216 296 1216 444 1217 359 1217 355 1217 444 1218 405 1218 379 1218 444 1219 379 1219 359 1219 444 1220 412 1220 405 1220 444 1221 296 1221 446 1221 355 1222 344 1222 335 1222 355 1223 352 1223 344 1223 442 1224 412 1224 444 1224 416 1225 414 1225 412 1225 416 1226 412 1226 442 1226 440 1227 416 1227 442 1227 300 1228 304 1228 302 1228 300 1229 306 1229 304 1229 300 1230 316 1230 306 1230 420 1231 418 1231 416 1231 300 1232 320 1232 316 1232 434 1233 438 1233 436 1233 434 1234 440 1234 438 1234 367 1235 363 1235 359 1235 296 1236 300 1236 298 1236 424 1237 422 1237 420 1237 424 1238 420 1238 416 1238 296 1239 320 1239 300 1239 432 1240 416 1240 440 1240 296 1241 335 1241 320 1241 432 1242 440 1242 434 1242 432 1243 424 1243 416 1243 338 1244 342 1244 346 1244 301 1245 303 1245 305 1245 301 1246 297 1246 299 1246 301 1247 346 1247 293 1247 437 1248 427 1248 431 1248 301 1249 293 1249 297 1249 301 1250 305 1250 346 1250 437 1251 431 1251 435 1251 396 1252 400 1252 404 1252 331 1253 333 1253 338 1253 441 1254 437 1254 439 1254 392 1255 396 1255 404 1255 410 1256 407 1256 409 1256 329 1257 331 1257 338 1257 411 1258 404 1258 407 1258 327 1259 338 1259 346 1259 327 1260 329 1260 338 1260 411 1261 407 1261 410 1261 411 1262 392 1262 404 1262 447 1263 443 1263 445 1263 447 1264 441 1264 443 1264 380 1265 384 1265 388 1265 447 1266 437 1266 441 1266 377 1267 380 1267 388 1267 417 1268 413 1268 415 1268 417 1269 411 1269 413 1269 417 1270 392 1270 411 1270 321 1271 323 1271 325 1271 451 1272 447 1272 449 1272 451 1273 392 1273 423 1273 451 1274 423 1274 427 1274 451 1275 427 1275 437 1275 451 1276 437 1276 447 1276 451 1277 365 1277 392 1277 319 1278 325 1278 327 1278 319 1279 327 1279 346 1279 319 1280 321 1280 325 1280 421 1281 417 1281 419 1281 365 1282 388 1282 392 1282 365 1283 373 1283 377 1283 365 1284 369 1284 373 1284 365 1285 377 1285 388 1285 423 1286 392 1286 417 1286 423 1287 417 1287 421 1287 285 1288 453 1288 288 1288 285 1289 451 1289 453 1289 313 1290 317 1290 319 1290 313 1291 315 1291 317 1291 313 1292 319 1292 346 1292 358 1293 362 1293 365 1293 427 1294 423 1294 425 1294 309 1295 311 1295 313 1295 309 1296 313 1296 346 1296 431 1297 427 1297 429 1297 293 1298 346 1298 365 1298 293 1299 365 1299 451 1299 293 1300 289 1300 291 1300 293 1301 285 1301 289 1301 293 1302 451 1302 285 1302 346 1303 358 1303 365 1303 346 1304 354 1304 358 1304 346 1305 350 1305 354 1305 305 1306 307 1306 309 1306 305 1307 309 1307 346 1307 297 1308 293 1308 295 1308 435 1309 431 1309 433 1309 49 1310 46 1310 41 1310 49 1311 41 1311 40 1311 49 1312 40 1312 68 1312 49 1313 68 1313 67 1313 49 1314 67 1314 66 1314 49 1315 66 1315 65 1315 49 1316 65 1316 64 1316 49 1317 64 1317 63 1317 49 1318 63 1318 62 1318 49 1319 62 1319 61 1319 49 1320 61 1320 60 1320 49 1321 60 1321 59 1321 49 1322 59 1322 58 1322 49 1323 58 1323 57 1323 49 1324 57 1324 56 1324 49 1325 56 1325 55 1325 49 1326 55 1326 54 1326 53 1327 49 1327 54 1327 52 1328 49 1328 53 1328 45 1329 44 1329 49 1329 51 1330 49 1330 52 1330 48 1331 45 1331 49 1331 48 1332 49 1332 51 1332 47 1333 49 1333 50 1333 42 1334 47 1334 43 1334 47 1335 50 1335 43 1335 39 1336 42 1336 1 1336 42 1337 43 1337 1 1337 39 1338 1 1338 38 1338 38 1339 1 1339 0 1339

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_pad.dae b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_pad.dae new file mode 100644 index 0000000..e0c6e64 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_arg2f_85_pad.dae @@ -0,0 +1,104 @@ + + + 2016-07-17T22:25:43.361178 + 2016-07-17T22:25:43.361188 + Z_UP + + + + + + + + 0.0 0.0 0.0 1.0 + + + 0.0 0.0 0.0 1.0 + + + 0.7 0.7 0.7 1.0 + + + 1 1 1 1.0 + + + 0.0 + + + 0.0 0.0 0.0 1.0 + + + 0.0 + + + 0.0 0.0 0.0 1.0 + + + 1.0 + + + + + + 0 + + + + + + + + + + 4.38531e-14 -1 -4.451336e-05 4.38531e-14 -1 -4.451336e-05 -4.38531e-14 1 4.451336e-05 -4.38531e-14 1 4.451336e-05 -1 -4.385301e-14 -2.011189e-15 -1 -4.385301e-14 -2.011189e-15 -2.009237e-15 -4.451336e-05 1 -2.009237e-15 -4.451336e-05 1 1 4.385301e-14 2.011189e-15 1 4.385301e-14 2.011189e-15 2.009237e-15 4.451336e-05 -1 2.009237e-15 4.451336e-05 -1 + + + + + + + + + + -10 -23.90175 13.51442 10 -23.9033 48.51442 -10 -23.9033 48.51442 10 -23.90175 13.51442 -10 -18.90175 13.51464 -10 -18.9033 48.51464 10 -18.90175 13.51464 10 -18.9033 48.51464 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 1 1 0 1 4 2 5 2 6 2 5 3 7 3 6 3 2 4 5 4 4 4 2 5 4 5 0 5 5 6 2 6 1 6 5 7 1 7 7 7 7 8 1 8 6 8 1 9 3 9 6 9 0 10 4 10 3 10 4 11 6 11 3 11

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_gripper_coupling.stl b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_gripper_coupling.stl new file mode 100644 index 0000000..02c600f Binary files /dev/null and b/ros_kortex/kortex_description/grippers/robotiq_2f_85/meshes/visual/robotiq_gripper_coupling.stl differ diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro new file mode 100644 index 0000000..bbe7e59 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro @@ -0,0 +1,7 @@ + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_transmission_macro.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_transmission_macro.xacro new file mode 100644 index 0000000..4ed28ba --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_transmission_macro.xacro @@ -0,0 +1,79 @@ + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + 1 + hardware_interface/PositionJointInterface + + + + + + ${prefix}finger_joint + ${prefix}right_outer_knuckle_joint + 1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}right_inner_knuckle_joint + 1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}left_inner_knuckle_joint + 1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}left_inner_finger_joint + -1.0 + 0.0 + 5.0 + + + + ${prefix}finger_joint + ${prefix}right_inner_finger_joint + -1.0 + 0.0 + 5.0 + + + + + + my_robotiq_gripper + ${prefix}bracelet_link + ${prefix}left_inner_finger + ${prefix}right_inner_finger + + 100 + 10 + 3 + 10 + 0.001 + false + __default_topic__ + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_arg2f.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_arg2f.xacro new file mode 100644 index 0000000..5f4035b --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_arg2f.xacro @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Black + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_arg2f_85_model_macro.xacro b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_arg2f_85_model_macro.xacro new file mode 100644 index 0000000..b8247e7 --- /dev/null +++ b/ros_kortex/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_arg2f_85_model_macro.xacro @@ -0,0 +1,215 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_description/launch/visualize.launch b/ros_kortex/kortex_description/launch/visualize.launch new file mode 100644 index 0000000..3091419 --- /dev/null +++ b/ros_kortex/kortex_description/launch/visualize.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + [base_feedback/joint_state] + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/multiple_robots/kortex_dual_robots.xacro b/ros_kortex/kortex_description/multiple_robots/kortex_dual_robots.xacro new file mode 100644 index 0000000..764eb04 --- /dev/null +++ b/ros_kortex/kortex_description/multiple_robots/kortex_dual_robots.xacro @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/package.xml b/ros_kortex/kortex_description/package.xml new file mode 100644 index 0000000..018c38c --- /dev/null +++ b/ros_kortex/kortex_description/package.xml @@ -0,0 +1,22 @@ + + kortex_description + 2.2.2 + +

URDF and xacro description package for Kortex robots

+

This package contains configuration data, 3D models and launch files +for Kortex arms and supported grippers

+
+ Alexandre Vannobel + + BSD + catkin + roslaunch + robot_state_publisher + rviz + joint_state_publisher + gazebo + xacro + + + +
diff --git a/ros_kortex/kortex_description/readme.md b/ros_kortex/kortex_description/readme.md new file mode 100644 index 0000000..2ecf830 --- /dev/null +++ b/ros_kortex/kortex_description/readme.md @@ -0,0 +1,33 @@ + + +# Kortex Description +This package contains the URDF (Unified Robot Description Format), STL and configuration files for the Kortex-compatible robots. + +## Usage + +To load the description of a robot, you simply have to load the **ARM.xacro** or the **ARM_GRIPPER.xacro** file, with **ARM** being your arm's name (gen3, gen3_lite), and if you have a gripper, **GRIPPER** being your gripper's name (robotiq_2f_85, gen3_lite_2f). + +**Arguments**: +- **sim** : If this argument is true, the Gazebo-specific files will be loaded. The default value is **false **. + +For example: + +- To load the Gen3 description with a Robotiq 2-F 85 gripper for simulation, you would put in your launch file : + + +- To load the Gen3 lite description, you would put in your launch file : + + +## Tool frame + +The `tool_frame` link refers to the tool frame used by the arm when it reports end effector position feedback. \ No newline at end of file diff --git a/ros_kortex/kortex_description/robots/gen3.xacro b/ros_kortex/kortex_description/robots/gen3.xacro new file mode 100644 index 0000000..163b8ee --- /dev/null +++ b/ros_kortex/kortex_description/robots/gen3.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro b/ros_kortex/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro new file mode 100644 index 0000000..be36b56 --- /dev/null +++ b/ros_kortex/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/robots/gen3_robotiq_2f_140.xacro b/ros_kortex/kortex_description/robots/gen3_robotiq_2f_140.xacro new file mode 100644 index 0000000..969be46 --- /dev/null +++ b/ros_kortex/kortex_description/robots/gen3_robotiq_2f_140.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/robots/gen3_robotiq_2f_85.xacro b/ros_kortex/kortex_description/robots/gen3_robotiq_2f_85.xacro new file mode 100644 index 0000000..03859d9 --- /dev/null +++ b/ros_kortex/kortex_description/robots/gen3_robotiq_2f_85.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_description/robots/kortex_robot.xacro b/ros_kortex/kortex_description/robots/kortex_robot.xacro new file mode 100644 index 0000000..684a644 --- /dev/null +++ b/ros_kortex/kortex_description/robots/kortex_robot.xacro @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + + \ No newline at end of file diff --git a/ros_kortex/docs/.gitignore b/ros_kortex/kortex_driver/.gitignore similarity index 53% rename from ros_kortex/docs/.gitignore rename to ros_kortex/kortex_driver/.gitignore index a303fff..567609b 100644 --- a/ros_kortex/docs/.gitignore +++ b/ros_kortex/kortex_driver/.gitignore @@ -1,2 +1 @@ build/ -site/ diff --git a/ros_kortex/kortex_driver/CMakeLists.txt b/ros_kortex/kortex_driver/CMakeLists.txt new file mode 100644 index 0000000..7e2c475 --- /dev/null +++ b/ros_kortex/kortex_driver/CMakeLists.txt @@ -0,0 +1,148 @@ +cmake_minimum_required(VERSION 2.8.3) +project(kortex_driver) + +add_compile_options(-std=c++11) +add_definitions(-D_OS_UNIX) + +option(USE_CONAN "Use the Conan package manager to automatically fetch the Kortex API" ON) + +if(NOT CONAN_TARGET_PLATFORM) + set(CONAN_TARGET_PLATFORM "x86") +endif() +message("CONAN_TARGET_PLATFORM is ${CONAN_TARGET_PLATFORM}") + +# Explicitely specify the build type in case the user did not do it +if(NOT CMAKE_BUILD_TYPE) + set(CMAKE_BUILD_TYPE Release) +endif() + +## find catkin and any catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs controller_manager_msgs message_generation actionlib control_msgs urdf moveit_ros_planning_interface) +find_package(Boost REQUIRED COMPONENTS system) + +file(GLOB_RECURSE generated_files RELATIVE ${PROJECT_SOURCE_DIR} "src/generated/robot/*.cpp" "src/generated/simulation/*.cpp") +file(GLOB_RECURSE non_generated_files RELATIVE ${PROJECT_SOURCE_DIR} "src/non-generated/driver/*.cpp") +file(GLOB_RECURSE test_files RELATIVE ${PROJECT_SOURCE_DIR} "src/non-generated/tests/*.cc") + +# Find all auto-generated subdirectories in msg/generated +file(GLOB children RELATIVE ${PROJECT_SOURCE_DIR}/msg/generated ${PROJECT_SOURCE_DIR}/msg/generated/*) +set(msg_generated_dir_list "") +foreach(child ${children}) + if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/msg/generated/${child}) + list(APPEND msg_generated_dir_list ${child}) + endif() +endforeach() + +# Find all auto-generated subdirectories in srv/generated +file(GLOB children RELATIVE ${PROJECT_SOURCE_DIR}/srv/generated ${PROJECT_SOURCE_DIR}/srv/generated/*) +set(srv_generated_dir_list "") +foreach(child ${children}) + if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/srv/generated/${child}) + list(APPEND srv_generated_dir_list ${child}) + endif() +endforeach() + +## declare ROS messages and services +add_message_files(DIRECTORY msg/non_generated) +add_message_files(DIRECTORY msg/generated) +foreach(sub_dir ${msg_generated_dir_list}) + add_message_files(DIRECTORY msg/generated/${sub_dir}) +endforeach() + +add_service_files(DIRECTORY srv/non_generated) +foreach(sub_dir ${srv_generated_dir_list}) + add_service_files(DIRECTORY srv/generated/${sub_dir}) +endforeach() + +## generate added messages and services +generate_messages(DEPENDENCIES std_msgs) + +## declare a catkin package +catkin_package() + +if(USE_CONAN) + # Include conan.cmake module and download Kortex API from artifactory + include(${PROJECT_SOURCE_DIR}/cmake/conan.cmake) + conan_check(REQUIRED) + conan_add_remote(NAME kinova_public + URL https://artifactory.kinovaapps.com/artifactory/api/conan/conan-public) + if("${CONAN_TARGET_PLATFORM}" STREQUAL "x86") + conan_cmake_run(CONANFILE conanfile.py + UPDATE + BASIC_SETUP CMAKE_TARGETS + NO_OUTPUT_DIRS + SETTINGS kortex_api_cpp:compiler=gcc kortex_api_cpp:compiler.version=5 kortex_api_cpp:compiler.libcxx=libstdc++11) + elseif("${CONAN_TARGET_PLATFORM}" STREQUAL "artik710") + conan_cmake_run(CONANFILE conanfile.py + UPDATE + BASIC_SETUP CMAKE_TARGETS + NO_OUTPUT_DIRS + SETTINGS kortex_api_cpp:arch=armv7 kortex_api_cpp:compiler=gcc kortex_api_cpp:compiler.version=5 kortex_api_cpp:compiler.libcxx=libstdc++11 + OPTIONS kortex_api_cpp:target=artik710) + elseif("${CONAN_TARGET_PLATFORM}" STREQUAL "imx6") + conan_cmake_run(CONANFILE conanfile.py + UPDATE + BASIC_SETUP CMAKE_TARGETS + NO_OUTPUT_DIRS + SETTINGS kortex_api_cpp:arch=armv7 kortex_api_cpp:compiler=gcc kortex_api_cpp:compiler.version=6.4 kortex_api_cpp:compiler.libcxx=libstdc++11 + OPTIONS kortex_api_cpp:target=imx6) + elseif("${CONAN_TARGET_PLATFORM}" STREQUAL "jetson") + conan_cmake_run(CONANFILE conanfile.py + UPDATE + BASIC_SETUP CMAKE_TARGETS + NO_OUTPUT_DIRS + SETTINGS kortex_api_cpp:arch=armv7 kortex_api_cpp:compiler=gcc kortex_api_cpp:compiler.version=7 kortex_api_cpp:compiler.libcxx=libstdc++11 + OPTIONS kortex_api_cpp:target=jetson) + endif() +endif() + +include_directories(include ${catkin_INCLUDE_DIRS}) +include_directories(include ${Boost_INCLUDE_DIRS}) +include_directories(include ${PROJECT_SOURCE_DIR}/src) +include_directories(include ${PROJECT_SOURCE_DIR}/include) + +if(NOT USE_CONAN) + include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/client) + include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/client_stubs) + include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/messages) + include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/common) + include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include) + link_directories(${PROJECT_SOURCE_DIR}/../kortex_api/lib/release) +endif() + +# Generated files library +add_library(kortex_driver_generated_files ${generated_files}) +if(USE_CONAN) + target_link_libraries(kortex_driver_generated_files CONAN_PKG::kortex_api_cpp ${catkin_LIBRARIES} gcov) +else() + target_link_libraries(kortex_driver_generated_files KortexApiCpp ${catkin_LIBRARIES} gcov) +endif() +add_dependencies(kortex_driver_generated_files ${PROJECT_NAME}_gencpp) +# Remove deprecation warnings from Kortex API +target_compile_options(kortex_driver_generated_files PRIVATE "-Wno-deprecated-declarations") + +# Non-generated files library (driver implementation) +add_library(kortex_arm_driver_implementation ${non_generated_files}) +if(USE_CONAN) + target_link_libraries(kortex_arm_driver_implementation CONAN_PKG::kortex_api_cpp ${catkin_LIBRARIES} gcov kortex_driver_generated_files) +else() + target_link_libraries(kortex_arm_driver_implementation KortexApiCpp ${catkin_LIBRARIES} gcov kortex_driver_generated_files) +endif() +add_dependencies(kortex_arm_driver_implementation kortex_driver_generated_files) + +# Entry point executable for the driver +add_executable(kortex_arm_driver src/non-generated/main.cpp) +if(USE_CONAN) + target_link_libraries(kortex_arm_driver CONAN_PKG::kortex_api_cpp ${catkin_LIBRARIES} gcov kortex_arm_driver_implementation) +else() + target_link_libraries(kortex_arm_driver KortexApiCpp ${catkin_LIBRARIES} gcov kortex_arm_driver_implementation) +endif() +add_dependencies(kortex_arm_driver kortex_arm_driver_implementation) + +## Add gtest based cpp test target and link libraries +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + catkin_add_gtest(kortex_arm_driver_func_tests ${test_files}) + target_link_libraries(kortex_arm_driver_func_tests ${catkin_LIBRARIES} kortex_arm_driver_implementation) + add_dependencies(kortex_arm_driver_func_tests kortex_arm_driver_implementation) +endif() diff --git a/ros_kortex/kortex_driver/cmake/README.md b/ros_kortex/kortex_driver/cmake/README.md new file mode 100644 index 0000000..14be9d0 --- /dev/null +++ b/ros_kortex/kortex_driver/cmake/README.md @@ -0,0 +1,3 @@ +File: **conan.cmake** +Version: **0.14** +External Link: https://github.com/conan-io/cmake-conan/releases diff --git a/ros_kortex/kortex_driver/cmake/conan.cmake b/ros_kortex/kortex_driver/cmake/conan.cmake new file mode 100644 index 0000000..1eae75e --- /dev/null +++ b/ros_kortex/kortex_driver/cmake/conan.cmake @@ -0,0 +1,554 @@ +# The MIT License (MIT) + +# Copyright (c) 2018 JFrog + +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: + +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. + +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. + + + +# This file comes from: https://github.com/conan-io/cmake-conan. Please refer +# to this repository for issues and documentation. + +# Its purpose is to wrap and launch Conan C/C++ Package Manager when cmake is called. +# It will take CMake current settings (os, compiler, compiler version, architecture) +# and translate them to conan settings for installing and retrieving dependencies. + +# It is intended to facilitate developers building projects that have conan dependencies, +# but it is only necessary on the end-user side. It is not necessary to create conan +# packages, in fact it shouldn't be use for that. Check the project documentation. + + +include(CMakeParseArguments) + +function(_get_msvc_ide_version result) + set(${result} "" PARENT_SCOPE) + if(NOT MSVC_VERSION VERSION_LESS 1400 AND MSVC_VERSION VERSION_LESS 1500) + set(${result} 8 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1500 AND MSVC_VERSION VERSION_LESS 1600) + set(${result} 9 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1600 AND MSVC_VERSION VERSION_LESS 1700) + set(${result} 10 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1700 AND MSVC_VERSION VERSION_LESS 1800) + set(${result} 11 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1800 AND MSVC_VERSION VERSION_LESS 1900) + set(${result} 12 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1900 AND MSVC_VERSION VERSION_LESS 1910) + set(${result} 14 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1910 AND MSVC_VERSION VERSION_LESS 1920) + set(${result} 15 PARENT_SCOPE) + elseif(NOT MSVC_VERSION VERSION_LESS 1920 AND MSVC_VERSION VERSION_LESS 1930) + set(${result} 16 PARENT_SCOPE) + else() + message(FATAL_ERROR "Conan: Unknown MSVC compiler version [${MSVC_VERSION}]") + endif() +endfunction() + +function(conan_cmake_settings result) + #message(STATUS "COMPILER " ${CMAKE_CXX_COMPILER}) + #message(STATUS "COMPILER " ${CMAKE_CXX_COMPILER_ID}) + #message(STATUS "VERSION " ${CMAKE_CXX_COMPILER_VERSION}) + #message(STATUS "FLAGS " ${CMAKE_LANG_FLAGS}) + #message(STATUS "LIB ARCH " ${CMAKE_CXX_LIBRARY_ARCHITECTURE}) + #message(STATUS "BUILD TYPE " ${CMAKE_BUILD_TYPE}) + #message(STATUS "GENERATOR " ${CMAKE_GENERATOR}) + #message(STATUS "GENERATOR WIN64 " ${CMAKE_CL_64}) + + message(STATUS "Conan: Automatic detection of conan settings from cmake") + + parse_arguments(${ARGV}) + + if(ARGUMENTS_BUILD_TYPE) + set(_CONAN_SETTING_BUILD_TYPE ${ARGUMENTS_BUILD_TYPE}) + elseif(CMAKE_BUILD_TYPE) + set(_CONAN_SETTING_BUILD_TYPE ${CMAKE_BUILD_TYPE}) + else() + message(FATAL_ERROR "Please specify in command line CMAKE_BUILD_TYPE (-DCMAKE_BUILD_TYPE=Release)") + endif() + + string(TOUPPER ${_CONAN_SETTING_BUILD_TYPE} _CONAN_SETTING_BUILD_TYPE_UPPER) + if (_CONAN_SETTING_BUILD_TYPE_UPPER STREQUAL "DEBUG") + set(_CONAN_SETTING_BUILD_TYPE "Debug") + elseif(_CONAN_SETTING_BUILD_TYPE_UPPER STREQUAL "RELEASE") + set(_CONAN_SETTING_BUILD_TYPE "Release") + elseif(_CONAN_SETTING_BUILD_TYPE_UPPER STREQUAL "RELWITHDEBINFO") + set(_CONAN_SETTING_BUILD_TYPE "RelWithDebInfo") + elseif(_CONAN_SETTING_BUILD_TYPE_UPPER STREQUAL "MINSIZEREL") + set(_CONAN_SETTING_BUILD_TYPE "MinSizeRel") + endif() + + if(ARGUMENTS_ARCH) + set(_CONAN_SETTING_ARCH ${ARGUMENTS_ARCH}) + endif() + #handle -s os setting + if(CMAKE_SYSTEM_NAME) + #use default conan os setting if CMAKE_SYSTEM_NAME is not defined + set(CONAN_SYSTEM_NAME ${CMAKE_SYSTEM_NAME}) + if(${CMAKE_SYSTEM_NAME} STREQUAL "Darwin") + set(CONAN_SYSTEM_NAME Macos) + endif() + set(CONAN_SUPPORTED_PLATFORMS Windows Linux Macos Android iOS FreeBSD WindowsStore) + list (FIND CONAN_SUPPORTED_PLATFORMS "${CONAN_SYSTEM_NAME}" _index) + if (${_index} GREATER -1) + #check if the cmake system is a conan supported one + set(_CONAN_SETTING_OS ${CONAN_SYSTEM_NAME}) + else() + message(FATAL_ERROR "cmake system ${CONAN_SYSTEM_NAME} is not supported by conan. Use one of ${CONAN_SUPPORTED_PLATFORMS}") + endif() + endif() + + get_property(_languages GLOBAL PROPERTY ENABLED_LANGUAGES) + if (";${_languages};" MATCHES ";CXX;") + set(LANGUAGE CXX) + set(USING_CXX 1) + elseif (";${_languages};" MATCHES ";C;") + set(LANGUAGE C) + set(USING_CXX 0) + else () + message(FATAL_ERROR "Conan: Neither C or C++ was detected as a language for the project. Unabled to detect compiler version.") + endif() + + if (${CMAKE_${LANGUAGE}_COMPILER_ID} STREQUAL GNU) + # using GCC + # TODO: Handle other params + string(REPLACE "." ";" VERSION_LIST ${CMAKE_${LANGUAGE}_COMPILER_VERSION}) + list(GET VERSION_LIST 0 MAJOR) + list(GET VERSION_LIST 1 MINOR) + set(COMPILER_VERSION ${MAJOR}.${MINOR}) + if(${MAJOR} GREATER 4) + set(COMPILER_VERSION ${MAJOR}) + endif() + set(_CONAN_SETTING_COMPILER gcc) + set(_CONAN_SETTING_COMPILER_VERSION ${COMPILER_VERSION}) + if (USING_CXX) + conan_cmake_detect_unix_libcxx(_LIBCXX) + set(_CONAN_SETTING_COMPILER_LIBCXX ${_LIBCXX}) + endif () + elseif (${CMAKE_${LANGUAGE}_COMPILER_ID} STREQUAL AppleClang) + # using AppleClang + string(REPLACE "." ";" VERSION_LIST ${CMAKE_${LANGUAGE}_COMPILER_VERSION}) + list(GET VERSION_LIST 0 MAJOR) + list(GET VERSION_LIST 1 MINOR) + set(_CONAN_SETTING_COMPILER apple-clang) + set(_CONAN_SETTING_COMPILER_VERSION ${MAJOR}.${MINOR}) + if (USING_CXX) + conan_cmake_detect_unix_libcxx(_LIBCXX) + set(_CONAN_SETTING_COMPILER_LIBCXX ${_LIBCXX}) + endif () + elseif (${CMAKE_${LANGUAGE}_COMPILER_ID} STREQUAL Clang) + string(REPLACE "." ";" VERSION_LIST ${CMAKE_${LANGUAGE}_COMPILER_VERSION}) + list(GET VERSION_LIST 0 MAJOR) + list(GET VERSION_LIST 1 MINOR) + set(_CONAN_SETTING_COMPILER clang) + set(_CONAN_SETTING_COMPILER_VERSION ${MAJOR}.${MINOR}) + if(APPLE) + cmake_policy(GET CMP0025 APPLE_CLANG_POLICY_ENABLED) + if(NOT APPLE_CLANG_POLICY_ENABLED) + message(STATUS "Conan: APPLE and Clang detected. Assuming apple-clang compiler. Set CMP0025 to avoid it") + set(_CONAN_SETTING_COMPILER apple-clang) + endif() + endif() + if(${_CONAN_SETTING_COMPILER} STREQUAL clang AND ${MAJOR} GREATER 7) + set(_CONAN_SETTING_COMPILER_VERSION ${MAJOR}) + endif() + if (USING_CXX) + conan_cmake_detect_unix_libcxx(_LIBCXX) + set(_CONAN_SETTING_COMPILER_LIBCXX ${_LIBCXX}) + endif () + elseif(${CMAKE_${LANGUAGE}_COMPILER_ID} STREQUAL MSVC) + set(_VISUAL "Visual Studio") + _get_msvc_ide_version(_VISUAL_VERSION) + if("${_VISUAL_VERSION}" STREQUAL "") + message(FATAL_ERROR "Conan: Visual Studio not recognized") + else() + set(_CONAN_SETTING_COMPILER ${_VISUAL}) + set(_CONAN_SETTING_COMPILER_VERSION ${_VISUAL_VERSION}) + endif() + + if(NOT _CONAN_SETTING_ARCH) + if (MSVC_${LANGUAGE}_ARCHITECTURE_ID MATCHES "64") + set(_CONAN_SETTING_ARCH x86_64) + elseif (MSVC_${LANGUAGE}_ARCHITECTURE_ID MATCHES "^ARM") + message(STATUS "Conan: Using default ARM architecture from MSVC") + set(_CONAN_SETTING_ARCH armv6) + elseif (MSVC_${LANGUAGE}_ARCHITECTURE_ID MATCHES "86") + set(_CONAN_SETTING_ARCH x86) + else () + message(FATAL_ERROR "Conan: Unknown MSVC architecture [${MSVC_${LANGUAGE}_ARCHITECTURE_ID}]") + endif() + endif() + + conan_cmake_detect_vs_runtime(_vs_runtime) + message(STATUS "Conan: Detected VS runtime: ${_vs_runtime}") + set(_CONAN_SETTING_COMPILER_RUNTIME ${_vs_runtime}) + + if (CMAKE_GENERATOR_TOOLSET) + set(_CONAN_SETTING_COMPILER_TOOLSET ${CMAKE_VS_PLATFORM_TOOLSET}) + elseif(CMAKE_VS_PLATFORM_TOOLSET AND (CMAKE_GENERATOR STREQUAL "Ninja")) + set(_CONAN_SETTING_COMPILER_TOOLSET ${CMAKE_VS_PLATFORM_TOOLSET}) + endif() + else() + message(FATAL_ERROR "Conan: compiler setup not recognized") + endif() + + # If profile is defined it is used + if(CMAKE_BUILD_TYPE STREQUAL "Debug" AND ARGUMENTS_DEBUG_PROFILE) + set(_APPLIED_PROFILES ${ARGUMENTS_DEBUG_PROFILE}) + elseif(CMAKE_BUILD_TYPE STREQUAL "Release" AND ARGUMENTS_RELEASE_PROFILE) + set(_APPLIED_PROFILES ${ARGUMENTS_RELEASE_PROFILE}) + elseif(CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo" AND ARGUMENTS_RELWITHDEBINFO_PROFILE) + set(_APPLIED_PROFILES ${ARGUMENTS_RELWITHDEBINFO_PROFILE}) + elseif(CMAKE_BUILD_TYPE STREQUAL "MinSizeRel" AND ARGUMENTS_MINSIZEREL_PROFILE) + set(_APPLIED_PROFILES ${ARGUMENTS_MINSIZEREL_PROFILE}) + elseif(ARGUMENTS_PROFILE) + set(_APPLIED_PROFILES ${ARGUMENTS_PROFILE}) + endif() + + foreach(ARG ${_APPLIED_PROFILES}) + set(_SETTINGS ${_SETTINGS} -pr ${ARG}) + endforeach() + + if(NOT _SETTINGS OR ARGUMENTS_PROFILE_AUTO STREQUAL "ALL") + set(ARGUMENTS_PROFILE_AUTO arch build_type compiler compiler.version + compiler.runtime compiler.libcxx compiler.toolset) + endif() + + # Automatic from CMake + foreach(ARG ${ARGUMENTS_PROFILE_AUTO}) + string(TOUPPER ${ARG} _arg_name) + string(REPLACE "." "_" _arg_name ${_arg_name}) + if(_CONAN_SETTING_${_arg_name}) + set(_SETTINGS ${_SETTINGS} -s ${ARG}=${_CONAN_SETTING_${_arg_name}}) + endif() + endforeach() + + foreach(ARG ${ARGUMENTS_SETTINGS}) + set(_SETTINGS ${_SETTINGS} -s ${ARG}) + endforeach() + + message(STATUS "Conan: Settings= ${_SETTINGS}") + + set(${result} ${_SETTINGS} PARENT_SCOPE) +endfunction() + + +function(conan_cmake_detect_unix_libcxx result) + # Take into account any -stdlib in compile options + get_directory_property(compile_options DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} COMPILE_OPTIONS) + + # Take into account any _GLIBCXX_USE_CXX11_ABI in compile definitions + get_directory_property(defines DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} COMPILE_DEFINITIONS) + foreach(define ${defines}) + if(define MATCHES "_GLIBCXX_USE_CXX11_ABI") + if(define MATCHES "^-D") + set(compile_options ${compile_options} "${define}") + else() + set(compile_options ${compile_options} "-D${define}") + endif() + endif() + endforeach() + + execute_process( + COMMAND ${CMAKE_COMMAND} -E echo "#include " + COMMAND ${CMAKE_CXX_COMPILER} -x c++ ${compile_options} -E -dM - + OUTPUT_VARIABLE string_defines + ) + + if(string_defines MATCHES "#define __GLIBCXX__") + # Allow -D_GLIBCXX_USE_CXX11_ABI=ON/OFF as argument to cmake + if(DEFINED _GLIBCXX_USE_CXX11_ABI) + if(_GLIBCXX_USE_CXX11_ABI) + set(${result} libstdc++11 PARENT_SCOPE) + return() + else() + set(${result} libstdc++ PARENT_SCOPE) + return() + endif() + endif() + + if(string_defines MATCHES "#define _GLIBCXX_USE_CXX11_ABI 1\n") + set(${result} libstdc++11 PARENT_SCOPE) + else() + # Either the compiler is missing the define because it is old, and so + # it can't use the new abi, or the compiler was configured to use the + # old abi by the user or distro (e.g. devtoolset on RHEL/CentOS) + set(${result} libstdc++ PARENT_SCOPE) + endif() + else() + set(${result} libc++ PARENT_SCOPE) + endif() +endfunction() + +function(conan_cmake_detect_vs_runtime result) + string(TOUPPER ${CMAKE_BUILD_TYPE} build_type) + set(variables CMAKE_CXX_FLAGS_${build_type} CMAKE_C_FLAGS_${build_type} CMAKE_CXX_FLAGS CMAKE_C_FLAGS) + foreach(variable ${variables}) + string(REPLACE " " ";" flags ${${variable}}) + foreach (flag ${flags}) + if(${flag} STREQUAL "/MD" OR ${flag} STREQUAL "/MDd" OR ${flag} STREQUAL "/MT" OR ${flag} STREQUAL "/MTd") + string(SUBSTRING ${flag} 1 -1 runtime) + set(${result} ${runtime} PARENT_SCOPE) + return() + endif() + endforeach() + endforeach() + if(${build_type} STREQUAL "DEBUG") + set(${result} "MDd" PARENT_SCOPE) + else() + set(${result} "MD" PARENT_SCOPE) + endif() +endfunction() + + +macro(parse_arguments) + set(options BASIC_SETUP CMAKE_TARGETS UPDATE KEEP_RPATHS NO_LOAD NO_OUTPUT_DIRS OUTPUT_QUIET NO_IMPORTS) + set(oneValueArgs CONANFILE ARCH BUILD_TYPE INSTALL_FOLDER CONAN_COMMAND) + set(multiValueArgs DEBUG_PROFILE RELEASE_PROFILE RELWITHDEBINFO_PROFILE MINSIZEREL_PROFILE + PROFILE REQUIRES OPTIONS IMPORTS SETTINGS BUILD ENV GENERATORS PROFILE_AUTO + INSTALL_ARGS) + cmake_parse_arguments(ARGUMENTS "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) +endmacro() + +function(conan_cmake_install) + # Calls "conan install" + # Argument BUILD is equivalant to --build={missing, PkgName,...} or + # --build when argument is 'BUILD all' (which builds all packages from source) + # Argument CONAN_COMMAND, to specify the conan path, e.g. in case of running from source + # cmake does not identify conan as command, even if it is +x and it is in the path + parse_arguments(${ARGV}) + + if(CONAN_CMAKE_MULTI) + set(ARGUMENTS_GENERATORS ${ARGUMENTS_GENERATORS} cmake_multi) + else() + set(ARGUMENTS_GENERATORS ${ARGUMENTS_GENERATORS} cmake) + endif() + + set(CONAN_BUILD_POLICY "") + foreach(ARG ${ARGUMENTS_BUILD}) + if(${ARG} STREQUAL "all") + set(CONAN_BUILD_POLICY ${CONAN_BUILD_POLICY} --build) + break() + else() + set(CONAN_BUILD_POLICY ${CONAN_BUILD_POLICY} --build=${ARG}) + endif() + endforeach() + if(ARGUMENTS_CONAN_COMMAND) + set(conan_command ${ARGUMENTS_CONAN_COMMAND}) + else() + set(conan_command conan) + endif() + set(CONAN_OPTIONS "") + if(ARGUMENTS_CONANFILE) + set(CONANFILE ${CMAKE_CURRENT_SOURCE_DIR}/${ARGUMENTS_CONANFILE}) + # A conan file has been specified - apply specified options as well if provided + foreach(ARG ${ARGUMENTS_OPTIONS}) + set(CONAN_OPTIONS ${CONAN_OPTIONS} -o=${ARG}) + endforeach() + else() + set(CONANFILE ".") + endif() + if(ARGUMENTS_UPDATE) + set(CONAN_INSTALL_UPDATE --update) + endif() + if(ARGUMENTS_NO_IMPORTS) + set(CONAN_INSTALL_NO_IMPORTS --no-imports) + endif() + set(CONAN_INSTALL_FOLDER "") + if(ARGUMENTS_INSTALL_FOLDER) + set(CONAN_INSTALL_FOLDER -if=${ARGUMENTS_INSTALL_FOLDER}) + endif() + foreach(ARG ${ARGUMENTS_GENERATORS}) + set(CONAN_GENERATORS ${CONAN_GENERATORS} -g=${ARG}) + endforeach() + foreach(ARG ${ARGUMENTS_ENV}) + set(CONAN_ENV_VARS ${CONAN_ENV_VARS} -e=${ARG}) + endforeach() + set(conan_args install ${CONANFILE} ${settings} ${CONAN_ENV_VARS} ${CONAN_GENERATORS} ${CONAN_BUILD_POLICY} ${CONAN_INSTALL_UPDATE} ${CONAN_INSTALL_NO_IMPORTS} ${CONAN_OPTIONS} ${CONAN_INSTALL_FOLDER} ${ARGUMENTS_INSTALL_ARGS}) + + string (REPLACE ";" " " _conan_args "${conan_args}") + message(STATUS "Conan executing: ${conan_command} ${_conan_args}") + + if(ARGUMENTS_OUTPUT_QUIET) + execute_process(COMMAND ${conan_command} ${conan_args} + RESULT_VARIABLE return_code + OUTPUT_VARIABLE conan_output + ERROR_VARIABLE conan_output + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + else() + execute_process(COMMAND ${conan_command} ${conan_args} + RESULT_VARIABLE return_code + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + endif() + + if(NOT "${return_code}" STREQUAL "0") + message(FATAL_ERROR "Conan install failed='${return_code}'") + endif() + +endfunction() + + +function(conan_cmake_setup_conanfile) + parse_arguments(${ARGV}) + if(ARGUMENTS_CONANFILE) + get_filename_component(_CONANFILE_NAME ${ARGUMENTS_CONANFILE} NAME) + # configure_file will make sure cmake re-runs when conanfile is updated + configure_file(${ARGUMENTS_CONANFILE} ${CMAKE_CURRENT_BINARY_DIR}/${_CONANFILE_NAME}.junk) + file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/${_CONANFILE_NAME}.junk) + else() + conan_cmake_generate_conanfile(${ARGV}) + endif() +endfunction() + +function(conan_cmake_generate_conanfile) + # Generate, writing in disk a conanfile.txt with the requires, options, and imports + # specified as arguments + # This will be considered as temporary file, generated in CMAKE_CURRENT_BINARY_DIR) + parse_arguments(${ARGV}) + set(_FN "${CMAKE_CURRENT_BINARY_DIR}/conanfile.txt") + + file(WRITE ${_FN} "[generators]\ncmake\n\n[requires]\n") + foreach(ARG ${ARGUMENTS_REQUIRES}) + file(APPEND ${_FN} ${ARG} "\n") + endforeach() + + file(APPEND ${_FN} ${ARG} "\n[options]\n") + foreach(ARG ${ARGUMENTS_OPTIONS}) + file(APPEND ${_FN} ${ARG} "\n") + endforeach() + + file(APPEND ${_FN} ${ARG} "\n[imports]\n") + foreach(ARG ${ARGUMENTS_IMPORTS}) + file(APPEND ${_FN} ${ARG} "\n") + endforeach() +endfunction() + + +macro(conan_load_buildinfo) + if(CONAN_CMAKE_MULTI) + set(_CONANBUILDINFO conanbuildinfo_multi.cmake) + else() + set(_CONANBUILDINFO conanbuildinfo.cmake) + endif() + if(ARGUMENTS_INSTALL_FOLDER) + set(_CONANBUILDINFOFOLDER ${ARGUMENTS_INSTALL_FOLDER}) + else() + set(_CONANBUILDINFOFOLDER ${CMAKE_CURRENT_BINARY_DIR}) + endif() + # Checks for the existence of conanbuildinfo.cmake, and loads it + # important that it is macro, so variables defined at parent scope + if(EXISTS "${_CONANBUILDINFOFOLDER}/${_CONANBUILDINFO}") + message(STATUS "Conan: Loading ${_CONANBUILDINFO}") + include(${_CONANBUILDINFOFOLDER}/${_CONANBUILDINFO}) + else() + message(FATAL_ERROR "${_CONANBUILDINFO} doesn't exist in ${CMAKE_CURRENT_BINARY_DIR}") + endif() +endmacro() + + +macro(conan_cmake_run) + parse_arguments(${ARGV}) + + if(CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE AND NOT CONAN_EXPORTED + AND NOT ARGUMENTS_BUILD_TYPE) + set(CONAN_CMAKE_MULTI ON) + message(STATUS "Conan: Using cmake-multi generator") + else() + set(CONAN_CMAKE_MULTI OFF) + endif() + + if(NOT CONAN_EXPORTED) + conan_cmake_setup_conanfile(${ARGV}) + if(CONAN_CMAKE_MULTI) + foreach(CMAKE_BUILD_TYPE "Release" "Debug") + set(ENV{CONAN_IMPORT_PATH} ${CMAKE_BUILD_TYPE}) + conan_cmake_settings(settings ${ARGV}) + conan_cmake_install(SETTINGS ${settings} ${ARGV}) + endforeach() + set(CMAKE_BUILD_TYPE) + else() + conan_cmake_settings(settings ${ARGV}) + conan_cmake_install(SETTINGS ${settings} ${ARGV}) + endif() + endif() + + if (NOT ARGUMENTS_NO_LOAD) + conan_load_buildinfo() + endif() + + if(ARGUMENTS_BASIC_SETUP) + foreach(_option CMAKE_TARGETS KEEP_RPATHS NO_OUTPUT_DIRS) + if(ARGUMENTS_${_option}) + if(${_option} STREQUAL "CMAKE_TARGETS") + list(APPEND _setup_options "TARGETS") + else() + list(APPEND _setup_options ${_option}) + endif() + endif() + endforeach() + conan_basic_setup(${_setup_options}) + endif() +endmacro() + +macro(conan_check) + # Checks conan availability in PATH + # Arguments REQUIRED and VERSION are optional + # Example usage: + # conan_check(VERSION 1.0.0 REQUIRED) + message(STATUS "Conan: checking conan executable in path") + set(options REQUIRED) + set(oneValueArgs VERSION) + cmake_parse_arguments(CONAN "${options}" "${oneValueArgs}" "" ${ARGN}) + + find_program(CONAN_CMD conan) + if(NOT CONAN_CMD AND CONAN_REQUIRED) + message(FATAL_ERROR "Conan executable not found!") + endif() + message(STATUS "Conan: Found program ${CONAN_CMD}") + execute_process(COMMAND ${CONAN_CMD} --version + OUTPUT_VARIABLE CONAN_VERSION_OUTPUT + ERROR_VARIABLE CONAN_VERSION_OUTPUT) + message(STATUS "Conan: Version found ${CONAN_VERSION_OUTPUT}") + + if(DEFINED CONAN_VERSION) + string(REGEX MATCH ".*Conan version ([0-9]+\.[0-9]+\.[0-9]+)" FOO + "${CONAN_VERSION_OUTPUT}") + if(${CMAKE_MATCH_1} VERSION_LESS ${CONAN_VERSION}) + message(FATAL_ERROR "Conan outdated. Installed: ${CMAKE_MATCH_1}, \ + required: ${CONAN_VERSION}. Consider updating via 'pip \ + install conan==${CONAN_VERSION}'.") + endif() + endif() +endmacro() + +macro(conan_add_remote) + # Adds a remote + # Arguments URL and NAME are required, INDEX is optional + # Example usage: + # conan_add_remote(NAME bincrafters INDEX 1 + # URL https://api.bintray.com/conan/bincrafters/public-conan) + set(oneValueArgs URL NAME INDEX) + cmake_parse_arguments(CONAN "" "${oneValueArgs}" "" ${ARGN}) + + if(DEFINED CONAN_INDEX) + set(CONAN_INDEX_ARG "-i ${CONAN_INDEX}") + endif() + + message(STATUS "Conan: Adding ${CONAN_NAME} remote repository (${CONAN_URL})") + execute_process(COMMAND ${CONAN_CMD} remote add ${CONAN_NAME} ${CONAN_URL} + ${CONAN_INDEX_ARG} -f) +endmacro() diff --git a/ros_kortex/kortex_driver/conanfile.py b/ros_kortex/kortex_driver/conanfile.py new file mode 100644 index 0000000..d494eff --- /dev/null +++ b/ros_kortex/kortex_driver/conanfile.py @@ -0,0 +1,9 @@ +from conans import ConanFile, CMake +import os +import shutil +import time + +class ROSKortexConan(ConanFile): + + def requirements(self): + self.requires("kortex_api_cpp/2.2.0-r.31@kortex/stable") diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/actuatorconfig_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/actuatorconfig_services_interface.h new file mode 100644 index 0000000..0aedc89 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/actuatorconfig_services_interface.h @@ -0,0 +1,111 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCONFIG_SERVICES_INTERFACE_H_ +#define _KORTEX_ACTUATORCONFIG_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/GetAxisOffsets.h" +#include "kortex_driver/SetAxisOffsets.h" +#include "kortex_driver/SetTorqueOffset.h" +#include "kortex_driver/ActuatorConfig_GetControlMode.h" +#include "kortex_driver/SetControlMode.h" +#include "kortex_driver/GetActivatedControlLoop.h" +#include "kortex_driver/SetActivatedControlLoop.h" +#include "kortex_driver/GetControlLoopParameters.h" +#include "kortex_driver/SetControlLoopParameters.h" +#include "kortex_driver/SelectCustomData.h" +#include "kortex_driver/GetSelectedCustomData.h" +#include "kortex_driver/SetCommandMode.h" +#include "kortex_driver/ActuatorConfig_ClearFaults.h" +#include "kortex_driver/SetServoing.h" +#include "kortex_driver/MoveToPosition.h" +#include "kortex_driver/GetCommandMode.h" +#include "kortex_driver/GetServoing.h" +#include "kortex_driver/GetTorqueOffset.h" +#include "kortex_driver/SetCoggingFeedforwardMode.h" +#include "kortex_driver/GetCoggingFeedforwardMode.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IActuatorConfigServices +{ + public: + IActuatorConfigServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool GetAxisOffsets(kortex_driver::GetAxisOffsets::Request &req, kortex_driver::GetAxisOffsets::Response &res) = 0; + virtual bool SetAxisOffsets(kortex_driver::SetAxisOffsets::Request &req, kortex_driver::SetAxisOffsets::Response &res) = 0; + virtual bool SetTorqueOffset(kortex_driver::SetTorqueOffset::Request &req, kortex_driver::SetTorqueOffset::Response &res) = 0; + virtual bool ActuatorConfig_GetControlMode(kortex_driver::ActuatorConfig_GetControlMode::Request &req, kortex_driver::ActuatorConfig_GetControlMode::Response &res) = 0; + virtual bool SetControlMode(kortex_driver::SetControlMode::Request &req, kortex_driver::SetControlMode::Response &res) = 0; + virtual bool GetActivatedControlLoop(kortex_driver::GetActivatedControlLoop::Request &req, kortex_driver::GetActivatedControlLoop::Response &res) = 0; + virtual bool SetActivatedControlLoop(kortex_driver::SetActivatedControlLoop::Request &req, kortex_driver::SetActivatedControlLoop::Response &res) = 0; + virtual bool GetControlLoopParameters(kortex_driver::GetControlLoopParameters::Request &req, kortex_driver::GetControlLoopParameters::Response &res) = 0; + virtual bool SetControlLoopParameters(kortex_driver::SetControlLoopParameters::Request &req, kortex_driver::SetControlLoopParameters::Response &res) = 0; + virtual bool SelectCustomData(kortex_driver::SelectCustomData::Request &req, kortex_driver::SelectCustomData::Response &res) = 0; + virtual bool GetSelectedCustomData(kortex_driver::GetSelectedCustomData::Request &req, kortex_driver::GetSelectedCustomData::Response &res) = 0; + virtual bool SetCommandMode(kortex_driver::SetCommandMode::Request &req, kortex_driver::SetCommandMode::Response &res) = 0; + virtual bool ActuatorConfig_ClearFaults(kortex_driver::ActuatorConfig_ClearFaults::Request &req, kortex_driver::ActuatorConfig_ClearFaults::Response &res) = 0; + virtual bool SetServoing(kortex_driver::SetServoing::Request &req, kortex_driver::SetServoing::Response &res) = 0; + virtual bool MoveToPosition(kortex_driver::MoveToPosition::Request &req, kortex_driver::MoveToPosition::Response &res) = 0; + virtual bool GetCommandMode(kortex_driver::GetCommandMode::Request &req, kortex_driver::GetCommandMode::Response &res) = 0; + virtual bool GetServoing(kortex_driver::GetServoing::Request &req, kortex_driver::GetServoing::Response &res) = 0; + virtual bool GetTorqueOffset(kortex_driver::GetTorqueOffset::Request &req, kortex_driver::GetTorqueOffset::Response &res) = 0; + virtual bool SetCoggingFeedforwardMode(kortex_driver::SetCoggingFeedforwardMode::Request &req, kortex_driver::SetCoggingFeedforwardMode::Response &res) = 0; + virtual bool GetCoggingFeedforwardMode(kortex_driver::GetCoggingFeedforwardMode::Request &req, kortex_driver::GetCoggingFeedforwardMode::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceGetAxisOffsets; + ros::ServiceServer m_serviceSetAxisOffsets; + ros::ServiceServer m_serviceSetTorqueOffset; + ros::ServiceServer m_serviceActuatorConfig_GetControlMode; + ros::ServiceServer m_serviceSetControlMode; + ros::ServiceServer m_serviceGetActivatedControlLoop; + ros::ServiceServer m_serviceSetActivatedControlLoop; + ros::ServiceServer m_serviceGetControlLoopParameters; + ros::ServiceServer m_serviceSetControlLoopParameters; + ros::ServiceServer m_serviceSelectCustomData; + ros::ServiceServer m_serviceGetSelectedCustomData; + ros::ServiceServer m_serviceSetCommandMode; + ros::ServiceServer m_serviceActuatorConfig_ClearFaults; + ros::ServiceServer m_serviceSetServoing; + ros::ServiceServer m_serviceMoveToPosition; + ros::ServiceServer m_serviceGetCommandMode; + ros::ServiceServer m_serviceGetServoing; + ros::ServiceServer m_serviceGetTorqueOffset; + ros::ServiceServer m_serviceSetCoggingFeedforwardMode; + ros::ServiceServer m_serviceGetCoggingFeedforwardMode; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/base_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/base_services_interface.h new file mode 100644 index 0000000..1df8686 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/base_services_interface.h @@ -0,0 +1,539 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASE_SERVICES_INTERFACE_H_ +#define _KORTEX_BASE_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/CreateUserProfile.h" +#include "kortex_driver/UpdateUserProfile.h" +#include "kortex_driver/ReadUserProfile.h" +#include "kortex_driver/DeleteUserProfile.h" +#include "kortex_driver/ReadAllUserProfiles.h" +#include "kortex_driver/ReadAllUsers.h" +#include "kortex_driver/ChangePassword.h" +#include "kortex_driver/CreateSequence.h" +#include "kortex_driver/UpdateSequence.h" +#include "kortex_driver/ReadSequence.h" +#include "kortex_driver/DeleteSequence.h" +#include "kortex_driver/ReadAllSequences.h" +#include "kortex_driver/PlaySequence.h" +#include "kortex_driver/PlayAdvancedSequence.h" +#include "kortex_driver/StopSequence.h" +#include "kortex_driver/PauseSequence.h" +#include "kortex_driver/ResumeSequence.h" +#include "kortex_driver/CreateProtectionZone.h" +#include "kortex_driver/UpdateProtectionZone.h" +#include "kortex_driver/ReadProtectionZone.h" +#include "kortex_driver/DeleteProtectionZone.h" +#include "kortex_driver/ReadAllProtectionZones.h" +#include "kortex_driver/CreateMapping.h" +#include "kortex_driver/ReadMapping.h" +#include "kortex_driver/UpdateMapping.h" +#include "kortex_driver/DeleteMapping.h" +#include "kortex_driver/ReadAllMappings.h" +#include "kortex_driver/CreateMap.h" +#include "kortex_driver/ReadMap.h" +#include "kortex_driver/UpdateMap.h" +#include "kortex_driver/DeleteMap.h" +#include "kortex_driver/ReadAllMaps.h" +#include "kortex_driver/ActivateMap.h" +#include "kortex_driver/CreateAction.h" +#include "kortex_driver/ReadAction.h" +#include "kortex_driver/ReadAllActions.h" +#include "kortex_driver/DeleteAction.h" +#include "kortex_driver/UpdateAction.h" +#include "kortex_driver/ExecuteActionFromReference.h" +#include "kortex_driver/ExecuteAction.h" +#include "kortex_driver/PauseAction.h" +#include "kortex_driver/StopAction.h" +#include "kortex_driver/ResumeAction.h" +#include "kortex_driver/GetIPv4Configuration.h" +#include "kortex_driver/SetIPv4Configuration.h" +#include "kortex_driver/SetCommunicationInterfaceEnable.h" +#include "kortex_driver/IsCommunicationInterfaceEnable.h" +#include "kortex_driver/GetAvailableWifi.h" +#include "kortex_driver/GetWifiInformation.h" +#include "kortex_driver/AddWifiConfiguration.h" +#include "kortex_driver/DeleteWifiConfiguration.h" +#include "kortex_driver/GetAllConfiguredWifis.h" +#include "kortex_driver/ConnectWifi.h" +#include "kortex_driver/DisconnectWifi.h" +#include "kortex_driver/GetConnectedWifiInformation.h" +#include "kortex_driver/Base_Unsubscribe.h" +#include "kortex_driver/OnNotificationConfigurationChangeTopic.h" +#include "kortex_driver/ConfigurationChangeNotification.h" +#include "kortex_driver/OnNotificationMappingInfoTopic.h" +#include "kortex_driver/MappingInfoNotification.h" +#include "kortex_driver/OnNotificationControlModeTopic.h" +#include "kortex_driver/ControlModeNotification.h" +#include "kortex_driver/OnNotificationOperatingModeTopic.h" +#include "kortex_driver/OperatingModeNotification.h" +#include "kortex_driver/OnNotificationSequenceInfoTopic.h" +#include "kortex_driver/SequenceInfoNotification.h" +#include "kortex_driver/OnNotificationProtectionZoneTopic.h" +#include "kortex_driver/ProtectionZoneNotification.h" +#include "kortex_driver/OnNotificationUserTopic.h" +#include "kortex_driver/UserNotification.h" +#include "kortex_driver/OnNotificationControllerTopic.h" +#include "kortex_driver/ControllerNotification.h" +#include "kortex_driver/OnNotificationActionTopic.h" +#include "kortex_driver/ActionNotification.h" +#include "kortex_driver/OnNotificationRobotEventTopic.h" +#include "kortex_driver/RobotEventNotification.h" +#include "kortex_driver/PlayCartesianTrajectory.h" +#include "kortex_driver/PlayCartesianTrajectoryPosition.h" +#include "kortex_driver/PlayCartesianTrajectoryOrientation.h" +#include "kortex_driver/Stop.h" +#include "kortex_driver/GetMeasuredCartesianPose.h" +#include "kortex_driver/SendWrenchCommand.h" +#include "kortex_driver/SendWrenchJoystickCommand.h" +#include "kortex_driver/SendTwistJoystickCommand.h" +#include "kortex_driver/SendTwistCommand.h" +#include "kortex_driver/PlayJointTrajectory.h" +#include "kortex_driver/PlaySelectedJointTrajectory.h" +#include "kortex_driver/GetMeasuredJointAngles.h" +#include "kortex_driver/SendJointSpeedsCommand.h" +#include "kortex_driver/SendSelectedJointSpeedCommand.h" +#include "kortex_driver/SendGripperCommand.h" +#include "kortex_driver/GetMeasuredGripperMovement.h" +#include "kortex_driver/SetAdmittance.h" +#include "kortex_driver/SetOperatingMode.h" +#include "kortex_driver/ApplyEmergencyStop.h" +#include "kortex_driver/Base_ClearFaults.h" +#include "kortex_driver/Base_GetControlMode.h" +#include "kortex_driver/GetOperatingMode.h" +#include "kortex_driver/SetServoingMode.h" +#include "kortex_driver/GetServoingMode.h" +#include "kortex_driver/OnNotificationServoingModeTopic.h" +#include "kortex_driver/ServoingModeNotification.h" +#include "kortex_driver/RestoreFactorySettings.h" +#include "kortex_driver/OnNotificationFactoryTopic.h" +#include "kortex_driver/FactoryNotification.h" +#include "kortex_driver/GetAllConnectedControllers.h" +#include "kortex_driver/GetControllerState.h" +#include "kortex_driver/GetActuatorCount.h" +#include "kortex_driver/StartWifiScan.h" +#include "kortex_driver/GetConfiguredWifi.h" +#include "kortex_driver/OnNotificationNetworkTopic.h" +#include "kortex_driver/NetworkNotification.h" +#include "kortex_driver/GetArmState.h" +#include "kortex_driver/OnNotificationArmStateTopic.h" +#include "kortex_driver/ArmStateNotification.h" +#include "kortex_driver/GetIPv4Information.h" +#include "kortex_driver/SetWifiCountryCode.h" +#include "kortex_driver/GetWifiCountryCode.h" +#include "kortex_driver/Base_SetCapSenseConfig.h" +#include "kortex_driver/Base_GetCapSenseConfig.h" +#include "kortex_driver/GetAllJointsSpeedHardLimitation.h" +#include "kortex_driver/GetAllJointsTorqueHardLimitation.h" +#include "kortex_driver/GetTwistHardLimitation.h" +#include "kortex_driver/GetWrenchHardLimitation.h" +#include "kortex_driver/SendJointSpeedsJoystickCommand.h" +#include "kortex_driver/SendSelectedJointSpeedJoystickCommand.h" +#include "kortex_driver/EnableBridge.h" +#include "kortex_driver/DisableBridge.h" +#include "kortex_driver/GetBridgeList.h" +#include "kortex_driver/GetBridgeConfig.h" +#include "kortex_driver/PlayPreComputedJointTrajectory.h" +#include "kortex_driver/GetProductConfiguration.h" +#include "kortex_driver/UpdateEndEffectorTypeConfiguration.h" +#include "kortex_driver/RestoreFactoryProductConfiguration.h" +#include "kortex_driver/GetTrajectoryErrorReport.h" +#include "kortex_driver/GetAllJointsSpeedSoftLimitation.h" +#include "kortex_driver/GetAllJointsTorqueSoftLimitation.h" +#include "kortex_driver/GetTwistSoftLimitation.h" +#include "kortex_driver/GetWrenchSoftLimitation.h" +#include "kortex_driver/SetControllerConfigurationMode.h" +#include "kortex_driver/GetControllerConfigurationMode.h" +#include "kortex_driver/StartTeaching.h" +#include "kortex_driver/StopTeaching.h" +#include "kortex_driver/AddSequenceTasks.h" +#include "kortex_driver/UpdateSequenceTask.h" +#include "kortex_driver/SwapSequenceTasks.h" +#include "kortex_driver/ReadSequenceTask.h" +#include "kortex_driver/ReadAllSequenceTasks.h" +#include "kortex_driver/DeleteSequenceTask.h" +#include "kortex_driver/DeleteAllSequenceTasks.h" +#include "kortex_driver/TakeSnapshot.h" +#include "kortex_driver/GetFirmwareBundleVersions.h" +#include "kortex_driver/MoveSequenceTask.h" +#include "kortex_driver/DuplicateMapping.h" +#include "kortex_driver/DuplicateMap.h" +#include "kortex_driver/SetControllerConfiguration.h" +#include "kortex_driver/GetControllerConfiguration.h" +#include "kortex_driver/GetAllControllerConfigurations.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IBaseServices +{ + public: + IBaseServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool CreateUserProfile(kortex_driver::CreateUserProfile::Request &req, kortex_driver::CreateUserProfile::Response &res) = 0; + virtual bool UpdateUserProfile(kortex_driver::UpdateUserProfile::Request &req, kortex_driver::UpdateUserProfile::Response &res) = 0; + virtual bool ReadUserProfile(kortex_driver::ReadUserProfile::Request &req, kortex_driver::ReadUserProfile::Response &res) = 0; + virtual bool DeleteUserProfile(kortex_driver::DeleteUserProfile::Request &req, kortex_driver::DeleteUserProfile::Response &res) = 0; + virtual bool ReadAllUserProfiles(kortex_driver::ReadAllUserProfiles::Request &req, kortex_driver::ReadAllUserProfiles::Response &res) = 0; + virtual bool ReadAllUsers(kortex_driver::ReadAllUsers::Request &req, kortex_driver::ReadAllUsers::Response &res) = 0; + virtual bool ChangePassword(kortex_driver::ChangePassword::Request &req, kortex_driver::ChangePassword::Response &res) = 0; + virtual bool CreateSequence(kortex_driver::CreateSequence::Request &req, kortex_driver::CreateSequence::Response &res) = 0; + virtual bool UpdateSequence(kortex_driver::UpdateSequence::Request &req, kortex_driver::UpdateSequence::Response &res) = 0; + virtual bool ReadSequence(kortex_driver::ReadSequence::Request &req, kortex_driver::ReadSequence::Response &res) = 0; + virtual bool DeleteSequence(kortex_driver::DeleteSequence::Request &req, kortex_driver::DeleteSequence::Response &res) = 0; + virtual bool ReadAllSequences(kortex_driver::ReadAllSequences::Request &req, kortex_driver::ReadAllSequences::Response &res) = 0; + virtual bool PlaySequence(kortex_driver::PlaySequence::Request &req, kortex_driver::PlaySequence::Response &res) = 0; + virtual bool PlayAdvancedSequence(kortex_driver::PlayAdvancedSequence::Request &req, kortex_driver::PlayAdvancedSequence::Response &res) = 0; + virtual bool StopSequence(kortex_driver::StopSequence::Request &req, kortex_driver::StopSequence::Response &res) = 0; + virtual bool PauseSequence(kortex_driver::PauseSequence::Request &req, kortex_driver::PauseSequence::Response &res) = 0; + virtual bool ResumeSequence(kortex_driver::ResumeSequence::Request &req, kortex_driver::ResumeSequence::Response &res) = 0; + virtual bool CreateProtectionZone(kortex_driver::CreateProtectionZone::Request &req, kortex_driver::CreateProtectionZone::Response &res) = 0; + virtual bool UpdateProtectionZone(kortex_driver::UpdateProtectionZone::Request &req, kortex_driver::UpdateProtectionZone::Response &res) = 0; + virtual bool ReadProtectionZone(kortex_driver::ReadProtectionZone::Request &req, kortex_driver::ReadProtectionZone::Response &res) = 0; + virtual bool DeleteProtectionZone(kortex_driver::DeleteProtectionZone::Request &req, kortex_driver::DeleteProtectionZone::Response &res) = 0; + virtual bool ReadAllProtectionZones(kortex_driver::ReadAllProtectionZones::Request &req, kortex_driver::ReadAllProtectionZones::Response &res) = 0; + virtual bool CreateMapping(kortex_driver::CreateMapping::Request &req, kortex_driver::CreateMapping::Response &res) = 0; + virtual bool ReadMapping(kortex_driver::ReadMapping::Request &req, kortex_driver::ReadMapping::Response &res) = 0; + virtual bool UpdateMapping(kortex_driver::UpdateMapping::Request &req, kortex_driver::UpdateMapping::Response &res) = 0; + virtual bool DeleteMapping(kortex_driver::DeleteMapping::Request &req, kortex_driver::DeleteMapping::Response &res) = 0; + virtual bool ReadAllMappings(kortex_driver::ReadAllMappings::Request &req, kortex_driver::ReadAllMappings::Response &res) = 0; + virtual bool CreateMap(kortex_driver::CreateMap::Request &req, kortex_driver::CreateMap::Response &res) = 0; + virtual bool ReadMap(kortex_driver::ReadMap::Request &req, kortex_driver::ReadMap::Response &res) = 0; + virtual bool UpdateMap(kortex_driver::UpdateMap::Request &req, kortex_driver::UpdateMap::Response &res) = 0; + virtual bool DeleteMap(kortex_driver::DeleteMap::Request &req, kortex_driver::DeleteMap::Response &res) = 0; + virtual bool ReadAllMaps(kortex_driver::ReadAllMaps::Request &req, kortex_driver::ReadAllMaps::Response &res) = 0; + virtual bool ActivateMap(kortex_driver::ActivateMap::Request &req, kortex_driver::ActivateMap::Response &res) = 0; + virtual bool CreateAction(kortex_driver::CreateAction::Request &req, kortex_driver::CreateAction::Response &res) = 0; + virtual bool ReadAction(kortex_driver::ReadAction::Request &req, kortex_driver::ReadAction::Response &res) = 0; + virtual bool ReadAllActions(kortex_driver::ReadAllActions::Request &req, kortex_driver::ReadAllActions::Response &res) = 0; + virtual bool DeleteAction(kortex_driver::DeleteAction::Request &req, kortex_driver::DeleteAction::Response &res) = 0; + virtual bool UpdateAction(kortex_driver::UpdateAction::Request &req, kortex_driver::UpdateAction::Response &res) = 0; + virtual bool ExecuteActionFromReference(kortex_driver::ExecuteActionFromReference::Request &req, kortex_driver::ExecuteActionFromReference::Response &res) = 0; + virtual bool ExecuteAction(kortex_driver::ExecuteAction::Request &req, kortex_driver::ExecuteAction::Response &res) = 0; + virtual bool PauseAction(kortex_driver::PauseAction::Request &req, kortex_driver::PauseAction::Response &res) = 0; + virtual bool StopAction(kortex_driver::StopAction::Request &req, kortex_driver::StopAction::Response &res) = 0; + virtual bool ResumeAction(kortex_driver::ResumeAction::Request &req, kortex_driver::ResumeAction::Response &res) = 0; + virtual bool GetIPv4Configuration(kortex_driver::GetIPv4Configuration::Request &req, kortex_driver::GetIPv4Configuration::Response &res) = 0; + virtual bool SetIPv4Configuration(kortex_driver::SetIPv4Configuration::Request &req, kortex_driver::SetIPv4Configuration::Response &res) = 0; + virtual bool SetCommunicationInterfaceEnable(kortex_driver::SetCommunicationInterfaceEnable::Request &req, kortex_driver::SetCommunicationInterfaceEnable::Response &res) = 0; + virtual bool IsCommunicationInterfaceEnable(kortex_driver::IsCommunicationInterfaceEnable::Request &req, kortex_driver::IsCommunicationInterfaceEnable::Response &res) = 0; + virtual bool GetAvailableWifi(kortex_driver::GetAvailableWifi::Request &req, kortex_driver::GetAvailableWifi::Response &res) = 0; + virtual bool GetWifiInformation(kortex_driver::GetWifiInformation::Request &req, kortex_driver::GetWifiInformation::Response &res) = 0; + virtual bool AddWifiConfiguration(kortex_driver::AddWifiConfiguration::Request &req, kortex_driver::AddWifiConfiguration::Response &res) = 0; + virtual bool DeleteWifiConfiguration(kortex_driver::DeleteWifiConfiguration::Request &req, kortex_driver::DeleteWifiConfiguration::Response &res) = 0; + virtual bool GetAllConfiguredWifis(kortex_driver::GetAllConfiguredWifis::Request &req, kortex_driver::GetAllConfiguredWifis::Response &res) = 0; + virtual bool ConnectWifi(kortex_driver::ConnectWifi::Request &req, kortex_driver::ConnectWifi::Response &res) = 0; + virtual bool DisconnectWifi(kortex_driver::DisconnectWifi::Request &req, kortex_driver::DisconnectWifi::Response &res) = 0; + virtual bool GetConnectedWifiInformation(kortex_driver::GetConnectedWifiInformation::Request &req, kortex_driver::GetConnectedWifiInformation::Response &res) = 0; + virtual bool Base_Unsubscribe(kortex_driver::Base_Unsubscribe::Request &req, kortex_driver::Base_Unsubscribe::Response &res) = 0; + virtual bool OnNotificationConfigurationChangeTopic(kortex_driver::OnNotificationConfigurationChangeTopic::Request &req, kortex_driver::OnNotificationConfigurationChangeTopic::Response &res) = 0; + virtual void cb_ConfigurationChangeTopic(Kinova::Api::Base::ConfigurationChangeNotification notif) = 0; + virtual bool OnNotificationMappingInfoTopic(kortex_driver::OnNotificationMappingInfoTopic::Request &req, kortex_driver::OnNotificationMappingInfoTopic::Response &res) = 0; + virtual void cb_MappingInfoTopic(Kinova::Api::Base::MappingInfoNotification notif) = 0; + virtual bool OnNotificationControlModeTopic(kortex_driver::OnNotificationControlModeTopic::Request &req, kortex_driver::OnNotificationControlModeTopic::Response &res) = 0; + virtual void cb_ControlModeTopic(Kinova::Api::Base::ControlModeNotification notif) = 0; + virtual bool OnNotificationOperatingModeTopic(kortex_driver::OnNotificationOperatingModeTopic::Request &req, kortex_driver::OnNotificationOperatingModeTopic::Response &res) = 0; + virtual void cb_OperatingModeTopic(Kinova::Api::Base::OperatingModeNotification notif) = 0; + virtual bool OnNotificationSequenceInfoTopic(kortex_driver::OnNotificationSequenceInfoTopic::Request &req, kortex_driver::OnNotificationSequenceInfoTopic::Response &res) = 0; + virtual void cb_SequenceInfoTopic(Kinova::Api::Base::SequenceInfoNotification notif) = 0; + virtual bool OnNotificationProtectionZoneTopic(kortex_driver::OnNotificationProtectionZoneTopic::Request &req, kortex_driver::OnNotificationProtectionZoneTopic::Response &res) = 0; + virtual void cb_ProtectionZoneTopic(Kinova::Api::Base::ProtectionZoneNotification notif) = 0; + virtual bool OnNotificationUserTopic(kortex_driver::OnNotificationUserTopic::Request &req, kortex_driver::OnNotificationUserTopic::Response &res) = 0; + virtual void cb_UserTopic(Kinova::Api::Base::UserNotification notif) = 0; + virtual bool OnNotificationControllerTopic(kortex_driver::OnNotificationControllerTopic::Request &req, kortex_driver::OnNotificationControllerTopic::Response &res) = 0; + virtual void cb_ControllerTopic(Kinova::Api::Base::ControllerNotification notif) = 0; + virtual bool OnNotificationActionTopic(kortex_driver::OnNotificationActionTopic::Request &req, kortex_driver::OnNotificationActionTopic::Response &res) = 0; + virtual void cb_ActionTopic(Kinova::Api::Base::ActionNotification notif) = 0; + virtual bool OnNotificationRobotEventTopic(kortex_driver::OnNotificationRobotEventTopic::Request &req, kortex_driver::OnNotificationRobotEventTopic::Response &res) = 0; + virtual void cb_RobotEventTopic(Kinova::Api::Base::RobotEventNotification notif) = 0; + virtual bool PlayCartesianTrajectory(kortex_driver::PlayCartesianTrajectory::Request &req, kortex_driver::PlayCartesianTrajectory::Response &res) = 0; + virtual bool PlayCartesianTrajectoryPosition(kortex_driver::PlayCartesianTrajectoryPosition::Request &req, kortex_driver::PlayCartesianTrajectoryPosition::Response &res) = 0; + virtual bool PlayCartesianTrajectoryOrientation(kortex_driver::PlayCartesianTrajectoryOrientation::Request &req, kortex_driver::PlayCartesianTrajectoryOrientation::Response &res) = 0; + virtual bool Stop(kortex_driver::Stop::Request &req, kortex_driver::Stop::Response &res) = 0; + virtual bool GetMeasuredCartesianPose(kortex_driver::GetMeasuredCartesianPose::Request &req, kortex_driver::GetMeasuredCartesianPose::Response &res) = 0; + virtual bool SendWrenchCommand(kortex_driver::SendWrenchCommand::Request &req, kortex_driver::SendWrenchCommand::Response &res) = 0; + virtual bool SendWrenchJoystickCommand(kortex_driver::SendWrenchJoystickCommand::Request &req, kortex_driver::SendWrenchJoystickCommand::Response &res) = 0; + virtual bool SendTwistJoystickCommand(kortex_driver::SendTwistJoystickCommand::Request &req, kortex_driver::SendTwistJoystickCommand::Response &res) = 0; + virtual bool SendTwistCommand(kortex_driver::SendTwistCommand::Request &req, kortex_driver::SendTwistCommand::Response &res) = 0; + virtual bool PlayJointTrajectory(kortex_driver::PlayJointTrajectory::Request &req, kortex_driver::PlayJointTrajectory::Response &res) = 0; + virtual bool PlaySelectedJointTrajectory(kortex_driver::PlaySelectedJointTrajectory::Request &req, kortex_driver::PlaySelectedJointTrajectory::Response &res) = 0; + virtual bool GetMeasuredJointAngles(kortex_driver::GetMeasuredJointAngles::Request &req, kortex_driver::GetMeasuredJointAngles::Response &res) = 0; + virtual bool SendJointSpeedsCommand(kortex_driver::SendJointSpeedsCommand::Request &req, kortex_driver::SendJointSpeedsCommand::Response &res) = 0; + virtual bool SendSelectedJointSpeedCommand(kortex_driver::SendSelectedJointSpeedCommand::Request &req, kortex_driver::SendSelectedJointSpeedCommand::Response &res) = 0; + virtual bool SendGripperCommand(kortex_driver::SendGripperCommand::Request &req, kortex_driver::SendGripperCommand::Response &res) = 0; + virtual bool GetMeasuredGripperMovement(kortex_driver::GetMeasuredGripperMovement::Request &req, kortex_driver::GetMeasuredGripperMovement::Response &res) = 0; + virtual bool SetAdmittance(kortex_driver::SetAdmittance::Request &req, kortex_driver::SetAdmittance::Response &res) = 0; + virtual bool SetOperatingMode(kortex_driver::SetOperatingMode::Request &req, kortex_driver::SetOperatingMode::Response &res) = 0; + virtual bool ApplyEmergencyStop(kortex_driver::ApplyEmergencyStop::Request &req, kortex_driver::ApplyEmergencyStop::Response &res) = 0; + virtual bool Base_ClearFaults(kortex_driver::Base_ClearFaults::Request &req, kortex_driver::Base_ClearFaults::Response &res) = 0; + virtual bool Base_GetControlMode(kortex_driver::Base_GetControlMode::Request &req, kortex_driver::Base_GetControlMode::Response &res) = 0; + virtual bool GetOperatingMode(kortex_driver::GetOperatingMode::Request &req, kortex_driver::GetOperatingMode::Response &res) = 0; + virtual bool SetServoingMode(kortex_driver::SetServoingMode::Request &req, kortex_driver::SetServoingMode::Response &res) = 0; + virtual bool GetServoingMode(kortex_driver::GetServoingMode::Request &req, kortex_driver::GetServoingMode::Response &res) = 0; + virtual bool OnNotificationServoingModeTopic(kortex_driver::OnNotificationServoingModeTopic::Request &req, kortex_driver::OnNotificationServoingModeTopic::Response &res) = 0; + virtual void cb_ServoingModeTopic(Kinova::Api::Base::ServoingModeNotification notif) = 0; + virtual bool RestoreFactorySettings(kortex_driver::RestoreFactorySettings::Request &req, kortex_driver::RestoreFactorySettings::Response &res) = 0; + virtual bool OnNotificationFactoryTopic(kortex_driver::OnNotificationFactoryTopic::Request &req, kortex_driver::OnNotificationFactoryTopic::Response &res) = 0; + virtual void cb_FactoryTopic(Kinova::Api::Base::FactoryNotification notif) = 0; + virtual bool GetAllConnectedControllers(kortex_driver::GetAllConnectedControllers::Request &req, kortex_driver::GetAllConnectedControllers::Response &res) = 0; + virtual bool GetControllerState(kortex_driver::GetControllerState::Request &req, kortex_driver::GetControllerState::Response &res) = 0; + virtual bool GetActuatorCount(kortex_driver::GetActuatorCount::Request &req, kortex_driver::GetActuatorCount::Response &res) = 0; + virtual bool StartWifiScan(kortex_driver::StartWifiScan::Request &req, kortex_driver::StartWifiScan::Response &res) = 0; + virtual bool GetConfiguredWifi(kortex_driver::GetConfiguredWifi::Request &req, kortex_driver::GetConfiguredWifi::Response &res) = 0; + virtual bool OnNotificationNetworkTopic(kortex_driver::OnNotificationNetworkTopic::Request &req, kortex_driver::OnNotificationNetworkTopic::Response &res) = 0; + virtual void cb_NetworkTopic(Kinova::Api::Base::NetworkNotification notif) = 0; + virtual bool GetArmState(kortex_driver::GetArmState::Request &req, kortex_driver::GetArmState::Response &res) = 0; + virtual bool OnNotificationArmStateTopic(kortex_driver::OnNotificationArmStateTopic::Request &req, kortex_driver::OnNotificationArmStateTopic::Response &res) = 0; + virtual void cb_ArmStateTopic(Kinova::Api::Base::ArmStateNotification notif) = 0; + virtual bool GetIPv4Information(kortex_driver::GetIPv4Information::Request &req, kortex_driver::GetIPv4Information::Response &res) = 0; + virtual bool SetWifiCountryCode(kortex_driver::SetWifiCountryCode::Request &req, kortex_driver::SetWifiCountryCode::Response &res) = 0; + virtual bool GetWifiCountryCode(kortex_driver::GetWifiCountryCode::Request &req, kortex_driver::GetWifiCountryCode::Response &res) = 0; + virtual bool Base_SetCapSenseConfig(kortex_driver::Base_SetCapSenseConfig::Request &req, kortex_driver::Base_SetCapSenseConfig::Response &res) = 0; + virtual bool Base_GetCapSenseConfig(kortex_driver::Base_GetCapSenseConfig::Request &req, kortex_driver::Base_GetCapSenseConfig::Response &res) = 0; + virtual bool GetAllJointsSpeedHardLimitation(kortex_driver::GetAllJointsSpeedHardLimitation::Request &req, kortex_driver::GetAllJointsSpeedHardLimitation::Response &res) = 0; + virtual bool GetAllJointsTorqueHardLimitation(kortex_driver::GetAllJointsTorqueHardLimitation::Request &req, kortex_driver::GetAllJointsTorqueHardLimitation::Response &res) = 0; + virtual bool GetTwistHardLimitation(kortex_driver::GetTwistHardLimitation::Request &req, kortex_driver::GetTwistHardLimitation::Response &res) = 0; + virtual bool GetWrenchHardLimitation(kortex_driver::GetWrenchHardLimitation::Request &req, kortex_driver::GetWrenchHardLimitation::Response &res) = 0; + virtual bool SendJointSpeedsJoystickCommand(kortex_driver::SendJointSpeedsJoystickCommand::Request &req, kortex_driver::SendJointSpeedsJoystickCommand::Response &res) = 0; + virtual bool SendSelectedJointSpeedJoystickCommand(kortex_driver::SendSelectedJointSpeedJoystickCommand::Request &req, kortex_driver::SendSelectedJointSpeedJoystickCommand::Response &res) = 0; + virtual bool EnableBridge(kortex_driver::EnableBridge::Request &req, kortex_driver::EnableBridge::Response &res) = 0; + virtual bool DisableBridge(kortex_driver::DisableBridge::Request &req, kortex_driver::DisableBridge::Response &res) = 0; + virtual bool GetBridgeList(kortex_driver::GetBridgeList::Request &req, kortex_driver::GetBridgeList::Response &res) = 0; + virtual bool GetBridgeConfig(kortex_driver::GetBridgeConfig::Request &req, kortex_driver::GetBridgeConfig::Response &res) = 0; + virtual bool PlayPreComputedJointTrajectory(kortex_driver::PlayPreComputedJointTrajectory::Request &req, kortex_driver::PlayPreComputedJointTrajectory::Response &res) = 0; + virtual bool GetProductConfiguration(kortex_driver::GetProductConfiguration::Request &req, kortex_driver::GetProductConfiguration::Response &res) = 0; + virtual bool UpdateEndEffectorTypeConfiguration(kortex_driver::UpdateEndEffectorTypeConfiguration::Request &req, kortex_driver::UpdateEndEffectorTypeConfiguration::Response &res) = 0; + virtual bool RestoreFactoryProductConfiguration(kortex_driver::RestoreFactoryProductConfiguration::Request &req, kortex_driver::RestoreFactoryProductConfiguration::Response &res) = 0; + virtual bool GetTrajectoryErrorReport(kortex_driver::GetTrajectoryErrorReport::Request &req, kortex_driver::GetTrajectoryErrorReport::Response &res) = 0; + virtual bool GetAllJointsSpeedSoftLimitation(kortex_driver::GetAllJointsSpeedSoftLimitation::Request &req, kortex_driver::GetAllJointsSpeedSoftLimitation::Response &res) = 0; + virtual bool GetAllJointsTorqueSoftLimitation(kortex_driver::GetAllJointsTorqueSoftLimitation::Request &req, kortex_driver::GetAllJointsTorqueSoftLimitation::Response &res) = 0; + virtual bool GetTwistSoftLimitation(kortex_driver::GetTwistSoftLimitation::Request &req, kortex_driver::GetTwistSoftLimitation::Response &res) = 0; + virtual bool GetWrenchSoftLimitation(kortex_driver::GetWrenchSoftLimitation::Request &req, kortex_driver::GetWrenchSoftLimitation::Response &res) = 0; + virtual bool SetControllerConfigurationMode(kortex_driver::SetControllerConfigurationMode::Request &req, kortex_driver::SetControllerConfigurationMode::Response &res) = 0; + virtual bool GetControllerConfigurationMode(kortex_driver::GetControllerConfigurationMode::Request &req, kortex_driver::GetControllerConfigurationMode::Response &res) = 0; + virtual bool StartTeaching(kortex_driver::StartTeaching::Request &req, kortex_driver::StartTeaching::Response &res) = 0; + virtual bool StopTeaching(kortex_driver::StopTeaching::Request &req, kortex_driver::StopTeaching::Response &res) = 0; + virtual bool AddSequenceTasks(kortex_driver::AddSequenceTasks::Request &req, kortex_driver::AddSequenceTasks::Response &res) = 0; + virtual bool UpdateSequenceTask(kortex_driver::UpdateSequenceTask::Request &req, kortex_driver::UpdateSequenceTask::Response &res) = 0; + virtual bool SwapSequenceTasks(kortex_driver::SwapSequenceTasks::Request &req, kortex_driver::SwapSequenceTasks::Response &res) = 0; + virtual bool ReadSequenceTask(kortex_driver::ReadSequenceTask::Request &req, kortex_driver::ReadSequenceTask::Response &res) = 0; + virtual bool ReadAllSequenceTasks(kortex_driver::ReadAllSequenceTasks::Request &req, kortex_driver::ReadAllSequenceTasks::Response &res) = 0; + virtual bool DeleteSequenceTask(kortex_driver::DeleteSequenceTask::Request &req, kortex_driver::DeleteSequenceTask::Response &res) = 0; + virtual bool DeleteAllSequenceTasks(kortex_driver::DeleteAllSequenceTasks::Request &req, kortex_driver::DeleteAllSequenceTasks::Response &res) = 0; + virtual bool TakeSnapshot(kortex_driver::TakeSnapshot::Request &req, kortex_driver::TakeSnapshot::Response &res) = 0; + virtual bool GetFirmwareBundleVersions(kortex_driver::GetFirmwareBundleVersions::Request &req, kortex_driver::GetFirmwareBundleVersions::Response &res) = 0; + virtual bool MoveSequenceTask(kortex_driver::MoveSequenceTask::Request &req, kortex_driver::MoveSequenceTask::Response &res) = 0; + virtual bool DuplicateMapping(kortex_driver::DuplicateMapping::Request &req, kortex_driver::DuplicateMapping::Response &res) = 0; + virtual bool DuplicateMap(kortex_driver::DuplicateMap::Request &req, kortex_driver::DuplicateMap::Response &res) = 0; + virtual bool SetControllerConfiguration(kortex_driver::SetControllerConfiguration::Request &req, kortex_driver::SetControllerConfiguration::Response &res) = 0; + virtual bool GetControllerConfiguration(kortex_driver::GetControllerConfiguration::Request &req, kortex_driver::GetControllerConfiguration::Response &res) = 0; + virtual bool GetAllControllerConfigurations(kortex_driver::GetAllControllerConfigurations::Request &req, kortex_driver::GetAllControllerConfigurations::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + ros::Publisher m_pub_ConfigurationChangeTopic; + bool m_is_activated_ConfigurationChangeTopic; + ros::Publisher m_pub_MappingInfoTopic; + bool m_is_activated_MappingInfoTopic; + ros::Publisher m_pub_ControlModeTopic; + bool m_is_activated_ControlModeTopic; + ros::Publisher m_pub_OperatingModeTopic; + bool m_is_activated_OperatingModeTopic; + ros::Publisher m_pub_SequenceInfoTopic; + bool m_is_activated_SequenceInfoTopic; + ros::Publisher m_pub_ProtectionZoneTopic; + bool m_is_activated_ProtectionZoneTopic; + ros::Publisher m_pub_UserTopic; + bool m_is_activated_UserTopic; + ros::Publisher m_pub_ControllerTopic; + bool m_is_activated_ControllerTopic; + ros::Publisher m_pub_ActionTopic; + bool m_is_activated_ActionTopic; + ros::Publisher m_pub_RobotEventTopic; + bool m_is_activated_RobotEventTopic; + ros::Publisher m_pub_ServoingModeTopic; + bool m_is_activated_ServoingModeTopic; + ros::Publisher m_pub_FactoryTopic; + bool m_is_activated_FactoryTopic; + ros::Publisher m_pub_NetworkTopic; + bool m_is_activated_NetworkTopic; + ros::Publisher m_pub_ArmStateTopic; + bool m_is_activated_ArmStateTopic; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceCreateUserProfile; + ros::ServiceServer m_serviceUpdateUserProfile; + ros::ServiceServer m_serviceReadUserProfile; + ros::ServiceServer m_serviceDeleteUserProfile; + ros::ServiceServer m_serviceReadAllUserProfiles; + ros::ServiceServer m_serviceReadAllUsers; + ros::ServiceServer m_serviceChangePassword; + ros::ServiceServer m_serviceCreateSequence; + ros::ServiceServer m_serviceUpdateSequence; + ros::ServiceServer m_serviceReadSequence; + ros::ServiceServer m_serviceDeleteSequence; + ros::ServiceServer m_serviceReadAllSequences; + ros::ServiceServer m_servicePlaySequence; + ros::ServiceServer m_servicePlayAdvancedSequence; + ros::ServiceServer m_serviceStopSequence; + ros::ServiceServer m_servicePauseSequence; + ros::ServiceServer m_serviceResumeSequence; + ros::ServiceServer m_serviceCreateProtectionZone; + ros::ServiceServer m_serviceUpdateProtectionZone; + ros::ServiceServer m_serviceReadProtectionZone; + ros::ServiceServer m_serviceDeleteProtectionZone; + ros::ServiceServer m_serviceReadAllProtectionZones; + ros::ServiceServer m_serviceCreateMapping; + ros::ServiceServer m_serviceReadMapping; + ros::ServiceServer m_serviceUpdateMapping; + ros::ServiceServer m_serviceDeleteMapping; + ros::ServiceServer m_serviceReadAllMappings; + ros::ServiceServer m_serviceCreateMap; + ros::ServiceServer m_serviceReadMap; + ros::ServiceServer m_serviceUpdateMap; + ros::ServiceServer m_serviceDeleteMap; + ros::ServiceServer m_serviceReadAllMaps; + ros::ServiceServer m_serviceActivateMap; + ros::ServiceServer m_serviceCreateAction; + ros::ServiceServer m_serviceReadAction; + ros::ServiceServer m_serviceReadAllActions; + ros::ServiceServer m_serviceDeleteAction; + ros::ServiceServer m_serviceUpdateAction; + ros::ServiceServer m_serviceExecuteActionFromReference; + ros::ServiceServer m_serviceExecuteAction; + ros::ServiceServer m_servicePauseAction; + ros::ServiceServer m_serviceStopAction; + ros::ServiceServer m_serviceResumeAction; + ros::ServiceServer m_serviceGetIPv4Configuration; + ros::ServiceServer m_serviceSetIPv4Configuration; + ros::ServiceServer m_serviceSetCommunicationInterfaceEnable; + ros::ServiceServer m_serviceIsCommunicationInterfaceEnable; + ros::ServiceServer m_serviceGetAvailableWifi; + ros::ServiceServer m_serviceGetWifiInformation; + ros::ServiceServer m_serviceAddWifiConfiguration; + ros::ServiceServer m_serviceDeleteWifiConfiguration; + ros::ServiceServer m_serviceGetAllConfiguredWifis; + ros::ServiceServer m_serviceConnectWifi; + ros::ServiceServer m_serviceDisconnectWifi; + ros::ServiceServer m_serviceGetConnectedWifiInformation; + ros::ServiceServer m_serviceBase_Unsubscribe; + ros::ServiceServer m_serviceOnNotificationConfigurationChangeTopic; + ros::ServiceServer m_serviceOnNotificationMappingInfoTopic; + ros::ServiceServer m_serviceOnNotificationControlModeTopic; + ros::ServiceServer m_serviceOnNotificationOperatingModeTopic; + ros::ServiceServer m_serviceOnNotificationSequenceInfoTopic; + ros::ServiceServer m_serviceOnNotificationProtectionZoneTopic; + ros::ServiceServer m_serviceOnNotificationUserTopic; + ros::ServiceServer m_serviceOnNotificationControllerTopic; + ros::ServiceServer m_serviceOnNotificationActionTopic; + ros::ServiceServer m_serviceOnNotificationRobotEventTopic; + ros::ServiceServer m_servicePlayCartesianTrajectory; + ros::ServiceServer m_servicePlayCartesianTrajectoryPosition; + ros::ServiceServer m_servicePlayCartesianTrajectoryOrientation; + ros::ServiceServer m_serviceStop; + ros::ServiceServer m_serviceGetMeasuredCartesianPose; + ros::ServiceServer m_serviceSendWrenchCommand; + ros::ServiceServer m_serviceSendWrenchJoystickCommand; + ros::ServiceServer m_serviceSendTwistJoystickCommand; + ros::ServiceServer m_serviceSendTwistCommand; + ros::ServiceServer m_servicePlayJointTrajectory; + ros::ServiceServer m_servicePlaySelectedJointTrajectory; + ros::ServiceServer m_serviceGetMeasuredJointAngles; + ros::ServiceServer m_serviceSendJointSpeedsCommand; + ros::ServiceServer m_serviceSendSelectedJointSpeedCommand; + ros::ServiceServer m_serviceSendGripperCommand; + ros::ServiceServer m_serviceGetMeasuredGripperMovement; + ros::ServiceServer m_serviceSetAdmittance; + ros::ServiceServer m_serviceSetOperatingMode; + ros::ServiceServer m_serviceApplyEmergencyStop; + ros::ServiceServer m_serviceBase_ClearFaults; + ros::ServiceServer m_serviceBase_GetControlMode; + ros::ServiceServer m_serviceGetOperatingMode; + ros::ServiceServer m_serviceSetServoingMode; + ros::ServiceServer m_serviceGetServoingMode; + ros::ServiceServer m_serviceOnNotificationServoingModeTopic; + ros::ServiceServer m_serviceRestoreFactorySettings; + ros::ServiceServer m_serviceOnNotificationFactoryTopic; + ros::ServiceServer m_serviceGetAllConnectedControllers; + ros::ServiceServer m_serviceGetControllerState; + ros::ServiceServer m_serviceGetActuatorCount; + ros::ServiceServer m_serviceStartWifiScan; + ros::ServiceServer m_serviceGetConfiguredWifi; + ros::ServiceServer m_serviceOnNotificationNetworkTopic; + ros::ServiceServer m_serviceGetArmState; + ros::ServiceServer m_serviceOnNotificationArmStateTopic; + ros::ServiceServer m_serviceGetIPv4Information; + ros::ServiceServer m_serviceSetWifiCountryCode; + ros::ServiceServer m_serviceGetWifiCountryCode; + ros::ServiceServer m_serviceBase_SetCapSenseConfig; + ros::ServiceServer m_serviceBase_GetCapSenseConfig; + ros::ServiceServer m_serviceGetAllJointsSpeedHardLimitation; + ros::ServiceServer m_serviceGetAllJointsTorqueHardLimitation; + ros::ServiceServer m_serviceGetTwistHardLimitation; + ros::ServiceServer m_serviceGetWrenchHardLimitation; + ros::ServiceServer m_serviceSendJointSpeedsJoystickCommand; + ros::ServiceServer m_serviceSendSelectedJointSpeedJoystickCommand; + ros::ServiceServer m_serviceEnableBridge; + ros::ServiceServer m_serviceDisableBridge; + ros::ServiceServer m_serviceGetBridgeList; + ros::ServiceServer m_serviceGetBridgeConfig; + ros::ServiceServer m_servicePlayPreComputedJointTrajectory; + ros::ServiceServer m_serviceGetProductConfiguration; + ros::ServiceServer m_serviceUpdateEndEffectorTypeConfiguration; + ros::ServiceServer m_serviceRestoreFactoryProductConfiguration; + ros::ServiceServer m_serviceGetTrajectoryErrorReport; + ros::ServiceServer m_serviceGetAllJointsSpeedSoftLimitation; + ros::ServiceServer m_serviceGetAllJointsTorqueSoftLimitation; + ros::ServiceServer m_serviceGetTwistSoftLimitation; + ros::ServiceServer m_serviceGetWrenchSoftLimitation; + ros::ServiceServer m_serviceSetControllerConfigurationMode; + ros::ServiceServer m_serviceGetControllerConfigurationMode; + ros::ServiceServer m_serviceStartTeaching; + ros::ServiceServer m_serviceStopTeaching; + ros::ServiceServer m_serviceAddSequenceTasks; + ros::ServiceServer m_serviceUpdateSequenceTask; + ros::ServiceServer m_serviceSwapSequenceTasks; + ros::ServiceServer m_serviceReadSequenceTask; + ros::ServiceServer m_serviceReadAllSequenceTasks; + ros::ServiceServer m_serviceDeleteSequenceTask; + ros::ServiceServer m_serviceDeleteAllSequenceTasks; + ros::ServiceServer m_serviceTakeSnapshot; + ros::ServiceServer m_serviceGetFirmwareBundleVersions; + ros::ServiceServer m_serviceMoveSequenceTask; + ros::ServiceServer m_serviceDuplicateMapping; + ros::ServiceServer m_serviceDuplicateMap; + ros::ServiceServer m_serviceSetControllerConfiguration; + ros::ServiceServer m_serviceGetControllerConfiguration; + ros::ServiceServer m_serviceGetAllControllerConfigurations; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/controlconfig_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/controlconfig_services_interface.h new file mode 100644 index 0000000..6475c3d --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/controlconfig_services_interface.h @@ -0,0 +1,142 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_CONTROLCONFIG_SERVICES_INTERFACE_H_ +#define _KORTEX_CONTROLCONFIG_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/SetGravityVector.h" +#include "kortex_driver/GetGravityVector.h" +#include "kortex_driver/SetPayloadInformation.h" +#include "kortex_driver/GetPayloadInformation.h" +#include "kortex_driver/SetToolConfiguration.h" +#include "kortex_driver/GetToolConfiguration.h" +#include "kortex_driver/OnNotificationControlConfigurationTopic.h" +#include "kortex_driver/ControlConfigurationNotification.h" +#include "kortex_driver/ControlConfig_Unsubscribe.h" +#include "kortex_driver/SetCartesianReferenceFrame.h" +#include "kortex_driver/GetCartesianReferenceFrame.h" +#include "kortex_driver/ControlConfig_GetControlMode.h" +#include "kortex_driver/SetJointSpeedSoftLimits.h" +#include "kortex_driver/SetTwistLinearSoftLimit.h" +#include "kortex_driver/SetTwistAngularSoftLimit.h" +#include "kortex_driver/SetJointAccelerationSoftLimits.h" +#include "kortex_driver/GetKinematicHardLimits.h" +#include "kortex_driver/GetKinematicSoftLimits.h" +#include "kortex_driver/GetAllKinematicSoftLimits.h" +#include "kortex_driver/SetDesiredLinearTwist.h" +#include "kortex_driver/SetDesiredAngularTwist.h" +#include "kortex_driver/SetDesiredJointSpeeds.h" +#include "kortex_driver/GetDesiredSpeeds.h" +#include "kortex_driver/ResetGravityVector.h" +#include "kortex_driver/ResetPayloadInformation.h" +#include "kortex_driver/ResetToolConfiguration.h" +#include "kortex_driver/ResetJointSpeedSoftLimits.h" +#include "kortex_driver/ResetTwistLinearSoftLimit.h" +#include "kortex_driver/ResetTwistAngularSoftLimit.h" +#include "kortex_driver/ResetJointAccelerationSoftLimits.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IControlConfigServices +{ + public: + IControlConfigServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool SetGravityVector(kortex_driver::SetGravityVector::Request &req, kortex_driver::SetGravityVector::Response &res) = 0; + virtual bool GetGravityVector(kortex_driver::GetGravityVector::Request &req, kortex_driver::GetGravityVector::Response &res) = 0; + virtual bool SetPayloadInformation(kortex_driver::SetPayloadInformation::Request &req, kortex_driver::SetPayloadInformation::Response &res) = 0; + virtual bool GetPayloadInformation(kortex_driver::GetPayloadInformation::Request &req, kortex_driver::GetPayloadInformation::Response &res) = 0; + virtual bool SetToolConfiguration(kortex_driver::SetToolConfiguration::Request &req, kortex_driver::SetToolConfiguration::Response &res) = 0; + virtual bool GetToolConfiguration(kortex_driver::GetToolConfiguration::Request &req, kortex_driver::GetToolConfiguration::Response &res) = 0; + virtual bool OnNotificationControlConfigurationTopic(kortex_driver::OnNotificationControlConfigurationTopic::Request &req, kortex_driver::OnNotificationControlConfigurationTopic::Response &res) = 0; + virtual void cb_ControlConfigurationTopic(Kinova::Api::ControlConfig::ControlConfigurationNotification notif) = 0; + virtual bool ControlConfig_Unsubscribe(kortex_driver::ControlConfig_Unsubscribe::Request &req, kortex_driver::ControlConfig_Unsubscribe::Response &res) = 0; + virtual bool SetCartesianReferenceFrame(kortex_driver::SetCartesianReferenceFrame::Request &req, kortex_driver::SetCartesianReferenceFrame::Response &res) = 0; + virtual bool GetCartesianReferenceFrame(kortex_driver::GetCartesianReferenceFrame::Request &req, kortex_driver::GetCartesianReferenceFrame::Response &res) = 0; + virtual bool ControlConfig_GetControlMode(kortex_driver::ControlConfig_GetControlMode::Request &req, kortex_driver::ControlConfig_GetControlMode::Response &res) = 0; + virtual bool SetJointSpeedSoftLimits(kortex_driver::SetJointSpeedSoftLimits::Request &req, kortex_driver::SetJointSpeedSoftLimits::Response &res) = 0; + virtual bool SetTwistLinearSoftLimit(kortex_driver::SetTwistLinearSoftLimit::Request &req, kortex_driver::SetTwistLinearSoftLimit::Response &res) = 0; + virtual bool SetTwistAngularSoftLimit(kortex_driver::SetTwistAngularSoftLimit::Request &req, kortex_driver::SetTwistAngularSoftLimit::Response &res) = 0; + virtual bool SetJointAccelerationSoftLimits(kortex_driver::SetJointAccelerationSoftLimits::Request &req, kortex_driver::SetJointAccelerationSoftLimits::Response &res) = 0; + virtual bool GetKinematicHardLimits(kortex_driver::GetKinematicHardLimits::Request &req, kortex_driver::GetKinematicHardLimits::Response &res) = 0; + virtual bool GetKinematicSoftLimits(kortex_driver::GetKinematicSoftLimits::Request &req, kortex_driver::GetKinematicSoftLimits::Response &res) = 0; + virtual bool GetAllKinematicSoftLimits(kortex_driver::GetAllKinematicSoftLimits::Request &req, kortex_driver::GetAllKinematicSoftLimits::Response &res) = 0; + virtual bool SetDesiredLinearTwist(kortex_driver::SetDesiredLinearTwist::Request &req, kortex_driver::SetDesiredLinearTwist::Response &res) = 0; + virtual bool SetDesiredAngularTwist(kortex_driver::SetDesiredAngularTwist::Request &req, kortex_driver::SetDesiredAngularTwist::Response &res) = 0; + virtual bool SetDesiredJointSpeeds(kortex_driver::SetDesiredJointSpeeds::Request &req, kortex_driver::SetDesiredJointSpeeds::Response &res) = 0; + virtual bool GetDesiredSpeeds(kortex_driver::GetDesiredSpeeds::Request &req, kortex_driver::GetDesiredSpeeds::Response &res) = 0; + virtual bool ResetGravityVector(kortex_driver::ResetGravityVector::Request &req, kortex_driver::ResetGravityVector::Response &res) = 0; + virtual bool ResetPayloadInformation(kortex_driver::ResetPayloadInformation::Request &req, kortex_driver::ResetPayloadInformation::Response &res) = 0; + virtual bool ResetToolConfiguration(kortex_driver::ResetToolConfiguration::Request &req, kortex_driver::ResetToolConfiguration::Response &res) = 0; + virtual bool ResetJointSpeedSoftLimits(kortex_driver::ResetJointSpeedSoftLimits::Request &req, kortex_driver::ResetJointSpeedSoftLimits::Response &res) = 0; + virtual bool ResetTwistLinearSoftLimit(kortex_driver::ResetTwistLinearSoftLimit::Request &req, kortex_driver::ResetTwistLinearSoftLimit::Response &res) = 0; + virtual bool ResetTwistAngularSoftLimit(kortex_driver::ResetTwistAngularSoftLimit::Request &req, kortex_driver::ResetTwistAngularSoftLimit::Response &res) = 0; + virtual bool ResetJointAccelerationSoftLimits(kortex_driver::ResetJointAccelerationSoftLimits::Request &req, kortex_driver::ResetJointAccelerationSoftLimits::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + ros::Publisher m_pub_ControlConfigurationTopic; + bool m_is_activated_ControlConfigurationTopic; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceSetGravityVector; + ros::ServiceServer m_serviceGetGravityVector; + ros::ServiceServer m_serviceSetPayloadInformation; + ros::ServiceServer m_serviceGetPayloadInformation; + ros::ServiceServer m_serviceSetToolConfiguration; + ros::ServiceServer m_serviceGetToolConfiguration; + ros::ServiceServer m_serviceOnNotificationControlConfigurationTopic; + ros::ServiceServer m_serviceControlConfig_Unsubscribe; + ros::ServiceServer m_serviceSetCartesianReferenceFrame; + ros::ServiceServer m_serviceGetCartesianReferenceFrame; + ros::ServiceServer m_serviceControlConfig_GetControlMode; + ros::ServiceServer m_serviceSetJointSpeedSoftLimits; + ros::ServiceServer m_serviceSetTwistLinearSoftLimit; + ros::ServiceServer m_serviceSetTwistAngularSoftLimit; + ros::ServiceServer m_serviceSetJointAccelerationSoftLimits; + ros::ServiceServer m_serviceGetKinematicHardLimits; + ros::ServiceServer m_serviceGetKinematicSoftLimits; + ros::ServiceServer m_serviceGetAllKinematicSoftLimits; + ros::ServiceServer m_serviceSetDesiredLinearTwist; + ros::ServiceServer m_serviceSetDesiredAngularTwist; + ros::ServiceServer m_serviceSetDesiredJointSpeeds; + ros::ServiceServer m_serviceGetDesiredSpeeds; + ros::ServiceServer m_serviceResetGravityVector; + ros::ServiceServer m_serviceResetPayloadInformation; + ros::ServiceServer m_serviceResetToolConfiguration; + ros::ServiceServer m_serviceResetJointSpeedSoftLimits; + ros::ServiceServer m_serviceResetTwistLinearSoftLimit; + ros::ServiceServer m_serviceResetTwistAngularSoftLimit; + ros::ServiceServer m_serviceResetJointAccelerationSoftLimits; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/deviceconfig_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/deviceconfig_services_interface.h new file mode 100644 index 0000000..4f4b7d1 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/deviceconfig_services_interface.h @@ -0,0 +1,151 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICECONFIG_SERVICES_INTERFACE_H_ +#define _KORTEX_DEVICECONFIG_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/GetRunMode.h" +#include "kortex_driver/SetRunMode.h" +#include "kortex_driver/GetDeviceType.h" +#include "kortex_driver/GetFirmwareVersion.h" +#include "kortex_driver/GetBootloaderVersion.h" +#include "kortex_driver/GetModelNumber.h" +#include "kortex_driver/GetPartNumber.h" +#include "kortex_driver/GetSerialNumber.h" +#include "kortex_driver/GetMACAddress.h" +#include "kortex_driver/GetIPv4Settings.h" +#include "kortex_driver/SetIPv4Settings.h" +#include "kortex_driver/GetPartNumberRevision.h" +#include "kortex_driver/RebootRequest.h" +#include "kortex_driver/SetSafetyEnable.h" +#include "kortex_driver/SetSafetyErrorThreshold.h" +#include "kortex_driver/SetSafetyWarningThreshold.h" +#include "kortex_driver/SetSafetyConfiguration.h" +#include "kortex_driver/GetSafetyConfiguration.h" +#include "kortex_driver/GetSafetyInformation.h" +#include "kortex_driver/GetSafetyEnable.h" +#include "kortex_driver/GetSafetyStatus.h" +#include "kortex_driver/ClearAllSafetyStatus.h" +#include "kortex_driver/ClearSafetyStatus.h" +#include "kortex_driver/GetAllSafetyConfiguration.h" +#include "kortex_driver/GetAllSafetyInformation.h" +#include "kortex_driver/ResetSafetyDefaults.h" +#include "kortex_driver/OnNotificationSafetyTopic.h" +#include "kortex_driver/SafetyNotification.h" +#include "kortex_driver/ExecuteCalibration.h" +#include "kortex_driver/GetCalibrationResult.h" +#include "kortex_driver/StopCalibration.h" +#include "kortex_driver/DeviceConfig_SetCapSenseConfig.h" +#include "kortex_driver/DeviceConfig_GetCapSenseConfig.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IDeviceConfigServices +{ + public: + IDeviceConfigServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool GetRunMode(kortex_driver::GetRunMode::Request &req, kortex_driver::GetRunMode::Response &res) = 0; + virtual bool SetRunMode(kortex_driver::SetRunMode::Request &req, kortex_driver::SetRunMode::Response &res) = 0; + virtual bool GetDeviceType(kortex_driver::GetDeviceType::Request &req, kortex_driver::GetDeviceType::Response &res) = 0; + virtual bool GetFirmwareVersion(kortex_driver::GetFirmwareVersion::Request &req, kortex_driver::GetFirmwareVersion::Response &res) = 0; + virtual bool GetBootloaderVersion(kortex_driver::GetBootloaderVersion::Request &req, kortex_driver::GetBootloaderVersion::Response &res) = 0; + virtual bool GetModelNumber(kortex_driver::GetModelNumber::Request &req, kortex_driver::GetModelNumber::Response &res) = 0; + virtual bool GetPartNumber(kortex_driver::GetPartNumber::Request &req, kortex_driver::GetPartNumber::Response &res) = 0; + virtual bool GetSerialNumber(kortex_driver::GetSerialNumber::Request &req, kortex_driver::GetSerialNumber::Response &res) = 0; + virtual bool GetMACAddress(kortex_driver::GetMACAddress::Request &req, kortex_driver::GetMACAddress::Response &res) = 0; + virtual bool GetIPv4Settings(kortex_driver::GetIPv4Settings::Request &req, kortex_driver::GetIPv4Settings::Response &res) = 0; + virtual bool SetIPv4Settings(kortex_driver::SetIPv4Settings::Request &req, kortex_driver::SetIPv4Settings::Response &res) = 0; + virtual bool GetPartNumberRevision(kortex_driver::GetPartNumberRevision::Request &req, kortex_driver::GetPartNumberRevision::Response &res) = 0; + virtual bool RebootRequest(kortex_driver::RebootRequest::Request &req, kortex_driver::RebootRequest::Response &res) = 0; + virtual bool SetSafetyEnable(kortex_driver::SetSafetyEnable::Request &req, kortex_driver::SetSafetyEnable::Response &res) = 0; + virtual bool SetSafetyErrorThreshold(kortex_driver::SetSafetyErrorThreshold::Request &req, kortex_driver::SetSafetyErrorThreshold::Response &res) = 0; + virtual bool SetSafetyWarningThreshold(kortex_driver::SetSafetyWarningThreshold::Request &req, kortex_driver::SetSafetyWarningThreshold::Response &res) = 0; + virtual bool SetSafetyConfiguration(kortex_driver::SetSafetyConfiguration::Request &req, kortex_driver::SetSafetyConfiguration::Response &res) = 0; + virtual bool GetSafetyConfiguration(kortex_driver::GetSafetyConfiguration::Request &req, kortex_driver::GetSafetyConfiguration::Response &res) = 0; + virtual bool GetSafetyInformation(kortex_driver::GetSafetyInformation::Request &req, kortex_driver::GetSafetyInformation::Response &res) = 0; + virtual bool GetSafetyEnable(kortex_driver::GetSafetyEnable::Request &req, kortex_driver::GetSafetyEnable::Response &res) = 0; + virtual bool GetSafetyStatus(kortex_driver::GetSafetyStatus::Request &req, kortex_driver::GetSafetyStatus::Response &res) = 0; + virtual bool ClearAllSafetyStatus(kortex_driver::ClearAllSafetyStatus::Request &req, kortex_driver::ClearAllSafetyStatus::Response &res) = 0; + virtual bool ClearSafetyStatus(kortex_driver::ClearSafetyStatus::Request &req, kortex_driver::ClearSafetyStatus::Response &res) = 0; + virtual bool GetAllSafetyConfiguration(kortex_driver::GetAllSafetyConfiguration::Request &req, kortex_driver::GetAllSafetyConfiguration::Response &res) = 0; + virtual bool GetAllSafetyInformation(kortex_driver::GetAllSafetyInformation::Request &req, kortex_driver::GetAllSafetyInformation::Response &res) = 0; + virtual bool ResetSafetyDefaults(kortex_driver::ResetSafetyDefaults::Request &req, kortex_driver::ResetSafetyDefaults::Response &res) = 0; + virtual bool OnNotificationSafetyTopic(kortex_driver::OnNotificationSafetyTopic::Request &req, kortex_driver::OnNotificationSafetyTopic::Response &res) = 0; + virtual void cb_SafetyTopic(Kinova::Api::Common::SafetyNotification notif) = 0; + virtual bool ExecuteCalibration(kortex_driver::ExecuteCalibration::Request &req, kortex_driver::ExecuteCalibration::Response &res) = 0; + virtual bool GetCalibrationResult(kortex_driver::GetCalibrationResult::Request &req, kortex_driver::GetCalibrationResult::Response &res) = 0; + virtual bool StopCalibration(kortex_driver::StopCalibration::Request &req, kortex_driver::StopCalibration::Response &res) = 0; + virtual bool DeviceConfig_SetCapSenseConfig(kortex_driver::DeviceConfig_SetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_SetCapSenseConfig::Response &res) = 0; + virtual bool DeviceConfig_GetCapSenseConfig(kortex_driver::DeviceConfig_GetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_GetCapSenseConfig::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + ros::Publisher m_pub_SafetyTopic; + bool m_is_activated_SafetyTopic; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceGetRunMode; + ros::ServiceServer m_serviceSetRunMode; + ros::ServiceServer m_serviceGetDeviceType; + ros::ServiceServer m_serviceGetFirmwareVersion; + ros::ServiceServer m_serviceGetBootloaderVersion; + ros::ServiceServer m_serviceGetModelNumber; + ros::ServiceServer m_serviceGetPartNumber; + ros::ServiceServer m_serviceGetSerialNumber; + ros::ServiceServer m_serviceGetMACAddress; + ros::ServiceServer m_serviceGetIPv4Settings; + ros::ServiceServer m_serviceSetIPv4Settings; + ros::ServiceServer m_serviceGetPartNumberRevision; + ros::ServiceServer m_serviceRebootRequest; + ros::ServiceServer m_serviceSetSafetyEnable; + ros::ServiceServer m_serviceSetSafetyErrorThreshold; + ros::ServiceServer m_serviceSetSafetyWarningThreshold; + ros::ServiceServer m_serviceSetSafetyConfiguration; + ros::ServiceServer m_serviceGetSafetyConfiguration; + ros::ServiceServer m_serviceGetSafetyInformation; + ros::ServiceServer m_serviceGetSafetyEnable; + ros::ServiceServer m_serviceGetSafetyStatus; + ros::ServiceServer m_serviceClearAllSafetyStatus; + ros::ServiceServer m_serviceClearSafetyStatus; + ros::ServiceServer m_serviceGetAllSafetyConfiguration; + ros::ServiceServer m_serviceGetAllSafetyInformation; + ros::ServiceServer m_serviceResetSafetyDefaults; + ros::ServiceServer m_serviceOnNotificationSafetyTopic; + ros::ServiceServer m_serviceExecuteCalibration; + ros::ServiceServer m_serviceGetCalibrationResult; + ros::ServiceServer m_serviceStopCalibration; + ros::ServiceServer m_serviceDeviceConfig_SetCapSenseConfig; + ros::ServiceServer m_serviceDeviceConfig_GetCapSenseConfig; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/devicemanager_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/devicemanager_services_interface.h new file mode 100644 index 0000000..a2e544e --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/devicemanager_services_interface.h @@ -0,0 +1,54 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICEMANAGER_SERVICES_INTERFACE_H_ +#define _KORTEX_DEVICEMANAGER_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/ReadAllDevices.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IDeviceManagerServices +{ + public: + IDeviceManagerServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool ReadAllDevices(kortex_driver::ReadAllDevices::Request &req, kortex_driver::ReadAllDevices::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceReadAllDevices; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/interconnectconfig_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/interconnectconfig_services_interface.h new file mode 100644 index 0000000..dc370d1 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/interconnectconfig_services_interface.h @@ -0,0 +1,93 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCONFIG_SERVICES_INTERFACE_H_ +#define _KORTEX_INTERCONNECTCONFIG_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/GetUARTConfiguration.h" +#include "kortex_driver/SetUARTConfiguration.h" +#include "kortex_driver/GetEthernetConfiguration.h" +#include "kortex_driver/SetEthernetConfiguration.h" +#include "kortex_driver/GetGPIOConfiguration.h" +#include "kortex_driver/SetGPIOConfiguration.h" +#include "kortex_driver/GetGPIOState.h" +#include "kortex_driver/SetGPIOState.h" +#include "kortex_driver/GetI2CConfiguration.h" +#include "kortex_driver/SetI2CConfiguration.h" +#include "kortex_driver/I2CRead.h" +#include "kortex_driver/I2CReadRegister.h" +#include "kortex_driver/I2CWrite.h" +#include "kortex_driver/I2CWriteRegister.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IInterconnectConfigServices +{ + public: + IInterconnectConfigServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool GetUARTConfiguration(kortex_driver::GetUARTConfiguration::Request &req, kortex_driver::GetUARTConfiguration::Response &res) = 0; + virtual bool SetUARTConfiguration(kortex_driver::SetUARTConfiguration::Request &req, kortex_driver::SetUARTConfiguration::Response &res) = 0; + virtual bool GetEthernetConfiguration(kortex_driver::GetEthernetConfiguration::Request &req, kortex_driver::GetEthernetConfiguration::Response &res) = 0; + virtual bool SetEthernetConfiguration(kortex_driver::SetEthernetConfiguration::Request &req, kortex_driver::SetEthernetConfiguration::Response &res) = 0; + virtual bool GetGPIOConfiguration(kortex_driver::GetGPIOConfiguration::Request &req, kortex_driver::GetGPIOConfiguration::Response &res) = 0; + virtual bool SetGPIOConfiguration(kortex_driver::SetGPIOConfiguration::Request &req, kortex_driver::SetGPIOConfiguration::Response &res) = 0; + virtual bool GetGPIOState(kortex_driver::GetGPIOState::Request &req, kortex_driver::GetGPIOState::Response &res) = 0; + virtual bool SetGPIOState(kortex_driver::SetGPIOState::Request &req, kortex_driver::SetGPIOState::Response &res) = 0; + virtual bool GetI2CConfiguration(kortex_driver::GetI2CConfiguration::Request &req, kortex_driver::GetI2CConfiguration::Response &res) = 0; + virtual bool SetI2CConfiguration(kortex_driver::SetI2CConfiguration::Request &req, kortex_driver::SetI2CConfiguration::Response &res) = 0; + virtual bool I2CRead(kortex_driver::I2CRead::Request &req, kortex_driver::I2CRead::Response &res) = 0; + virtual bool I2CReadRegister(kortex_driver::I2CReadRegister::Request &req, kortex_driver::I2CReadRegister::Response &res) = 0; + virtual bool I2CWrite(kortex_driver::I2CWrite::Request &req, kortex_driver::I2CWrite::Response &res) = 0; + virtual bool I2CWriteRegister(kortex_driver::I2CWriteRegister::Request &req, kortex_driver::I2CWriteRegister::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceGetUARTConfiguration; + ros::ServiceServer m_serviceSetUARTConfiguration; + ros::ServiceServer m_serviceGetEthernetConfiguration; + ros::ServiceServer m_serviceSetEthernetConfiguration; + ros::ServiceServer m_serviceGetGPIOConfiguration; + ros::ServiceServer m_serviceSetGPIOConfiguration; + ros::ServiceServer m_serviceGetGPIOState; + ros::ServiceServer m_serviceSetGPIOState; + ros::ServiceServer m_serviceGetI2CConfiguration; + ros::ServiceServer m_serviceSetI2CConfiguration; + ros::ServiceServer m_serviceI2CRead; + ros::ServiceServer m_serviceI2CReadRegister; + ros::ServiceServer m_serviceI2CWrite; + ros::ServiceServer m_serviceI2CWriteRegister; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/visionconfig_services_interface.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/visionconfig_services_interface.h new file mode 100644 index 0000000..1bf98c7 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/interfaces/visionconfig_services_interface.h @@ -0,0 +1,91 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_VISIONCONFIG_SERVICES_INTERFACE_H_ +#define _KORTEX_VISIONCONFIG_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include +#include "kortex_driver/SetSensorSettings.h" +#include "kortex_driver/GetSensorSettings.h" +#include "kortex_driver/GetOptionValue.h" +#include "kortex_driver/SetOptionValue.h" +#include "kortex_driver/GetOptionInformation.h" +#include "kortex_driver/OnNotificationVisionTopic.h" +#include "kortex_driver/VisionNotification.h" +#include "kortex_driver/DoSensorFocusAction.h" +#include "kortex_driver/GetIntrinsicParameters.h" +#include "kortex_driver/GetIntrinsicParametersProfile.h" +#include "kortex_driver/SetIntrinsicParameters.h" +#include "kortex_driver/GetExtrinsicParameters.h" +#include "kortex_driver/SetExtrinsicParameters.h" + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class IVisionConfigServices +{ + public: + IVisionConfigServices(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; + virtual bool SetSensorSettings(kortex_driver::SetSensorSettings::Request &req, kortex_driver::SetSensorSettings::Response &res) = 0; + virtual bool GetSensorSettings(kortex_driver::GetSensorSettings::Request &req, kortex_driver::GetSensorSettings::Response &res) = 0; + virtual bool GetOptionValue(kortex_driver::GetOptionValue::Request &req, kortex_driver::GetOptionValue::Response &res) = 0; + virtual bool SetOptionValue(kortex_driver::SetOptionValue::Request &req, kortex_driver::SetOptionValue::Response &res) = 0; + virtual bool GetOptionInformation(kortex_driver::GetOptionInformation::Request &req, kortex_driver::GetOptionInformation::Response &res) = 0; + virtual bool OnNotificationVisionTopic(kortex_driver::OnNotificationVisionTopic::Request &req, kortex_driver::OnNotificationVisionTopic::Response &res) = 0; + virtual void cb_VisionTopic(Kinova::Api::VisionConfig::VisionNotification notif) = 0; + virtual bool DoSensorFocusAction(kortex_driver::DoSensorFocusAction::Request &req, kortex_driver::DoSensorFocusAction::Response &res) = 0; + virtual bool GetIntrinsicParameters(kortex_driver::GetIntrinsicParameters::Request &req, kortex_driver::GetIntrinsicParameters::Response &res) = 0; + virtual bool GetIntrinsicParametersProfile(kortex_driver::GetIntrinsicParametersProfile::Request &req, kortex_driver::GetIntrinsicParametersProfile::Response &res) = 0; + virtual bool SetIntrinsicParameters(kortex_driver::SetIntrinsicParameters::Request &req, kortex_driver::SetIntrinsicParameters::Response &res) = 0; + virtual bool GetExtrinsicParameters(kortex_driver::GetExtrinsicParameters::Request &req, kortex_driver::GetExtrinsicParameters::Response &res) = 0; + virtual bool SetExtrinsicParameters(kortex_driver::SetExtrinsicParameters::Request &req, kortex_driver::SetExtrinsicParameters::Response &res) = 0; + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + ros::Publisher m_pub_VisionTopic; + bool m_is_activated_VisionTopic; + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; + + ros::ServiceServer m_serviceSetSensorSettings; + ros::ServiceServer m_serviceGetSensorSettings; + ros::ServiceServer m_serviceGetOptionValue; + ros::ServiceServer m_serviceSetOptionValue; + ros::ServiceServer m_serviceGetOptionInformation; + ros::ServiceServer m_serviceOnNotificationVisionTopic; + ros::ServiceServer m_serviceDoSensorFocusAction; + ros::ServiceServer m_serviceGetIntrinsicParameters; + ros::ServiceServer m_serviceGetIntrinsicParametersProfile; + ros::ServiceServer m_serviceSetIntrinsicParameters; + ros::ServiceServer m_serviceGetExtrinsicParameters; + ros::ServiceServer m_serviceSetExtrinsicParameters; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_proto_converter.h new file mode 100644 index 0000000..e91312b --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_proto_converter.h @@ -0,0 +1,83 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCONFIG_PROTO_CONVERTER_H_ +#define _KORTEX_ACTUATORCONFIG_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/AxisPosition.h" +#include "kortex_driver/AxisOffsets.h" +#include "kortex_driver/TorqueCalibration.h" +#include "kortex_driver/TorqueOffset.h" +#include "kortex_driver/ActuatorConfig_ControlModeInformation.h" +#include "kortex_driver/ControlLoop.h" +#include "kortex_driver/LoopSelection.h" +#include "kortex_driver/VectorDriveParameters.h" +#include "kortex_driver/EncoderDerivativeParameters.h" +#include "kortex_driver/ControlLoopParameters.h" +#include "kortex_driver/FrequencyResponse.h" +#include "kortex_driver/StepResponse.h" +#include "kortex_driver/RampResponse.h" +#include "kortex_driver/CustomDataSelection.h" +#include "kortex_driver/CommandModeInformation.h" +#include "kortex_driver/Servoing.h" +#include "kortex_driver/PositionCommand.h" +#include "kortex_driver/CoggingFeedforwardModeInformation.h" + + +int ToProtoData(kortex_driver::AxisPosition input, Kinova::Api::ActuatorConfig::AxisPosition *output); +int ToProtoData(kortex_driver::AxisOffsets input, Kinova::Api::ActuatorConfig::AxisOffsets *output); +int ToProtoData(kortex_driver::TorqueCalibration input, Kinova::Api::ActuatorConfig::TorqueCalibration *output); +int ToProtoData(kortex_driver::TorqueOffset input, Kinova::Api::ActuatorConfig::TorqueOffset *output); +int ToProtoData(kortex_driver::ActuatorConfig_ControlModeInformation input, Kinova::Api::ActuatorConfig::ControlModeInformation *output); +int ToProtoData(kortex_driver::ControlLoop input, Kinova::Api::ActuatorConfig::ControlLoop *output); +int ToProtoData(kortex_driver::LoopSelection input, Kinova::Api::ActuatorConfig::LoopSelection *output); +int ToProtoData(kortex_driver::VectorDriveParameters input, Kinova::Api::ActuatorConfig::VectorDriveParameters *output); +int ToProtoData(kortex_driver::EncoderDerivativeParameters input, Kinova::Api::ActuatorConfig::EncoderDerivativeParameters *output); +int ToProtoData(kortex_driver::ControlLoopParameters input, Kinova::Api::ActuatorConfig::ControlLoopParameters *output); +int ToProtoData(kortex_driver::FrequencyResponse input, Kinova::Api::ActuatorConfig::FrequencyResponse *output); +int ToProtoData(kortex_driver::StepResponse input, Kinova::Api::ActuatorConfig::StepResponse *output); +int ToProtoData(kortex_driver::RampResponse input, Kinova::Api::ActuatorConfig::RampResponse *output); +int ToProtoData(kortex_driver::CustomDataSelection input, Kinova::Api::ActuatorConfig::CustomDataSelection *output); +int ToProtoData(kortex_driver::CommandModeInformation input, Kinova::Api::ActuatorConfig::CommandModeInformation *output); +int ToProtoData(kortex_driver::Servoing input, Kinova::Api::ActuatorConfig::Servoing *output); +int ToProtoData(kortex_driver::PositionCommand input, Kinova::Api::ActuatorConfig::PositionCommand *output); +int ToProtoData(kortex_driver::CoggingFeedforwardModeInformation input, Kinova::Api::ActuatorConfig::CoggingFeedforwardModeInformation *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_ros_converter.h new file mode 100644 index 0000000..024e75a --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_ros_converter.h @@ -0,0 +1,83 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCONFIG_ROS_CONVERTER_H_ +#define _KORTEX_ACTUATORCONFIG_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/AxisPosition.h" +#include "kortex_driver/AxisOffsets.h" +#include "kortex_driver/TorqueCalibration.h" +#include "kortex_driver/TorqueOffset.h" +#include "kortex_driver/ActuatorConfig_ControlModeInformation.h" +#include "kortex_driver/ControlLoop.h" +#include "kortex_driver/LoopSelection.h" +#include "kortex_driver/VectorDriveParameters.h" +#include "kortex_driver/EncoderDerivativeParameters.h" +#include "kortex_driver/ControlLoopParameters.h" +#include "kortex_driver/FrequencyResponse.h" +#include "kortex_driver/StepResponse.h" +#include "kortex_driver/RampResponse.h" +#include "kortex_driver/CustomDataSelection.h" +#include "kortex_driver/CommandModeInformation.h" +#include "kortex_driver/Servoing.h" +#include "kortex_driver/PositionCommand.h" +#include "kortex_driver/CoggingFeedforwardModeInformation.h" + + +int ToRosData(Kinova::Api::ActuatorConfig::AxisPosition input, kortex_driver::AxisPosition &output); +int ToRosData(Kinova::Api::ActuatorConfig::AxisOffsets input, kortex_driver::AxisOffsets &output); +int ToRosData(Kinova::Api::ActuatorConfig::TorqueCalibration input, kortex_driver::TorqueCalibration &output); +int ToRosData(Kinova::Api::ActuatorConfig::TorqueOffset input, kortex_driver::TorqueOffset &output); +int ToRosData(Kinova::Api::ActuatorConfig::ControlModeInformation input, kortex_driver::ActuatorConfig_ControlModeInformation &output); +int ToRosData(Kinova::Api::ActuatorConfig::ControlLoop input, kortex_driver::ControlLoop &output); +int ToRosData(Kinova::Api::ActuatorConfig::LoopSelection input, kortex_driver::LoopSelection &output); +int ToRosData(Kinova::Api::ActuatorConfig::VectorDriveParameters input, kortex_driver::VectorDriveParameters &output); +int ToRosData(Kinova::Api::ActuatorConfig::EncoderDerivativeParameters input, kortex_driver::EncoderDerivativeParameters &output); +int ToRosData(Kinova::Api::ActuatorConfig::ControlLoopParameters input, kortex_driver::ControlLoopParameters &output); +int ToRosData(Kinova::Api::ActuatorConfig::FrequencyResponse input, kortex_driver::FrequencyResponse &output); +int ToRosData(Kinova::Api::ActuatorConfig::StepResponse input, kortex_driver::StepResponse &output); +int ToRosData(Kinova::Api::ActuatorConfig::RampResponse input, kortex_driver::RampResponse &output); +int ToRosData(Kinova::Api::ActuatorConfig::CustomDataSelection input, kortex_driver::CustomDataSelection &output); +int ToRosData(Kinova::Api::ActuatorConfig::CommandModeInformation input, kortex_driver::CommandModeInformation &output); +int ToRosData(Kinova::Api::ActuatorConfig::Servoing input, kortex_driver::Servoing &output); +int ToRosData(Kinova::Api::ActuatorConfig::PositionCommand input, kortex_driver::PositionCommand &output); +int ToRosData(Kinova::Api::ActuatorConfig::CoggingFeedforwardModeInformation input, kortex_driver::CoggingFeedforwardModeInformation &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_services.h new file mode 100644 index 0000000..0a7adac --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorconfig_services.h @@ -0,0 +1,61 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCONFIG_ROBOT_SERVICES_H_ +#define _KORTEX_ACTUATORCONFIG_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/actuatorconfig_services_interface.h" + +#include +#include + +using namespace std; + +class ActuatorConfigRobotServices : public IActuatorConfigServices +{ + public: + ActuatorConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::ActuatorConfig::ActuatorConfigClient* actuatorconfig, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool GetAxisOffsets(kortex_driver::GetAxisOffsets::Request &req, kortex_driver::GetAxisOffsets::Response &res) override; + virtual bool SetAxisOffsets(kortex_driver::SetAxisOffsets::Request &req, kortex_driver::SetAxisOffsets::Response &res) override; + virtual bool SetTorqueOffset(kortex_driver::SetTorqueOffset::Request &req, kortex_driver::SetTorqueOffset::Response &res) override; + virtual bool ActuatorConfig_GetControlMode(kortex_driver::ActuatorConfig_GetControlMode::Request &req, kortex_driver::ActuatorConfig_GetControlMode::Response &res) override; + virtual bool SetControlMode(kortex_driver::SetControlMode::Request &req, kortex_driver::SetControlMode::Response &res) override; + virtual bool GetActivatedControlLoop(kortex_driver::GetActivatedControlLoop::Request &req, kortex_driver::GetActivatedControlLoop::Response &res) override; + virtual bool SetActivatedControlLoop(kortex_driver::SetActivatedControlLoop::Request &req, kortex_driver::SetActivatedControlLoop::Response &res) override; + virtual bool GetControlLoopParameters(kortex_driver::GetControlLoopParameters::Request &req, kortex_driver::GetControlLoopParameters::Response &res) override; + virtual bool SetControlLoopParameters(kortex_driver::SetControlLoopParameters::Request &req, kortex_driver::SetControlLoopParameters::Response &res) override; + virtual bool SelectCustomData(kortex_driver::SelectCustomData::Request &req, kortex_driver::SelectCustomData::Response &res) override; + virtual bool GetSelectedCustomData(kortex_driver::GetSelectedCustomData::Request &req, kortex_driver::GetSelectedCustomData::Response &res) override; + virtual bool SetCommandMode(kortex_driver::SetCommandMode::Request &req, kortex_driver::SetCommandMode::Response &res) override; + virtual bool ActuatorConfig_ClearFaults(kortex_driver::ActuatorConfig_ClearFaults::Request &req, kortex_driver::ActuatorConfig_ClearFaults::Response &res) override; + virtual bool SetServoing(kortex_driver::SetServoing::Request &req, kortex_driver::SetServoing::Response &res) override; + virtual bool MoveToPosition(kortex_driver::MoveToPosition::Request &req, kortex_driver::MoveToPosition::Response &res) override; + virtual bool GetCommandMode(kortex_driver::GetCommandMode::Request &req, kortex_driver::GetCommandMode::Response &res) override; + virtual bool GetServoing(kortex_driver::GetServoing::Request &req, kortex_driver::GetServoing::Response &res) override; + virtual bool GetTorqueOffset(kortex_driver::GetTorqueOffset::Request &req, kortex_driver::GetTorqueOffset::Response &res) override; + virtual bool SetCoggingFeedforwardMode(kortex_driver::SetCoggingFeedforwardMode::Request &req, kortex_driver::SetCoggingFeedforwardMode::Response &res) override; + virtual bool GetCoggingFeedforwardMode(kortex_driver::GetCoggingFeedforwardMode::Request &req, kortex_driver::GetCoggingFeedforwardMode::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::ActuatorConfig::ActuatorConfigClient* m_actuatorconfig; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorcyclic_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorcyclic_proto_converter.h new file mode 100644 index 0000000..f463e1b --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorcyclic_proto_converter.h @@ -0,0 +1,55 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCYCLIC_PROTO_CONVERTER_H_ +#define _KORTEX_ACTUATORCYCLIC_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/ActuatorCyclic_MessageId.h" +#include "kortex_driver/ActuatorCyclic_Command.h" +#include "kortex_driver/ActuatorCyclic_Feedback.h" +#include "kortex_driver/ActuatorCyclic_CustomData.h" + + +int ToProtoData(kortex_driver::ActuatorCyclic_MessageId input, Kinova::Api::ActuatorCyclic::MessageId *output); +int ToProtoData(kortex_driver::ActuatorCyclic_Command input, Kinova::Api::ActuatorCyclic::Command *output); +int ToProtoData(kortex_driver::ActuatorCyclic_Feedback input, Kinova::Api::ActuatorCyclic::Feedback *output); +int ToProtoData(kortex_driver::ActuatorCyclic_CustomData input, Kinova::Api::ActuatorCyclic::CustomData *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorcyclic_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorcyclic_ros_converter.h new file mode 100644 index 0000000..02085e5 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/actuatorcyclic_ros_converter.h @@ -0,0 +1,55 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCYCLIC_ROS_CONVERTER_H_ +#define _KORTEX_ACTUATORCYCLIC_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/ActuatorCyclic_MessageId.h" +#include "kortex_driver/ActuatorCyclic_Command.h" +#include "kortex_driver/ActuatorCyclic_Feedback.h" +#include "kortex_driver/ActuatorCyclic_CustomData.h" + + +int ToRosData(Kinova::Api::ActuatorCyclic::MessageId input, kortex_driver::ActuatorCyclic_MessageId &output); +int ToRosData(Kinova::Api::ActuatorCyclic::Command input, kortex_driver::ActuatorCyclic_Command &output); +int ToRosData(Kinova::Api::ActuatorCyclic::Feedback input, kortex_driver::ActuatorCyclic_Feedback &output); +int ToRosData(Kinova::Api::ActuatorCyclic::CustomData input, kortex_driver::ActuatorCyclic_CustomData &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_proto_converter.h new file mode 100644 index 0000000..23cc90c --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_proto_converter.h @@ -0,0 +1,355 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASE_PROTO_CONVERTER_H_ +#define _KORTEX_BASE_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/FullUserProfile.h" +#include "kortex_driver/UserProfile.h" +#include "kortex_driver/UserProfileList.h" +#include "kortex_driver/UserList.h" +#include "kortex_driver/PasswordChange.h" +#include "kortex_driver/SequenceHandle.h" +#include "kortex_driver/AdvancedSequenceHandle.h" +#include "kortex_driver/SequenceTaskHandle.h" +#include "kortex_driver/SequenceTask.h" +#include "kortex_driver/SequenceTasks.h" +#include "kortex_driver/SequenceTasksConfiguration.h" +#include "kortex_driver/SequenceTaskConfiguration.h" +#include "kortex_driver/SequenceTasksRange.h" +#include "kortex_driver/SequenceTasksPair.h" +#include "kortex_driver/Sequence.h" +#include "kortex_driver/SequenceList.h" +#include "kortex_driver/AppendActionInformation.h" +#include "kortex_driver/ActionHandle.h" +#include "kortex_driver/RequestedActionType.h" +#include "kortex_driver/Action.h" +#include "kortex_driver/Snapshot.h" +#include "kortex_driver/SwitchControlMapping.h" +#include "kortex_driver/ChangeTwist.h" +#include "kortex_driver/ChangeJointSpeeds.h" +#include "kortex_driver/ChangeWrench.h" +#include "kortex_driver/EmergencyStop.h" +#include "kortex_driver/Faults.h" +#include "kortex_driver/Delay.h" +#include "kortex_driver/Base_Stop.h" +#include "kortex_driver/ActionList.h" +#include "kortex_driver/Timeout.h" +#include "kortex_driver/Ssid.h" +#include "kortex_driver/CommunicationInterfaceConfiguration.h" +#include "kortex_driver/NetworkHandle.h" +#include "kortex_driver/IPv4Configuration.h" +#include "kortex_driver/IPv4Information.h" +#include "kortex_driver/FullIPv4Configuration.h" +#include "kortex_driver/WifiInformation.h" +#include "kortex_driver/WifiInformationList.h" +#include "kortex_driver/WifiConfiguration.h" +#include "kortex_driver/WifiConfigurationList.h" +#include "kortex_driver/ProtectionZoneHandle.h" +#include "kortex_driver/Base_RotationMatrixRow.h" +#include "kortex_driver/Base_RotationMatrix.h" +#include "kortex_driver/Point.h" +#include "kortex_driver/ZoneShape.h" +#include "kortex_driver/ProtectionZone.h" +#include "kortex_driver/ProtectionZoneList.h" +#include "kortex_driver/CartesianLimitation.h" +#include "kortex_driver/TwistLimitation.h" +#include "kortex_driver/WrenchLimitation.h" +#include "kortex_driver/CartesianLimitationList.h" +#include "kortex_driver/JointLimitation.h" +#include "kortex_driver/JointsLimitationsList.h" +#include "kortex_driver/Query.h" +#include "kortex_driver/ConfigurationChangeNotification.h" +#include "kortex_driver/MappingInfoNotification.h" +#include "kortex_driver/Base_ControlModeInformation.h" +#include "kortex_driver/ControlModeNotification.h" +#include "kortex_driver/ServoingModeInformation.h" +#include "kortex_driver/OperatingModeInformation.h" +#include "kortex_driver/OperatingModeNotification.h" +#include "kortex_driver/ServoingModeNotification.h" +#include "kortex_driver/SequenceInfoNotification.h" +#include "kortex_driver/SequenceInformation.h" +#include "kortex_driver/ProtectionZoneNotification.h" +#include "kortex_driver/ProtectionZoneInformation.h" +#include "kortex_driver/UserNotification.h" +#include "kortex_driver/ControllerHandle.h" +#include "kortex_driver/ControllerElementHandle.h" +#include "kortex_driver/ControllerNotification.h" +#include "kortex_driver/ControllerList.h" +#include "kortex_driver/ControllerState.h" +#include "kortex_driver/ControllerElementState.h" +#include "kortex_driver/ActionNotification.h" +#include "kortex_driver/ActionExecutionState.h" +#include "kortex_driver/RobotEventNotification.h" +#include "kortex_driver/FactoryNotification.h" +#include "kortex_driver/NetworkNotification.h" +#include "kortex_driver/ConfigurationChangeNotificationList.h" +#include "kortex_driver/MappingInfoNotificationList.h" +#include "kortex_driver/ControlModeNotificationList.h" +#include "kortex_driver/OperatingModeNotificationList.h" +#include "kortex_driver/ServoingModeNotificationList.h" +#include "kortex_driver/SequenceInfoNotificationList.h" +#include "kortex_driver/ProtectionZoneNotificationList.h" +#include "kortex_driver/UserNotificationList.h" +#include "kortex_driver/SafetyNotificationList.h" +#include "kortex_driver/ControllerNotificationList.h" +#include "kortex_driver/ActionNotificationList.h" +#include "kortex_driver/RobotEventNotificationList.h" +#include "kortex_driver/NetworkNotificationList.h" +#include "kortex_driver/MappingHandle.h" +#include "kortex_driver/SafetyEvent.h" +#include "kortex_driver/ControllerEvent.h" +#include "kortex_driver/GpioEvent.h" +#include "kortex_driver/MapEvent.h" +#include "kortex_driver/MapElement.h" +#include "kortex_driver/ActivateMapHandle.h" +#include "kortex_driver/Map.h" +#include "kortex_driver/MapHandle.h" +#include "kortex_driver/MapList.h" +#include "kortex_driver/MapGroupHandle.h" +#include "kortex_driver/MapGroup.h" +#include "kortex_driver/MapGroupList.h" +#include "kortex_driver/Mapping.h" +#include "kortex_driver/MappingList.h" +#include "kortex_driver/TransformationMatrix.h" +#include "kortex_driver/TransformationRow.h" +#include "kortex_driver/Pose.h" +#include "kortex_driver/Base_Position.h" +#include "kortex_driver/Orientation.h" +#include "kortex_driver/CartesianSpeed.h" +#include "kortex_driver/CartesianTrajectoryConstraint.h" +#include "kortex_driver/JointTrajectoryConstraint.h" +#include "kortex_driver/Wrench.h" +#include "kortex_driver/Twist.h" +#include "kortex_driver/Admittance.h" +#include "kortex_driver/ConstrainedPose.h" +#include "kortex_driver/ConstrainedPosition.h" +#include "kortex_driver/ConstrainedOrientation.h" +#include "kortex_driver/WrenchCommand.h" +#include "kortex_driver/TwistCommand.h" +#include "kortex_driver/ConstrainedJointAngles.h" +#include "kortex_driver/ConstrainedJointAngle.h" +#include "kortex_driver/JointAngles.h" +#include "kortex_driver/JointAngle.h" +#include "kortex_driver/Base_JointSpeeds.h" +#include "kortex_driver/JointSpeed.h" +#include "kortex_driver/JointTorques.h" +#include "kortex_driver/JointTorque.h" +#include "kortex_driver/GripperCommand.h" +#include "kortex_driver/GripperRequest.h" +#include "kortex_driver/Gripper.h" +#include "kortex_driver/Finger.h" +#include "kortex_driver/SystemTime.h" +#include "kortex_driver/ControllerConfigurationMode.h" +#include "kortex_driver/ControllerConfiguration.h" +#include "kortex_driver/ControllerConfigurationList.h" +#include "kortex_driver/ActuatorInformation.h" +#include "kortex_driver/ArmStateInformation.h" +#include "kortex_driver/ArmStateNotification.h" +#include "kortex_driver/Base_CapSenseConfig.h" +#include "kortex_driver/BridgeList.h" +#include "kortex_driver/BridgeResult.h" +#include "kortex_driver/BridgeIdentifier.h" +#include "kortex_driver/BridgeConfig.h" +#include "kortex_driver/BridgePortConfig.h" +#include "kortex_driver/PreComputedJointTrajectory.h" +#include "kortex_driver/PreComputedJointTrajectoryElement.h" +#include "kortex_driver/TrajectoryErrorElement.h" +#include "kortex_driver/TrajectoryErrorReport.h" +#include "kortex_driver/FirmwareBundleVersions.h" +#include "kortex_driver/FirmwareComponentVersion.h" + + +int ToProtoData(kortex_driver::FullUserProfile input, Kinova::Api::Base::FullUserProfile *output); +int ToProtoData(kortex_driver::UserProfile input, Kinova::Api::Base::UserProfile *output); +int ToProtoData(kortex_driver::UserProfileList input, Kinova::Api::Base::UserProfileList *output); +int ToProtoData(kortex_driver::UserList input, Kinova::Api::Base::UserList *output); +int ToProtoData(kortex_driver::PasswordChange input, Kinova::Api::Base::PasswordChange *output); +int ToProtoData(kortex_driver::SequenceHandle input, Kinova::Api::Base::SequenceHandle *output); +int ToProtoData(kortex_driver::AdvancedSequenceHandle input, Kinova::Api::Base::AdvancedSequenceHandle *output); +int ToProtoData(kortex_driver::SequenceTaskHandle input, Kinova::Api::Base::SequenceTaskHandle *output); +int ToProtoData(kortex_driver::SequenceTask input, Kinova::Api::Base::SequenceTask *output); +int ToProtoData(kortex_driver::SequenceTasks input, Kinova::Api::Base::SequenceTasks *output); +int ToProtoData(kortex_driver::SequenceTasksConfiguration input, Kinova::Api::Base::SequenceTasksConfiguration *output); +int ToProtoData(kortex_driver::SequenceTaskConfiguration input, Kinova::Api::Base::SequenceTaskConfiguration *output); +int ToProtoData(kortex_driver::SequenceTasksRange input, Kinova::Api::Base::SequenceTasksRange *output); +int ToProtoData(kortex_driver::SequenceTasksPair input, Kinova::Api::Base::SequenceTasksPair *output); +int ToProtoData(kortex_driver::Sequence input, Kinova::Api::Base::Sequence *output); +int ToProtoData(kortex_driver::SequenceList input, Kinova::Api::Base::SequenceList *output); +int ToProtoData(kortex_driver::AppendActionInformation input, Kinova::Api::Base::AppendActionInformation *output); +int ToProtoData(kortex_driver::ActionHandle input, Kinova::Api::Base::ActionHandle *output); +int ToProtoData(kortex_driver::RequestedActionType input, Kinova::Api::Base::RequestedActionType *output); +int ToProtoData(kortex_driver::Action input, Kinova::Api::Base::Action *output); +int ToProtoData(kortex_driver::Snapshot input, Kinova::Api::Base::Snapshot *output); +int ToProtoData(kortex_driver::SwitchControlMapping input, Kinova::Api::Base::SwitchControlMapping *output); +int ToProtoData(kortex_driver::ChangeTwist input, Kinova::Api::Base::ChangeTwist *output); +int ToProtoData(kortex_driver::ChangeJointSpeeds input, Kinova::Api::Base::ChangeJointSpeeds *output); +int ToProtoData(kortex_driver::ChangeWrench input, Kinova::Api::Base::ChangeWrench *output); +int ToProtoData(kortex_driver::EmergencyStop input, Kinova::Api::Base::EmergencyStop *output); +int ToProtoData(kortex_driver::Faults input, Kinova::Api::Base::Faults *output); +int ToProtoData(kortex_driver::Delay input, Kinova::Api::Base::Delay *output); +int ToProtoData(kortex_driver::Base_Stop input, Kinova::Api::Base::Stop *output); +int ToProtoData(kortex_driver::ActionList input, Kinova::Api::Base::ActionList *output); +int ToProtoData(kortex_driver::Timeout input, Kinova::Api::Base::Timeout *output); +int ToProtoData(kortex_driver::Ssid input, Kinova::Api::Base::Ssid *output); +int ToProtoData(kortex_driver::CommunicationInterfaceConfiguration input, Kinova::Api::Base::CommunicationInterfaceConfiguration *output); +int ToProtoData(kortex_driver::NetworkHandle input, Kinova::Api::Base::NetworkHandle *output); +int ToProtoData(kortex_driver::IPv4Configuration input, Kinova::Api::Base::IPv4Configuration *output); +int ToProtoData(kortex_driver::IPv4Information input, Kinova::Api::Base::IPv4Information *output); +int ToProtoData(kortex_driver::FullIPv4Configuration input, Kinova::Api::Base::FullIPv4Configuration *output); +int ToProtoData(kortex_driver::WifiInformation input, Kinova::Api::Base::WifiInformation *output); +int ToProtoData(kortex_driver::WifiInformationList input, Kinova::Api::Base::WifiInformationList *output); +int ToProtoData(kortex_driver::WifiConfiguration input, Kinova::Api::Base::WifiConfiguration *output); +int ToProtoData(kortex_driver::WifiConfigurationList input, Kinova::Api::Base::WifiConfigurationList *output); +int ToProtoData(kortex_driver::ProtectionZoneHandle input, Kinova::Api::Base::ProtectionZoneHandle *output); +int ToProtoData(kortex_driver::Base_RotationMatrixRow input, Kinova::Api::Base::RotationMatrixRow *output); +int ToProtoData(kortex_driver::Base_RotationMatrix input, Kinova::Api::Base::RotationMatrix *output); +int ToProtoData(kortex_driver::Point input, Kinova::Api::Base::Point *output); +int ToProtoData(kortex_driver::ZoneShape input, Kinova::Api::Base::ZoneShape *output); +int ToProtoData(kortex_driver::ProtectionZone input, Kinova::Api::Base::ProtectionZone *output); +int ToProtoData(kortex_driver::ProtectionZoneList input, Kinova::Api::Base::ProtectionZoneList *output); +int ToProtoData(kortex_driver::CartesianLimitation input, Kinova::Api::Base::CartesianLimitation *output); +int ToProtoData(kortex_driver::TwistLimitation input, Kinova::Api::Base::TwistLimitation *output); +int ToProtoData(kortex_driver::WrenchLimitation input, Kinova::Api::Base::WrenchLimitation *output); +int ToProtoData(kortex_driver::CartesianLimitationList input, Kinova::Api::Base::CartesianLimitationList *output); +int ToProtoData(kortex_driver::JointLimitation input, Kinova::Api::Base::JointLimitation *output); +int ToProtoData(kortex_driver::JointsLimitationsList input, Kinova::Api::Base::JointsLimitationsList *output); +int ToProtoData(kortex_driver::Query input, Kinova::Api::Base::Query *output); +int ToProtoData(kortex_driver::ConfigurationChangeNotification input, Kinova::Api::Base::ConfigurationChangeNotification *output); +int ToProtoData(kortex_driver::MappingInfoNotification input, Kinova::Api::Base::MappingInfoNotification *output); +int ToProtoData(kortex_driver::Base_ControlModeInformation input, Kinova::Api::Base::ControlModeInformation *output); +int ToProtoData(kortex_driver::ControlModeNotification input, Kinova::Api::Base::ControlModeNotification *output); +int ToProtoData(kortex_driver::ServoingModeInformation input, Kinova::Api::Base::ServoingModeInformation *output); +int ToProtoData(kortex_driver::OperatingModeInformation input, Kinova::Api::Base::OperatingModeInformation *output); +int ToProtoData(kortex_driver::OperatingModeNotification input, Kinova::Api::Base::OperatingModeNotification *output); +int ToProtoData(kortex_driver::ServoingModeNotification input, Kinova::Api::Base::ServoingModeNotification *output); +int ToProtoData(kortex_driver::SequenceInfoNotification input, Kinova::Api::Base::SequenceInfoNotification *output); +int ToProtoData(kortex_driver::SequenceInformation input, Kinova::Api::Base::SequenceInformation *output); +int ToProtoData(kortex_driver::ProtectionZoneNotification input, Kinova::Api::Base::ProtectionZoneNotification *output); +int ToProtoData(kortex_driver::ProtectionZoneInformation input, Kinova::Api::Base::ProtectionZoneInformation *output); +int ToProtoData(kortex_driver::UserNotification input, Kinova::Api::Base::UserNotification *output); +int ToProtoData(kortex_driver::ControllerHandle input, Kinova::Api::Base::ControllerHandle *output); +int ToProtoData(kortex_driver::ControllerElementHandle input, Kinova::Api::Base::ControllerElementHandle *output); +int ToProtoData(kortex_driver::ControllerNotification input, Kinova::Api::Base::ControllerNotification *output); +int ToProtoData(kortex_driver::ControllerList input, Kinova::Api::Base::ControllerList *output); +int ToProtoData(kortex_driver::ControllerState input, Kinova::Api::Base::ControllerState *output); +int ToProtoData(kortex_driver::ControllerElementState input, Kinova::Api::Base::ControllerElementState *output); +int ToProtoData(kortex_driver::ActionNotification input, Kinova::Api::Base::ActionNotification *output); +int ToProtoData(kortex_driver::ActionExecutionState input, Kinova::Api::Base::ActionExecutionState *output); +int ToProtoData(kortex_driver::RobotEventNotification input, Kinova::Api::Base::RobotEventNotification *output); +int ToProtoData(kortex_driver::FactoryNotification input, Kinova::Api::Base::FactoryNotification *output); +int ToProtoData(kortex_driver::NetworkNotification input, Kinova::Api::Base::NetworkNotification *output); +int ToProtoData(kortex_driver::ConfigurationChangeNotificationList input, Kinova::Api::Base::ConfigurationChangeNotificationList *output); +int ToProtoData(kortex_driver::MappingInfoNotificationList input, Kinova::Api::Base::MappingInfoNotificationList *output); +int ToProtoData(kortex_driver::ControlModeNotificationList input, Kinova::Api::Base::ControlModeNotificationList *output); +int ToProtoData(kortex_driver::OperatingModeNotificationList input, Kinova::Api::Base::OperatingModeNotificationList *output); +int ToProtoData(kortex_driver::ServoingModeNotificationList input, Kinova::Api::Base::ServoingModeNotificationList *output); +int ToProtoData(kortex_driver::SequenceInfoNotificationList input, Kinova::Api::Base::SequenceInfoNotificationList *output); +int ToProtoData(kortex_driver::ProtectionZoneNotificationList input, Kinova::Api::Base::ProtectionZoneNotificationList *output); +int ToProtoData(kortex_driver::UserNotificationList input, Kinova::Api::Base::UserNotificationList *output); +int ToProtoData(kortex_driver::SafetyNotificationList input, Kinova::Api::Base::SafetyNotificationList *output); +int ToProtoData(kortex_driver::ControllerNotificationList input, Kinova::Api::Base::ControllerNotificationList *output); +int ToProtoData(kortex_driver::ActionNotificationList input, Kinova::Api::Base::ActionNotificationList *output); +int ToProtoData(kortex_driver::RobotEventNotificationList input, Kinova::Api::Base::RobotEventNotificationList *output); +int ToProtoData(kortex_driver::NetworkNotificationList input, Kinova::Api::Base::NetworkNotificationList *output); +int ToProtoData(kortex_driver::MappingHandle input, Kinova::Api::Base::MappingHandle *output); +int ToProtoData(kortex_driver::SafetyEvent input, Kinova::Api::Base::SafetyEvent *output); +int ToProtoData(kortex_driver::ControllerEvent input, Kinova::Api::Base::ControllerEvent *output); +int ToProtoData(kortex_driver::GpioEvent input, Kinova::Api::Base::GpioEvent *output); +int ToProtoData(kortex_driver::MapEvent input, Kinova::Api::Base::MapEvent *output); +int ToProtoData(kortex_driver::MapElement input, Kinova::Api::Base::MapElement *output); +int ToProtoData(kortex_driver::ActivateMapHandle input, Kinova::Api::Base::ActivateMapHandle *output); +int ToProtoData(kortex_driver::Map input, Kinova::Api::Base::Map *output); +int ToProtoData(kortex_driver::MapHandle input, Kinova::Api::Base::MapHandle *output); +int ToProtoData(kortex_driver::MapList input, Kinova::Api::Base::MapList *output); +int ToProtoData(kortex_driver::MapGroupHandle input, Kinova::Api::Base::MapGroupHandle *output); +int ToProtoData(kortex_driver::MapGroup input, Kinova::Api::Base::MapGroup *output); +int ToProtoData(kortex_driver::MapGroupList input, Kinova::Api::Base::MapGroupList *output); +int ToProtoData(kortex_driver::Mapping input, Kinova::Api::Base::Mapping *output); +int ToProtoData(kortex_driver::MappingList input, Kinova::Api::Base::MappingList *output); +int ToProtoData(kortex_driver::TransformationMatrix input, Kinova::Api::Base::TransformationMatrix *output); +int ToProtoData(kortex_driver::TransformationRow input, Kinova::Api::Base::TransformationRow *output); +int ToProtoData(kortex_driver::Pose input, Kinova::Api::Base::Pose *output); +int ToProtoData(kortex_driver::Base_Position input, Kinova::Api::Base::Position *output); +int ToProtoData(kortex_driver::Orientation input, Kinova::Api::Base::Orientation *output); +int ToProtoData(kortex_driver::CartesianSpeed input, Kinova::Api::Base::CartesianSpeed *output); +int ToProtoData(kortex_driver::CartesianTrajectoryConstraint input, Kinova::Api::Base::CartesianTrajectoryConstraint *output); +int ToProtoData(kortex_driver::JointTrajectoryConstraint input, Kinova::Api::Base::JointTrajectoryConstraint *output); +int ToProtoData(kortex_driver::Wrench input, Kinova::Api::Base::Wrench *output); +int ToProtoData(kortex_driver::Twist input, Kinova::Api::Base::Twist *output); +int ToProtoData(kortex_driver::Admittance input, Kinova::Api::Base::Admittance *output); +int ToProtoData(kortex_driver::ConstrainedPose input, Kinova::Api::Base::ConstrainedPose *output); +int ToProtoData(kortex_driver::ConstrainedPosition input, Kinova::Api::Base::ConstrainedPosition *output); +int ToProtoData(kortex_driver::ConstrainedOrientation input, Kinova::Api::Base::ConstrainedOrientation *output); +int ToProtoData(kortex_driver::WrenchCommand input, Kinova::Api::Base::WrenchCommand *output); +int ToProtoData(kortex_driver::TwistCommand input, Kinova::Api::Base::TwistCommand *output); +int ToProtoData(kortex_driver::ConstrainedJointAngles input, Kinova::Api::Base::ConstrainedJointAngles *output); +int ToProtoData(kortex_driver::ConstrainedJointAngle input, Kinova::Api::Base::ConstrainedJointAngle *output); +int ToProtoData(kortex_driver::JointAngles input, Kinova::Api::Base::JointAngles *output); +int ToProtoData(kortex_driver::JointAngle input, Kinova::Api::Base::JointAngle *output); +int ToProtoData(kortex_driver::Base_JointSpeeds input, Kinova::Api::Base::JointSpeeds *output); +int ToProtoData(kortex_driver::JointSpeed input, Kinova::Api::Base::JointSpeed *output); +int ToProtoData(kortex_driver::JointTorques input, Kinova::Api::Base::JointTorques *output); +int ToProtoData(kortex_driver::JointTorque input, Kinova::Api::Base::JointTorque *output); +int ToProtoData(kortex_driver::GripperCommand input, Kinova::Api::Base::GripperCommand *output); +int ToProtoData(kortex_driver::GripperRequest input, Kinova::Api::Base::GripperRequest *output); +int ToProtoData(kortex_driver::Gripper input, Kinova::Api::Base::Gripper *output); +int ToProtoData(kortex_driver::Finger input, Kinova::Api::Base::Finger *output); +int ToProtoData(kortex_driver::SystemTime input, Kinova::Api::Base::SystemTime *output); +int ToProtoData(kortex_driver::ControllerConfigurationMode input, Kinova::Api::Base::ControllerConfigurationMode *output); +int ToProtoData(kortex_driver::ControllerConfiguration input, Kinova::Api::Base::ControllerConfiguration *output); +int ToProtoData(kortex_driver::ControllerConfigurationList input, Kinova::Api::Base::ControllerConfigurationList *output); +int ToProtoData(kortex_driver::ActuatorInformation input, Kinova::Api::Base::ActuatorInformation *output); +int ToProtoData(kortex_driver::ArmStateInformation input, Kinova::Api::Base::ArmStateInformation *output); +int ToProtoData(kortex_driver::ArmStateNotification input, Kinova::Api::Base::ArmStateNotification *output); +int ToProtoData(kortex_driver::Base_CapSenseConfig input, Kinova::Api::Base::CapSenseConfig *output); +int ToProtoData(kortex_driver::BridgeList input, Kinova::Api::Base::BridgeList *output); +int ToProtoData(kortex_driver::BridgeResult input, Kinova::Api::Base::BridgeResult *output); +int ToProtoData(kortex_driver::BridgeIdentifier input, Kinova::Api::Base::BridgeIdentifier *output); +int ToProtoData(kortex_driver::BridgeConfig input, Kinova::Api::Base::BridgeConfig *output); +int ToProtoData(kortex_driver::BridgePortConfig input, Kinova::Api::Base::BridgePortConfig *output); +int ToProtoData(kortex_driver::PreComputedJointTrajectory input, Kinova::Api::Base::PreComputedJointTrajectory *output); +int ToProtoData(kortex_driver::PreComputedJointTrajectoryElement input, Kinova::Api::Base::PreComputedJointTrajectoryElement *output); +int ToProtoData(kortex_driver::TrajectoryErrorElement input, Kinova::Api::Base::TrajectoryErrorElement *output); +int ToProtoData(kortex_driver::TrajectoryErrorReport input, Kinova::Api::Base::TrajectoryErrorReport *output); +int ToProtoData(kortex_driver::FirmwareBundleVersions input, Kinova::Api::Base::FirmwareBundleVersions *output); +int ToProtoData(kortex_driver::FirmwareComponentVersion input, Kinova::Api::Base::FirmwareComponentVersion *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_ros_converter.h new file mode 100644 index 0000000..0cb57ed --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_ros_converter.h @@ -0,0 +1,355 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASE_ROS_CONVERTER_H_ +#define _KORTEX_BASE_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/FullUserProfile.h" +#include "kortex_driver/UserProfile.h" +#include "kortex_driver/UserProfileList.h" +#include "kortex_driver/UserList.h" +#include "kortex_driver/PasswordChange.h" +#include "kortex_driver/SequenceHandle.h" +#include "kortex_driver/AdvancedSequenceHandle.h" +#include "kortex_driver/SequenceTaskHandle.h" +#include "kortex_driver/SequenceTask.h" +#include "kortex_driver/SequenceTasks.h" +#include "kortex_driver/SequenceTasksConfiguration.h" +#include "kortex_driver/SequenceTaskConfiguration.h" +#include "kortex_driver/SequenceTasksRange.h" +#include "kortex_driver/SequenceTasksPair.h" +#include "kortex_driver/Sequence.h" +#include "kortex_driver/SequenceList.h" +#include "kortex_driver/AppendActionInformation.h" +#include "kortex_driver/ActionHandle.h" +#include "kortex_driver/RequestedActionType.h" +#include "kortex_driver/Action.h" +#include "kortex_driver/Snapshot.h" +#include "kortex_driver/SwitchControlMapping.h" +#include "kortex_driver/ChangeTwist.h" +#include "kortex_driver/ChangeJointSpeeds.h" +#include "kortex_driver/ChangeWrench.h" +#include "kortex_driver/EmergencyStop.h" +#include "kortex_driver/Faults.h" +#include "kortex_driver/Delay.h" +#include "kortex_driver/Base_Stop.h" +#include "kortex_driver/ActionList.h" +#include "kortex_driver/Timeout.h" +#include "kortex_driver/Ssid.h" +#include "kortex_driver/CommunicationInterfaceConfiguration.h" +#include "kortex_driver/NetworkHandle.h" +#include "kortex_driver/IPv4Configuration.h" +#include "kortex_driver/IPv4Information.h" +#include "kortex_driver/FullIPv4Configuration.h" +#include "kortex_driver/WifiInformation.h" +#include "kortex_driver/WifiInformationList.h" +#include "kortex_driver/WifiConfiguration.h" +#include "kortex_driver/WifiConfigurationList.h" +#include "kortex_driver/ProtectionZoneHandle.h" +#include "kortex_driver/Base_RotationMatrixRow.h" +#include "kortex_driver/Base_RotationMatrix.h" +#include "kortex_driver/Point.h" +#include "kortex_driver/ZoneShape.h" +#include "kortex_driver/ProtectionZone.h" +#include "kortex_driver/ProtectionZoneList.h" +#include "kortex_driver/CartesianLimitation.h" +#include "kortex_driver/TwistLimitation.h" +#include "kortex_driver/WrenchLimitation.h" +#include "kortex_driver/CartesianLimitationList.h" +#include "kortex_driver/JointLimitation.h" +#include "kortex_driver/JointsLimitationsList.h" +#include "kortex_driver/Query.h" +#include "kortex_driver/ConfigurationChangeNotification.h" +#include "kortex_driver/MappingInfoNotification.h" +#include "kortex_driver/Base_ControlModeInformation.h" +#include "kortex_driver/ControlModeNotification.h" +#include "kortex_driver/ServoingModeInformation.h" +#include "kortex_driver/OperatingModeInformation.h" +#include "kortex_driver/OperatingModeNotification.h" +#include "kortex_driver/ServoingModeNotification.h" +#include "kortex_driver/SequenceInfoNotification.h" +#include "kortex_driver/SequenceInformation.h" +#include "kortex_driver/ProtectionZoneNotification.h" +#include "kortex_driver/ProtectionZoneInformation.h" +#include "kortex_driver/UserNotification.h" +#include "kortex_driver/ControllerHandle.h" +#include "kortex_driver/ControllerElementHandle.h" +#include "kortex_driver/ControllerNotification.h" +#include "kortex_driver/ControllerList.h" +#include "kortex_driver/ControllerState.h" +#include "kortex_driver/ControllerElementState.h" +#include "kortex_driver/ActionNotification.h" +#include "kortex_driver/ActionExecutionState.h" +#include "kortex_driver/RobotEventNotification.h" +#include "kortex_driver/FactoryNotification.h" +#include "kortex_driver/NetworkNotification.h" +#include "kortex_driver/ConfigurationChangeNotificationList.h" +#include "kortex_driver/MappingInfoNotificationList.h" +#include "kortex_driver/ControlModeNotificationList.h" +#include "kortex_driver/OperatingModeNotificationList.h" +#include "kortex_driver/ServoingModeNotificationList.h" +#include "kortex_driver/SequenceInfoNotificationList.h" +#include "kortex_driver/ProtectionZoneNotificationList.h" +#include "kortex_driver/UserNotificationList.h" +#include "kortex_driver/SafetyNotificationList.h" +#include "kortex_driver/ControllerNotificationList.h" +#include "kortex_driver/ActionNotificationList.h" +#include "kortex_driver/RobotEventNotificationList.h" +#include "kortex_driver/NetworkNotificationList.h" +#include "kortex_driver/MappingHandle.h" +#include "kortex_driver/SafetyEvent.h" +#include "kortex_driver/ControllerEvent.h" +#include "kortex_driver/GpioEvent.h" +#include "kortex_driver/MapEvent.h" +#include "kortex_driver/MapElement.h" +#include "kortex_driver/ActivateMapHandle.h" +#include "kortex_driver/Map.h" +#include "kortex_driver/MapHandle.h" +#include "kortex_driver/MapList.h" +#include "kortex_driver/MapGroupHandle.h" +#include "kortex_driver/MapGroup.h" +#include "kortex_driver/MapGroupList.h" +#include "kortex_driver/Mapping.h" +#include "kortex_driver/MappingList.h" +#include "kortex_driver/TransformationMatrix.h" +#include "kortex_driver/TransformationRow.h" +#include "kortex_driver/Pose.h" +#include "kortex_driver/Base_Position.h" +#include "kortex_driver/Orientation.h" +#include "kortex_driver/CartesianSpeed.h" +#include "kortex_driver/CartesianTrajectoryConstraint.h" +#include "kortex_driver/JointTrajectoryConstraint.h" +#include "kortex_driver/Wrench.h" +#include "kortex_driver/Twist.h" +#include "kortex_driver/Admittance.h" +#include "kortex_driver/ConstrainedPose.h" +#include "kortex_driver/ConstrainedPosition.h" +#include "kortex_driver/ConstrainedOrientation.h" +#include "kortex_driver/WrenchCommand.h" +#include "kortex_driver/TwistCommand.h" +#include "kortex_driver/ConstrainedJointAngles.h" +#include "kortex_driver/ConstrainedJointAngle.h" +#include "kortex_driver/JointAngles.h" +#include "kortex_driver/JointAngle.h" +#include "kortex_driver/Base_JointSpeeds.h" +#include "kortex_driver/JointSpeed.h" +#include "kortex_driver/JointTorques.h" +#include "kortex_driver/JointTorque.h" +#include "kortex_driver/GripperCommand.h" +#include "kortex_driver/GripperRequest.h" +#include "kortex_driver/Gripper.h" +#include "kortex_driver/Finger.h" +#include "kortex_driver/SystemTime.h" +#include "kortex_driver/ControllerConfigurationMode.h" +#include "kortex_driver/ControllerConfiguration.h" +#include "kortex_driver/ControllerConfigurationList.h" +#include "kortex_driver/ActuatorInformation.h" +#include "kortex_driver/ArmStateInformation.h" +#include "kortex_driver/ArmStateNotification.h" +#include "kortex_driver/Base_CapSenseConfig.h" +#include "kortex_driver/BridgeList.h" +#include "kortex_driver/BridgeResult.h" +#include "kortex_driver/BridgeIdentifier.h" +#include "kortex_driver/BridgeConfig.h" +#include "kortex_driver/BridgePortConfig.h" +#include "kortex_driver/PreComputedJointTrajectory.h" +#include "kortex_driver/PreComputedJointTrajectoryElement.h" +#include "kortex_driver/TrajectoryErrorElement.h" +#include "kortex_driver/TrajectoryErrorReport.h" +#include "kortex_driver/FirmwareBundleVersions.h" +#include "kortex_driver/FirmwareComponentVersion.h" + + +int ToRosData(Kinova::Api::Base::FullUserProfile input, kortex_driver::FullUserProfile &output); +int ToRosData(Kinova::Api::Base::UserProfile input, kortex_driver::UserProfile &output); +int ToRosData(Kinova::Api::Base::UserProfileList input, kortex_driver::UserProfileList &output); +int ToRosData(Kinova::Api::Base::UserList input, kortex_driver::UserList &output); +int ToRosData(Kinova::Api::Base::PasswordChange input, kortex_driver::PasswordChange &output); +int ToRosData(Kinova::Api::Base::SequenceHandle input, kortex_driver::SequenceHandle &output); +int ToRosData(Kinova::Api::Base::AdvancedSequenceHandle input, kortex_driver::AdvancedSequenceHandle &output); +int ToRosData(Kinova::Api::Base::SequenceTaskHandle input, kortex_driver::SequenceTaskHandle &output); +int ToRosData(Kinova::Api::Base::SequenceTask input, kortex_driver::SequenceTask &output); +int ToRosData(Kinova::Api::Base::SequenceTasks input, kortex_driver::SequenceTasks &output); +int ToRosData(Kinova::Api::Base::SequenceTasksConfiguration input, kortex_driver::SequenceTasksConfiguration &output); +int ToRosData(Kinova::Api::Base::SequenceTaskConfiguration input, kortex_driver::SequenceTaskConfiguration &output); +int ToRosData(Kinova::Api::Base::SequenceTasksRange input, kortex_driver::SequenceTasksRange &output); +int ToRosData(Kinova::Api::Base::SequenceTasksPair input, kortex_driver::SequenceTasksPair &output); +int ToRosData(Kinova::Api::Base::Sequence input, kortex_driver::Sequence &output); +int ToRosData(Kinova::Api::Base::SequenceList input, kortex_driver::SequenceList &output); +int ToRosData(Kinova::Api::Base::AppendActionInformation input, kortex_driver::AppendActionInformation &output); +int ToRosData(Kinova::Api::Base::ActionHandle input, kortex_driver::ActionHandle &output); +int ToRosData(Kinova::Api::Base::RequestedActionType input, kortex_driver::RequestedActionType &output); +int ToRosData(Kinova::Api::Base::Action input, kortex_driver::Action &output); +int ToRosData(Kinova::Api::Base::Snapshot input, kortex_driver::Snapshot &output); +int ToRosData(Kinova::Api::Base::SwitchControlMapping input, kortex_driver::SwitchControlMapping &output); +int ToRosData(Kinova::Api::Base::ChangeTwist input, kortex_driver::ChangeTwist &output); +int ToRosData(Kinova::Api::Base::ChangeJointSpeeds input, kortex_driver::ChangeJointSpeeds &output); +int ToRosData(Kinova::Api::Base::ChangeWrench input, kortex_driver::ChangeWrench &output); +int ToRosData(Kinova::Api::Base::EmergencyStop input, kortex_driver::EmergencyStop &output); +int ToRosData(Kinova::Api::Base::Faults input, kortex_driver::Faults &output); +int ToRosData(Kinova::Api::Base::Delay input, kortex_driver::Delay &output); +int ToRosData(Kinova::Api::Base::Stop input, kortex_driver::Base_Stop &output); +int ToRosData(Kinova::Api::Base::ActionList input, kortex_driver::ActionList &output); +int ToRosData(Kinova::Api::Base::Timeout input, kortex_driver::Timeout &output); +int ToRosData(Kinova::Api::Base::Ssid input, kortex_driver::Ssid &output); +int ToRosData(Kinova::Api::Base::CommunicationInterfaceConfiguration input, kortex_driver::CommunicationInterfaceConfiguration &output); +int ToRosData(Kinova::Api::Base::NetworkHandle input, kortex_driver::NetworkHandle &output); +int ToRosData(Kinova::Api::Base::IPv4Configuration input, kortex_driver::IPv4Configuration &output); +int ToRosData(Kinova::Api::Base::IPv4Information input, kortex_driver::IPv4Information &output); +int ToRosData(Kinova::Api::Base::FullIPv4Configuration input, kortex_driver::FullIPv4Configuration &output); +int ToRosData(Kinova::Api::Base::WifiInformation input, kortex_driver::WifiInformation &output); +int ToRosData(Kinova::Api::Base::WifiInformationList input, kortex_driver::WifiInformationList &output); +int ToRosData(Kinova::Api::Base::WifiConfiguration input, kortex_driver::WifiConfiguration &output); +int ToRosData(Kinova::Api::Base::WifiConfigurationList input, kortex_driver::WifiConfigurationList &output); +int ToRosData(Kinova::Api::Base::ProtectionZoneHandle input, kortex_driver::ProtectionZoneHandle &output); +int ToRosData(Kinova::Api::Base::RotationMatrixRow input, kortex_driver::Base_RotationMatrixRow &output); +int ToRosData(Kinova::Api::Base::RotationMatrix input, kortex_driver::Base_RotationMatrix &output); +int ToRosData(Kinova::Api::Base::Point input, kortex_driver::Point &output); +int ToRosData(Kinova::Api::Base::ZoneShape input, kortex_driver::ZoneShape &output); +int ToRosData(Kinova::Api::Base::ProtectionZone input, kortex_driver::ProtectionZone &output); +int ToRosData(Kinova::Api::Base::ProtectionZoneList input, kortex_driver::ProtectionZoneList &output); +int ToRosData(Kinova::Api::Base::CartesianLimitation input, kortex_driver::CartesianLimitation &output); +int ToRosData(Kinova::Api::Base::TwistLimitation input, kortex_driver::TwistLimitation &output); +int ToRosData(Kinova::Api::Base::WrenchLimitation input, kortex_driver::WrenchLimitation &output); +int ToRosData(Kinova::Api::Base::CartesianLimitationList input, kortex_driver::CartesianLimitationList &output); +int ToRosData(Kinova::Api::Base::JointLimitation input, kortex_driver::JointLimitation &output); +int ToRosData(Kinova::Api::Base::JointsLimitationsList input, kortex_driver::JointsLimitationsList &output); +int ToRosData(Kinova::Api::Base::Query input, kortex_driver::Query &output); +int ToRosData(Kinova::Api::Base::ConfigurationChangeNotification input, kortex_driver::ConfigurationChangeNotification &output); +int ToRosData(Kinova::Api::Base::MappingInfoNotification input, kortex_driver::MappingInfoNotification &output); +int ToRosData(Kinova::Api::Base::ControlModeInformation input, kortex_driver::Base_ControlModeInformation &output); +int ToRosData(Kinova::Api::Base::ControlModeNotification input, kortex_driver::ControlModeNotification &output); +int ToRosData(Kinova::Api::Base::ServoingModeInformation input, kortex_driver::ServoingModeInformation &output); +int ToRosData(Kinova::Api::Base::OperatingModeInformation input, kortex_driver::OperatingModeInformation &output); +int ToRosData(Kinova::Api::Base::OperatingModeNotification input, kortex_driver::OperatingModeNotification &output); +int ToRosData(Kinova::Api::Base::ServoingModeNotification input, kortex_driver::ServoingModeNotification &output); +int ToRosData(Kinova::Api::Base::SequenceInfoNotification input, kortex_driver::SequenceInfoNotification &output); +int ToRosData(Kinova::Api::Base::SequenceInformation input, kortex_driver::SequenceInformation &output); +int ToRosData(Kinova::Api::Base::ProtectionZoneNotification input, kortex_driver::ProtectionZoneNotification &output); +int ToRosData(Kinova::Api::Base::ProtectionZoneInformation input, kortex_driver::ProtectionZoneInformation &output); +int ToRosData(Kinova::Api::Base::UserNotification input, kortex_driver::UserNotification &output); +int ToRosData(Kinova::Api::Base::ControllerHandle input, kortex_driver::ControllerHandle &output); +int ToRosData(Kinova::Api::Base::ControllerElementHandle input, kortex_driver::ControllerElementHandle &output); +int ToRosData(Kinova::Api::Base::ControllerNotification input, kortex_driver::ControllerNotification &output); +int ToRosData(Kinova::Api::Base::ControllerList input, kortex_driver::ControllerList &output); +int ToRosData(Kinova::Api::Base::ControllerState input, kortex_driver::ControllerState &output); +int ToRosData(Kinova::Api::Base::ControllerElementState input, kortex_driver::ControllerElementState &output); +int ToRosData(Kinova::Api::Base::ActionNotification input, kortex_driver::ActionNotification &output); +int ToRosData(Kinova::Api::Base::ActionExecutionState input, kortex_driver::ActionExecutionState &output); +int ToRosData(Kinova::Api::Base::RobotEventNotification input, kortex_driver::RobotEventNotification &output); +int ToRosData(Kinova::Api::Base::FactoryNotification input, kortex_driver::FactoryNotification &output); +int ToRosData(Kinova::Api::Base::NetworkNotification input, kortex_driver::NetworkNotification &output); +int ToRosData(Kinova::Api::Base::ConfigurationChangeNotificationList input, kortex_driver::ConfigurationChangeNotificationList &output); +int ToRosData(Kinova::Api::Base::MappingInfoNotificationList input, kortex_driver::MappingInfoNotificationList &output); +int ToRosData(Kinova::Api::Base::ControlModeNotificationList input, kortex_driver::ControlModeNotificationList &output); +int ToRosData(Kinova::Api::Base::OperatingModeNotificationList input, kortex_driver::OperatingModeNotificationList &output); +int ToRosData(Kinova::Api::Base::ServoingModeNotificationList input, kortex_driver::ServoingModeNotificationList &output); +int ToRosData(Kinova::Api::Base::SequenceInfoNotificationList input, kortex_driver::SequenceInfoNotificationList &output); +int ToRosData(Kinova::Api::Base::ProtectionZoneNotificationList input, kortex_driver::ProtectionZoneNotificationList &output); +int ToRosData(Kinova::Api::Base::UserNotificationList input, kortex_driver::UserNotificationList &output); +int ToRosData(Kinova::Api::Base::SafetyNotificationList input, kortex_driver::SafetyNotificationList &output); +int ToRosData(Kinova::Api::Base::ControllerNotificationList input, kortex_driver::ControllerNotificationList &output); +int ToRosData(Kinova::Api::Base::ActionNotificationList input, kortex_driver::ActionNotificationList &output); +int ToRosData(Kinova::Api::Base::RobotEventNotificationList input, kortex_driver::RobotEventNotificationList &output); +int ToRosData(Kinova::Api::Base::NetworkNotificationList input, kortex_driver::NetworkNotificationList &output); +int ToRosData(Kinova::Api::Base::MappingHandle input, kortex_driver::MappingHandle &output); +int ToRosData(Kinova::Api::Base::SafetyEvent input, kortex_driver::SafetyEvent &output); +int ToRosData(Kinova::Api::Base::ControllerEvent input, kortex_driver::ControllerEvent &output); +int ToRosData(Kinova::Api::Base::GpioEvent input, kortex_driver::GpioEvent &output); +int ToRosData(Kinova::Api::Base::MapEvent input, kortex_driver::MapEvent &output); +int ToRosData(Kinova::Api::Base::MapElement input, kortex_driver::MapElement &output); +int ToRosData(Kinova::Api::Base::ActivateMapHandle input, kortex_driver::ActivateMapHandle &output); +int ToRosData(Kinova::Api::Base::Map input, kortex_driver::Map &output); +int ToRosData(Kinova::Api::Base::MapHandle input, kortex_driver::MapHandle &output); +int ToRosData(Kinova::Api::Base::MapList input, kortex_driver::MapList &output); +int ToRosData(Kinova::Api::Base::MapGroupHandle input, kortex_driver::MapGroupHandle &output); +int ToRosData(Kinova::Api::Base::MapGroup input, kortex_driver::MapGroup &output); +int ToRosData(Kinova::Api::Base::MapGroupList input, kortex_driver::MapGroupList &output); +int ToRosData(Kinova::Api::Base::Mapping input, kortex_driver::Mapping &output); +int ToRosData(Kinova::Api::Base::MappingList input, kortex_driver::MappingList &output); +int ToRosData(Kinova::Api::Base::TransformationMatrix input, kortex_driver::TransformationMatrix &output); +int ToRosData(Kinova::Api::Base::TransformationRow input, kortex_driver::TransformationRow &output); +int ToRosData(Kinova::Api::Base::Pose input, kortex_driver::Pose &output); +int ToRosData(Kinova::Api::Base::Position input, kortex_driver::Base_Position &output); +int ToRosData(Kinova::Api::Base::Orientation input, kortex_driver::Orientation &output); +int ToRosData(Kinova::Api::Base::CartesianSpeed input, kortex_driver::CartesianSpeed &output); +int ToRosData(Kinova::Api::Base::CartesianTrajectoryConstraint input, kortex_driver::CartesianTrajectoryConstraint &output); +int ToRosData(Kinova::Api::Base::JointTrajectoryConstraint input, kortex_driver::JointTrajectoryConstraint &output); +int ToRosData(Kinova::Api::Base::Wrench input, kortex_driver::Wrench &output); +int ToRosData(Kinova::Api::Base::Twist input, kortex_driver::Twist &output); +int ToRosData(Kinova::Api::Base::Admittance input, kortex_driver::Admittance &output); +int ToRosData(Kinova::Api::Base::ConstrainedPose input, kortex_driver::ConstrainedPose &output); +int ToRosData(Kinova::Api::Base::ConstrainedPosition input, kortex_driver::ConstrainedPosition &output); +int ToRosData(Kinova::Api::Base::ConstrainedOrientation input, kortex_driver::ConstrainedOrientation &output); +int ToRosData(Kinova::Api::Base::WrenchCommand input, kortex_driver::WrenchCommand &output); +int ToRosData(Kinova::Api::Base::TwistCommand input, kortex_driver::TwistCommand &output); +int ToRosData(Kinova::Api::Base::ConstrainedJointAngles input, kortex_driver::ConstrainedJointAngles &output); +int ToRosData(Kinova::Api::Base::ConstrainedJointAngle input, kortex_driver::ConstrainedJointAngle &output); +int ToRosData(Kinova::Api::Base::JointAngles input, kortex_driver::JointAngles &output); +int ToRosData(Kinova::Api::Base::JointAngle input, kortex_driver::JointAngle &output); +int ToRosData(Kinova::Api::Base::JointSpeeds input, kortex_driver::Base_JointSpeeds &output); +int ToRosData(Kinova::Api::Base::JointSpeed input, kortex_driver::JointSpeed &output); +int ToRosData(Kinova::Api::Base::JointTorques input, kortex_driver::JointTorques &output); +int ToRosData(Kinova::Api::Base::JointTorque input, kortex_driver::JointTorque &output); +int ToRosData(Kinova::Api::Base::GripperCommand input, kortex_driver::GripperCommand &output); +int ToRosData(Kinova::Api::Base::GripperRequest input, kortex_driver::GripperRequest &output); +int ToRosData(Kinova::Api::Base::Gripper input, kortex_driver::Gripper &output); +int ToRosData(Kinova::Api::Base::Finger input, kortex_driver::Finger &output); +int ToRosData(Kinova::Api::Base::SystemTime input, kortex_driver::SystemTime &output); +int ToRosData(Kinova::Api::Base::ControllerConfigurationMode input, kortex_driver::ControllerConfigurationMode &output); +int ToRosData(Kinova::Api::Base::ControllerConfiguration input, kortex_driver::ControllerConfiguration &output); +int ToRosData(Kinova::Api::Base::ControllerConfigurationList input, kortex_driver::ControllerConfigurationList &output); +int ToRosData(Kinova::Api::Base::ActuatorInformation input, kortex_driver::ActuatorInformation &output); +int ToRosData(Kinova::Api::Base::ArmStateInformation input, kortex_driver::ArmStateInformation &output); +int ToRosData(Kinova::Api::Base::ArmStateNotification input, kortex_driver::ArmStateNotification &output); +int ToRosData(Kinova::Api::Base::CapSenseConfig input, kortex_driver::Base_CapSenseConfig &output); +int ToRosData(Kinova::Api::Base::BridgeList input, kortex_driver::BridgeList &output); +int ToRosData(Kinova::Api::Base::BridgeResult input, kortex_driver::BridgeResult &output); +int ToRosData(Kinova::Api::Base::BridgeIdentifier input, kortex_driver::BridgeIdentifier &output); +int ToRosData(Kinova::Api::Base::BridgeConfig input, kortex_driver::BridgeConfig &output); +int ToRosData(Kinova::Api::Base::BridgePortConfig input, kortex_driver::BridgePortConfig &output); +int ToRosData(Kinova::Api::Base::PreComputedJointTrajectory input, kortex_driver::PreComputedJointTrajectory &output); +int ToRosData(Kinova::Api::Base::PreComputedJointTrajectoryElement input, kortex_driver::PreComputedJointTrajectoryElement &output); +int ToRosData(Kinova::Api::Base::TrajectoryErrorElement input, kortex_driver::TrajectoryErrorElement &output); +int ToRosData(Kinova::Api::Base::TrajectoryErrorReport input, kortex_driver::TrajectoryErrorReport &output); +int ToRosData(Kinova::Api::Base::FirmwareBundleVersions input, kortex_driver::FirmwareBundleVersions &output); +int ToRosData(Kinova::Api::Base::FirmwareComponentVersion input, kortex_driver::FirmwareComponentVersion &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_services.h new file mode 100644 index 0000000..27c4832 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/base_services.h @@ -0,0 +1,199 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASE_ROBOT_SERVICES_H_ +#define _KORTEX_BASE_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/base_services_interface.h" + +#include +#include + +using namespace std; + +class BaseRobotServices : public IBaseServices +{ + public: + BaseRobotServices(ros::NodeHandle& node_handle, Kinova::Api::Base::BaseClient* base, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool CreateUserProfile(kortex_driver::CreateUserProfile::Request &req, kortex_driver::CreateUserProfile::Response &res) override; + virtual bool UpdateUserProfile(kortex_driver::UpdateUserProfile::Request &req, kortex_driver::UpdateUserProfile::Response &res) override; + virtual bool ReadUserProfile(kortex_driver::ReadUserProfile::Request &req, kortex_driver::ReadUserProfile::Response &res) override; + virtual bool DeleteUserProfile(kortex_driver::DeleteUserProfile::Request &req, kortex_driver::DeleteUserProfile::Response &res) override; + virtual bool ReadAllUserProfiles(kortex_driver::ReadAllUserProfiles::Request &req, kortex_driver::ReadAllUserProfiles::Response &res) override; + virtual bool ReadAllUsers(kortex_driver::ReadAllUsers::Request &req, kortex_driver::ReadAllUsers::Response &res) override; + virtual bool ChangePassword(kortex_driver::ChangePassword::Request &req, kortex_driver::ChangePassword::Response &res) override; + virtual bool CreateSequence(kortex_driver::CreateSequence::Request &req, kortex_driver::CreateSequence::Response &res) override; + virtual bool UpdateSequence(kortex_driver::UpdateSequence::Request &req, kortex_driver::UpdateSequence::Response &res) override; + virtual bool ReadSequence(kortex_driver::ReadSequence::Request &req, kortex_driver::ReadSequence::Response &res) override; + virtual bool DeleteSequence(kortex_driver::DeleteSequence::Request &req, kortex_driver::DeleteSequence::Response &res) override; + virtual bool ReadAllSequences(kortex_driver::ReadAllSequences::Request &req, kortex_driver::ReadAllSequences::Response &res) override; + virtual bool PlaySequence(kortex_driver::PlaySequence::Request &req, kortex_driver::PlaySequence::Response &res) override; + virtual bool PlayAdvancedSequence(kortex_driver::PlayAdvancedSequence::Request &req, kortex_driver::PlayAdvancedSequence::Response &res) override; + virtual bool StopSequence(kortex_driver::StopSequence::Request &req, kortex_driver::StopSequence::Response &res) override; + virtual bool PauseSequence(kortex_driver::PauseSequence::Request &req, kortex_driver::PauseSequence::Response &res) override; + virtual bool ResumeSequence(kortex_driver::ResumeSequence::Request &req, kortex_driver::ResumeSequence::Response &res) override; + virtual bool CreateProtectionZone(kortex_driver::CreateProtectionZone::Request &req, kortex_driver::CreateProtectionZone::Response &res) override; + virtual bool UpdateProtectionZone(kortex_driver::UpdateProtectionZone::Request &req, kortex_driver::UpdateProtectionZone::Response &res) override; + virtual bool ReadProtectionZone(kortex_driver::ReadProtectionZone::Request &req, kortex_driver::ReadProtectionZone::Response &res) override; + virtual bool DeleteProtectionZone(kortex_driver::DeleteProtectionZone::Request &req, kortex_driver::DeleteProtectionZone::Response &res) override; + virtual bool ReadAllProtectionZones(kortex_driver::ReadAllProtectionZones::Request &req, kortex_driver::ReadAllProtectionZones::Response &res) override; + virtual bool CreateMapping(kortex_driver::CreateMapping::Request &req, kortex_driver::CreateMapping::Response &res) override; + virtual bool ReadMapping(kortex_driver::ReadMapping::Request &req, kortex_driver::ReadMapping::Response &res) override; + virtual bool UpdateMapping(kortex_driver::UpdateMapping::Request &req, kortex_driver::UpdateMapping::Response &res) override; + virtual bool DeleteMapping(kortex_driver::DeleteMapping::Request &req, kortex_driver::DeleteMapping::Response &res) override; + virtual bool ReadAllMappings(kortex_driver::ReadAllMappings::Request &req, kortex_driver::ReadAllMappings::Response &res) override; + virtual bool CreateMap(kortex_driver::CreateMap::Request &req, kortex_driver::CreateMap::Response &res) override; + virtual bool ReadMap(kortex_driver::ReadMap::Request &req, kortex_driver::ReadMap::Response &res) override; + virtual bool UpdateMap(kortex_driver::UpdateMap::Request &req, kortex_driver::UpdateMap::Response &res) override; + virtual bool DeleteMap(kortex_driver::DeleteMap::Request &req, kortex_driver::DeleteMap::Response &res) override; + virtual bool ReadAllMaps(kortex_driver::ReadAllMaps::Request &req, kortex_driver::ReadAllMaps::Response &res) override; + virtual bool ActivateMap(kortex_driver::ActivateMap::Request &req, kortex_driver::ActivateMap::Response &res) override; + virtual bool CreateAction(kortex_driver::CreateAction::Request &req, kortex_driver::CreateAction::Response &res) override; + virtual bool ReadAction(kortex_driver::ReadAction::Request &req, kortex_driver::ReadAction::Response &res) override; + virtual bool ReadAllActions(kortex_driver::ReadAllActions::Request &req, kortex_driver::ReadAllActions::Response &res) override; + virtual bool DeleteAction(kortex_driver::DeleteAction::Request &req, kortex_driver::DeleteAction::Response &res) override; + virtual bool UpdateAction(kortex_driver::UpdateAction::Request &req, kortex_driver::UpdateAction::Response &res) override; + virtual bool ExecuteActionFromReference(kortex_driver::ExecuteActionFromReference::Request &req, kortex_driver::ExecuteActionFromReference::Response &res) override; + virtual bool ExecuteAction(kortex_driver::ExecuteAction::Request &req, kortex_driver::ExecuteAction::Response &res) override; + virtual bool PauseAction(kortex_driver::PauseAction::Request &req, kortex_driver::PauseAction::Response &res) override; + virtual bool StopAction(kortex_driver::StopAction::Request &req, kortex_driver::StopAction::Response &res) override; + virtual bool ResumeAction(kortex_driver::ResumeAction::Request &req, kortex_driver::ResumeAction::Response &res) override; + virtual bool GetIPv4Configuration(kortex_driver::GetIPv4Configuration::Request &req, kortex_driver::GetIPv4Configuration::Response &res) override; + virtual bool SetIPv4Configuration(kortex_driver::SetIPv4Configuration::Request &req, kortex_driver::SetIPv4Configuration::Response &res) override; + virtual bool SetCommunicationInterfaceEnable(kortex_driver::SetCommunicationInterfaceEnable::Request &req, kortex_driver::SetCommunicationInterfaceEnable::Response &res) override; + virtual bool IsCommunicationInterfaceEnable(kortex_driver::IsCommunicationInterfaceEnable::Request &req, kortex_driver::IsCommunicationInterfaceEnable::Response &res) override; + virtual bool GetAvailableWifi(kortex_driver::GetAvailableWifi::Request &req, kortex_driver::GetAvailableWifi::Response &res) override; + virtual bool GetWifiInformation(kortex_driver::GetWifiInformation::Request &req, kortex_driver::GetWifiInformation::Response &res) override; + virtual bool AddWifiConfiguration(kortex_driver::AddWifiConfiguration::Request &req, kortex_driver::AddWifiConfiguration::Response &res) override; + virtual bool DeleteWifiConfiguration(kortex_driver::DeleteWifiConfiguration::Request &req, kortex_driver::DeleteWifiConfiguration::Response &res) override; + virtual bool GetAllConfiguredWifis(kortex_driver::GetAllConfiguredWifis::Request &req, kortex_driver::GetAllConfiguredWifis::Response &res) override; + virtual bool ConnectWifi(kortex_driver::ConnectWifi::Request &req, kortex_driver::ConnectWifi::Response &res) override; + virtual bool DisconnectWifi(kortex_driver::DisconnectWifi::Request &req, kortex_driver::DisconnectWifi::Response &res) override; + virtual bool GetConnectedWifiInformation(kortex_driver::GetConnectedWifiInformation::Request &req, kortex_driver::GetConnectedWifiInformation::Response &res) override; + virtual bool Base_Unsubscribe(kortex_driver::Base_Unsubscribe::Request &req, kortex_driver::Base_Unsubscribe::Response &res) override; + virtual bool OnNotificationConfigurationChangeTopic(kortex_driver::OnNotificationConfigurationChangeTopic::Request &req, kortex_driver::OnNotificationConfigurationChangeTopic::Response &res) override; + virtual void cb_ConfigurationChangeTopic(Kinova::Api::Base::ConfigurationChangeNotification notif) override; + virtual bool OnNotificationMappingInfoTopic(kortex_driver::OnNotificationMappingInfoTopic::Request &req, kortex_driver::OnNotificationMappingInfoTopic::Response &res) override; + virtual void cb_MappingInfoTopic(Kinova::Api::Base::MappingInfoNotification notif) override; + virtual bool OnNotificationControlModeTopic(kortex_driver::OnNotificationControlModeTopic::Request &req, kortex_driver::OnNotificationControlModeTopic::Response &res) override; + virtual void cb_ControlModeTopic(Kinova::Api::Base::ControlModeNotification notif) override; + virtual bool OnNotificationOperatingModeTopic(kortex_driver::OnNotificationOperatingModeTopic::Request &req, kortex_driver::OnNotificationOperatingModeTopic::Response &res) override; + virtual void cb_OperatingModeTopic(Kinova::Api::Base::OperatingModeNotification notif) override; + virtual bool OnNotificationSequenceInfoTopic(kortex_driver::OnNotificationSequenceInfoTopic::Request &req, kortex_driver::OnNotificationSequenceInfoTopic::Response &res) override; + virtual void cb_SequenceInfoTopic(Kinova::Api::Base::SequenceInfoNotification notif) override; + virtual bool OnNotificationProtectionZoneTopic(kortex_driver::OnNotificationProtectionZoneTopic::Request &req, kortex_driver::OnNotificationProtectionZoneTopic::Response &res) override; + virtual void cb_ProtectionZoneTopic(Kinova::Api::Base::ProtectionZoneNotification notif) override; + virtual bool OnNotificationUserTopic(kortex_driver::OnNotificationUserTopic::Request &req, kortex_driver::OnNotificationUserTopic::Response &res) override; + virtual void cb_UserTopic(Kinova::Api::Base::UserNotification notif) override; + virtual bool OnNotificationControllerTopic(kortex_driver::OnNotificationControllerTopic::Request &req, kortex_driver::OnNotificationControllerTopic::Response &res) override; + virtual void cb_ControllerTopic(Kinova::Api::Base::ControllerNotification notif) override; + virtual bool OnNotificationActionTopic(kortex_driver::OnNotificationActionTopic::Request &req, kortex_driver::OnNotificationActionTopic::Response &res) override; + virtual void cb_ActionTopic(Kinova::Api::Base::ActionNotification notif) override; + virtual bool OnNotificationRobotEventTopic(kortex_driver::OnNotificationRobotEventTopic::Request &req, kortex_driver::OnNotificationRobotEventTopic::Response &res) override; + virtual void cb_RobotEventTopic(Kinova::Api::Base::RobotEventNotification notif) override; + virtual bool PlayCartesianTrajectory(kortex_driver::PlayCartesianTrajectory::Request &req, kortex_driver::PlayCartesianTrajectory::Response &res) override; + virtual bool PlayCartesianTrajectoryPosition(kortex_driver::PlayCartesianTrajectoryPosition::Request &req, kortex_driver::PlayCartesianTrajectoryPosition::Response &res) override; + virtual bool PlayCartesianTrajectoryOrientation(kortex_driver::PlayCartesianTrajectoryOrientation::Request &req, kortex_driver::PlayCartesianTrajectoryOrientation::Response &res) override; + virtual bool Stop(kortex_driver::Stop::Request &req, kortex_driver::Stop::Response &res) override; + virtual bool GetMeasuredCartesianPose(kortex_driver::GetMeasuredCartesianPose::Request &req, kortex_driver::GetMeasuredCartesianPose::Response &res) override; + virtual bool SendWrenchCommand(kortex_driver::SendWrenchCommand::Request &req, kortex_driver::SendWrenchCommand::Response &res) override; + virtual bool SendWrenchJoystickCommand(kortex_driver::SendWrenchJoystickCommand::Request &req, kortex_driver::SendWrenchJoystickCommand::Response &res) override; + virtual bool SendTwistJoystickCommand(kortex_driver::SendTwistJoystickCommand::Request &req, kortex_driver::SendTwistJoystickCommand::Response &res) override; + virtual bool SendTwistCommand(kortex_driver::SendTwistCommand::Request &req, kortex_driver::SendTwistCommand::Response &res) override; + virtual bool PlayJointTrajectory(kortex_driver::PlayJointTrajectory::Request &req, kortex_driver::PlayJointTrajectory::Response &res) override; + virtual bool PlaySelectedJointTrajectory(kortex_driver::PlaySelectedJointTrajectory::Request &req, kortex_driver::PlaySelectedJointTrajectory::Response &res) override; + virtual bool GetMeasuredJointAngles(kortex_driver::GetMeasuredJointAngles::Request &req, kortex_driver::GetMeasuredJointAngles::Response &res) override; + virtual bool SendJointSpeedsCommand(kortex_driver::SendJointSpeedsCommand::Request &req, kortex_driver::SendJointSpeedsCommand::Response &res) override; + virtual bool SendSelectedJointSpeedCommand(kortex_driver::SendSelectedJointSpeedCommand::Request &req, kortex_driver::SendSelectedJointSpeedCommand::Response &res) override; + virtual bool SendGripperCommand(kortex_driver::SendGripperCommand::Request &req, kortex_driver::SendGripperCommand::Response &res) override; + virtual bool GetMeasuredGripperMovement(kortex_driver::GetMeasuredGripperMovement::Request &req, kortex_driver::GetMeasuredGripperMovement::Response &res) override; + virtual bool SetAdmittance(kortex_driver::SetAdmittance::Request &req, kortex_driver::SetAdmittance::Response &res) override; + virtual bool SetOperatingMode(kortex_driver::SetOperatingMode::Request &req, kortex_driver::SetOperatingMode::Response &res) override; + virtual bool ApplyEmergencyStop(kortex_driver::ApplyEmergencyStop::Request &req, kortex_driver::ApplyEmergencyStop::Response &res) override; + virtual bool Base_ClearFaults(kortex_driver::Base_ClearFaults::Request &req, kortex_driver::Base_ClearFaults::Response &res) override; + virtual bool Base_GetControlMode(kortex_driver::Base_GetControlMode::Request &req, kortex_driver::Base_GetControlMode::Response &res) override; + virtual bool GetOperatingMode(kortex_driver::GetOperatingMode::Request &req, kortex_driver::GetOperatingMode::Response &res) override; + virtual bool SetServoingMode(kortex_driver::SetServoingMode::Request &req, kortex_driver::SetServoingMode::Response &res) override; + virtual bool GetServoingMode(kortex_driver::GetServoingMode::Request &req, kortex_driver::GetServoingMode::Response &res) override; + virtual bool OnNotificationServoingModeTopic(kortex_driver::OnNotificationServoingModeTopic::Request &req, kortex_driver::OnNotificationServoingModeTopic::Response &res) override; + virtual void cb_ServoingModeTopic(Kinova::Api::Base::ServoingModeNotification notif) override; + virtual bool RestoreFactorySettings(kortex_driver::RestoreFactorySettings::Request &req, kortex_driver::RestoreFactorySettings::Response &res) override; + virtual bool OnNotificationFactoryTopic(kortex_driver::OnNotificationFactoryTopic::Request &req, kortex_driver::OnNotificationFactoryTopic::Response &res) override; + virtual void cb_FactoryTopic(Kinova::Api::Base::FactoryNotification notif) override; + virtual bool GetAllConnectedControllers(kortex_driver::GetAllConnectedControllers::Request &req, kortex_driver::GetAllConnectedControllers::Response &res) override; + virtual bool GetControllerState(kortex_driver::GetControllerState::Request &req, kortex_driver::GetControllerState::Response &res) override; + virtual bool GetActuatorCount(kortex_driver::GetActuatorCount::Request &req, kortex_driver::GetActuatorCount::Response &res) override; + virtual bool StartWifiScan(kortex_driver::StartWifiScan::Request &req, kortex_driver::StartWifiScan::Response &res) override; + virtual bool GetConfiguredWifi(kortex_driver::GetConfiguredWifi::Request &req, kortex_driver::GetConfiguredWifi::Response &res) override; + virtual bool OnNotificationNetworkTopic(kortex_driver::OnNotificationNetworkTopic::Request &req, kortex_driver::OnNotificationNetworkTopic::Response &res) override; + virtual void cb_NetworkTopic(Kinova::Api::Base::NetworkNotification notif) override; + virtual bool GetArmState(kortex_driver::GetArmState::Request &req, kortex_driver::GetArmState::Response &res) override; + virtual bool OnNotificationArmStateTopic(kortex_driver::OnNotificationArmStateTopic::Request &req, kortex_driver::OnNotificationArmStateTopic::Response &res) override; + virtual void cb_ArmStateTopic(Kinova::Api::Base::ArmStateNotification notif) override; + virtual bool GetIPv4Information(kortex_driver::GetIPv4Information::Request &req, kortex_driver::GetIPv4Information::Response &res) override; + virtual bool SetWifiCountryCode(kortex_driver::SetWifiCountryCode::Request &req, kortex_driver::SetWifiCountryCode::Response &res) override; + virtual bool GetWifiCountryCode(kortex_driver::GetWifiCountryCode::Request &req, kortex_driver::GetWifiCountryCode::Response &res) override; + virtual bool Base_SetCapSenseConfig(kortex_driver::Base_SetCapSenseConfig::Request &req, kortex_driver::Base_SetCapSenseConfig::Response &res) override; + virtual bool Base_GetCapSenseConfig(kortex_driver::Base_GetCapSenseConfig::Request &req, kortex_driver::Base_GetCapSenseConfig::Response &res) override; + virtual bool GetAllJointsSpeedHardLimitation(kortex_driver::GetAllJointsSpeedHardLimitation::Request &req, kortex_driver::GetAllJointsSpeedHardLimitation::Response &res) override; + virtual bool GetAllJointsTorqueHardLimitation(kortex_driver::GetAllJointsTorqueHardLimitation::Request &req, kortex_driver::GetAllJointsTorqueHardLimitation::Response &res) override; + virtual bool GetTwistHardLimitation(kortex_driver::GetTwistHardLimitation::Request &req, kortex_driver::GetTwistHardLimitation::Response &res) override; + virtual bool GetWrenchHardLimitation(kortex_driver::GetWrenchHardLimitation::Request &req, kortex_driver::GetWrenchHardLimitation::Response &res) override; + virtual bool SendJointSpeedsJoystickCommand(kortex_driver::SendJointSpeedsJoystickCommand::Request &req, kortex_driver::SendJointSpeedsJoystickCommand::Response &res) override; + virtual bool SendSelectedJointSpeedJoystickCommand(kortex_driver::SendSelectedJointSpeedJoystickCommand::Request &req, kortex_driver::SendSelectedJointSpeedJoystickCommand::Response &res) override; + virtual bool EnableBridge(kortex_driver::EnableBridge::Request &req, kortex_driver::EnableBridge::Response &res) override; + virtual bool DisableBridge(kortex_driver::DisableBridge::Request &req, kortex_driver::DisableBridge::Response &res) override; + virtual bool GetBridgeList(kortex_driver::GetBridgeList::Request &req, kortex_driver::GetBridgeList::Response &res) override; + virtual bool GetBridgeConfig(kortex_driver::GetBridgeConfig::Request &req, kortex_driver::GetBridgeConfig::Response &res) override; + virtual bool PlayPreComputedJointTrajectory(kortex_driver::PlayPreComputedJointTrajectory::Request &req, kortex_driver::PlayPreComputedJointTrajectory::Response &res) override; + virtual bool GetProductConfiguration(kortex_driver::GetProductConfiguration::Request &req, kortex_driver::GetProductConfiguration::Response &res) override; + virtual bool UpdateEndEffectorTypeConfiguration(kortex_driver::UpdateEndEffectorTypeConfiguration::Request &req, kortex_driver::UpdateEndEffectorTypeConfiguration::Response &res) override; + virtual bool RestoreFactoryProductConfiguration(kortex_driver::RestoreFactoryProductConfiguration::Request &req, kortex_driver::RestoreFactoryProductConfiguration::Response &res) override; + virtual bool GetTrajectoryErrorReport(kortex_driver::GetTrajectoryErrorReport::Request &req, kortex_driver::GetTrajectoryErrorReport::Response &res) override; + virtual bool GetAllJointsSpeedSoftLimitation(kortex_driver::GetAllJointsSpeedSoftLimitation::Request &req, kortex_driver::GetAllJointsSpeedSoftLimitation::Response &res) override; + virtual bool GetAllJointsTorqueSoftLimitation(kortex_driver::GetAllJointsTorqueSoftLimitation::Request &req, kortex_driver::GetAllJointsTorqueSoftLimitation::Response &res) override; + virtual bool GetTwistSoftLimitation(kortex_driver::GetTwistSoftLimitation::Request &req, kortex_driver::GetTwistSoftLimitation::Response &res) override; + virtual bool GetWrenchSoftLimitation(kortex_driver::GetWrenchSoftLimitation::Request &req, kortex_driver::GetWrenchSoftLimitation::Response &res) override; + virtual bool SetControllerConfigurationMode(kortex_driver::SetControllerConfigurationMode::Request &req, kortex_driver::SetControllerConfigurationMode::Response &res) override; + virtual bool GetControllerConfigurationMode(kortex_driver::GetControllerConfigurationMode::Request &req, kortex_driver::GetControllerConfigurationMode::Response &res) override; + virtual bool StartTeaching(kortex_driver::StartTeaching::Request &req, kortex_driver::StartTeaching::Response &res) override; + virtual bool StopTeaching(kortex_driver::StopTeaching::Request &req, kortex_driver::StopTeaching::Response &res) override; + virtual bool AddSequenceTasks(kortex_driver::AddSequenceTasks::Request &req, kortex_driver::AddSequenceTasks::Response &res) override; + virtual bool UpdateSequenceTask(kortex_driver::UpdateSequenceTask::Request &req, kortex_driver::UpdateSequenceTask::Response &res) override; + virtual bool SwapSequenceTasks(kortex_driver::SwapSequenceTasks::Request &req, kortex_driver::SwapSequenceTasks::Response &res) override; + virtual bool ReadSequenceTask(kortex_driver::ReadSequenceTask::Request &req, kortex_driver::ReadSequenceTask::Response &res) override; + virtual bool ReadAllSequenceTasks(kortex_driver::ReadAllSequenceTasks::Request &req, kortex_driver::ReadAllSequenceTasks::Response &res) override; + virtual bool DeleteSequenceTask(kortex_driver::DeleteSequenceTask::Request &req, kortex_driver::DeleteSequenceTask::Response &res) override; + virtual bool DeleteAllSequenceTasks(kortex_driver::DeleteAllSequenceTasks::Request &req, kortex_driver::DeleteAllSequenceTasks::Response &res) override; + virtual bool TakeSnapshot(kortex_driver::TakeSnapshot::Request &req, kortex_driver::TakeSnapshot::Response &res) override; + virtual bool GetFirmwareBundleVersions(kortex_driver::GetFirmwareBundleVersions::Request &req, kortex_driver::GetFirmwareBundleVersions::Response &res) override; + virtual bool MoveSequenceTask(kortex_driver::MoveSequenceTask::Request &req, kortex_driver::MoveSequenceTask::Response &res) override; + virtual bool DuplicateMapping(kortex_driver::DuplicateMapping::Request &req, kortex_driver::DuplicateMapping::Response &res) override; + virtual bool DuplicateMap(kortex_driver::DuplicateMap::Request &req, kortex_driver::DuplicateMap::Response &res) override; + virtual bool SetControllerConfiguration(kortex_driver::SetControllerConfiguration::Request &req, kortex_driver::SetControllerConfiguration::Response &res) override; + virtual bool GetControllerConfiguration(kortex_driver::GetControllerConfiguration::Request &req, kortex_driver::GetControllerConfiguration::Response &res) override; + virtual bool GetAllControllerConfigurations(kortex_driver::GetAllControllerConfigurations::Request &req, kortex_driver::GetAllControllerConfigurations::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::Base::BaseClient* m_base; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/basecyclic_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/basecyclic_proto_converter.h new file mode 100644 index 0000000..ba500e2 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/basecyclic_proto_converter.h @@ -0,0 +1,61 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASECYCLIC_PROTO_CONVERTER_H_ +#define _KORTEX_BASECYCLIC_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/ActuatorCommand.h" +#include "kortex_driver/ActuatorFeedback.h" +#include "kortex_driver/ActuatorCustomData.h" +#include "kortex_driver/BaseFeedback.h" +#include "kortex_driver/BaseCyclic_CustomData.h" +#include "kortex_driver/BaseCyclic_Command.h" +#include "kortex_driver/BaseCyclic_Feedback.h" + + +int ToProtoData(kortex_driver::ActuatorCommand input, Kinova::Api::BaseCyclic::ActuatorCommand *output); +int ToProtoData(kortex_driver::ActuatorFeedback input, Kinova::Api::BaseCyclic::ActuatorFeedback *output); +int ToProtoData(kortex_driver::ActuatorCustomData input, Kinova::Api::BaseCyclic::ActuatorCustomData *output); +int ToProtoData(kortex_driver::BaseFeedback input, Kinova::Api::BaseCyclic::BaseFeedback *output); +int ToProtoData(kortex_driver::BaseCyclic_CustomData input, Kinova::Api::BaseCyclic::CustomData *output); +int ToProtoData(kortex_driver::BaseCyclic_Command input, Kinova::Api::BaseCyclic::Command *output); +int ToProtoData(kortex_driver::BaseCyclic_Feedback input, Kinova::Api::BaseCyclic::Feedback *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/basecyclic_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/basecyclic_ros_converter.h new file mode 100644 index 0000000..d0f8a8a --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/basecyclic_ros_converter.h @@ -0,0 +1,61 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASECYCLIC_ROS_CONVERTER_H_ +#define _KORTEX_BASECYCLIC_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/ActuatorCommand.h" +#include "kortex_driver/ActuatorFeedback.h" +#include "kortex_driver/ActuatorCustomData.h" +#include "kortex_driver/BaseFeedback.h" +#include "kortex_driver/BaseCyclic_CustomData.h" +#include "kortex_driver/BaseCyclic_Command.h" +#include "kortex_driver/BaseCyclic_Feedback.h" + + +int ToRosData(Kinova::Api::BaseCyclic::ActuatorCommand input, kortex_driver::ActuatorCommand &output); +int ToRosData(Kinova::Api::BaseCyclic::ActuatorFeedback input, kortex_driver::ActuatorFeedback &output); +int ToRosData(Kinova::Api::BaseCyclic::ActuatorCustomData input, kortex_driver::ActuatorCustomData &output); +int ToRosData(Kinova::Api::BaseCyclic::BaseFeedback input, kortex_driver::BaseFeedback &output); +int ToRosData(Kinova::Api::BaseCyclic::CustomData input, kortex_driver::BaseCyclic_CustomData &output); +int ToRosData(Kinova::Api::BaseCyclic::Command input, kortex_driver::BaseCyclic_Command &output); +int ToRosData(Kinova::Api::BaseCyclic::Feedback input, kortex_driver::BaseCyclic_Feedback &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/common_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/common_proto_converter.h new file mode 100644 index 0000000..786db33 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/common_proto_converter.h @@ -0,0 +1,71 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_COMMON_PROTO_CONVERTER_H_ +#define _KORTEX_COMMON_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/DeviceHandle.h" +#include "kortex_driver/Empty.h" +#include "kortex_driver/NotificationOptions.h" +#include "kortex_driver/SafetyHandle.h" +#include "kortex_driver/NotificationHandle.h" +#include "kortex_driver/SafetyNotification.h" +#include "kortex_driver/Timestamp.h" +#include "kortex_driver/UserProfileHandle.h" +#include "kortex_driver/Connection.h" +#include "kortex_driver/UARTConfiguration.h" +#include "kortex_driver/UARTDeviceIdentification.h" +#include "kortex_driver/CountryCode.h" + + +int ToProtoData(kortex_driver::DeviceHandle input, Kinova::Api::Common::DeviceHandle *output); +int ToProtoData(kortex_driver::Empty input, Kinova::Api::Common::Empty *output); +int ToProtoData(kortex_driver::NotificationOptions input, Kinova::Api::Common::NotificationOptions *output); +int ToProtoData(kortex_driver::SafetyHandle input, Kinova::Api::Common::SafetyHandle *output); +int ToProtoData(kortex_driver::NotificationHandle input, Kinova::Api::Common::NotificationHandle *output); +int ToProtoData(kortex_driver::SafetyNotification input, Kinova::Api::Common::SafetyNotification *output); +int ToProtoData(kortex_driver::Timestamp input, Kinova::Api::Common::Timestamp *output); +int ToProtoData(kortex_driver::UserProfileHandle input, Kinova::Api::Common::UserProfileHandle *output); +int ToProtoData(kortex_driver::Connection input, Kinova::Api::Common::Connection *output); +int ToProtoData(kortex_driver::UARTConfiguration input, Kinova::Api::Common::UARTConfiguration *output); +int ToProtoData(kortex_driver::UARTDeviceIdentification input, Kinova::Api::Common::UARTDeviceIdentification *output); +int ToProtoData(kortex_driver::CountryCode input, Kinova::Api::Common::CountryCode *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/common_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/common_ros_converter.h new file mode 100644 index 0000000..6aa14ec --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/common_ros_converter.h @@ -0,0 +1,71 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_COMMON_ROS_CONVERTER_H_ +#define _KORTEX_COMMON_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/DeviceHandle.h" +#include "kortex_driver/Empty.h" +#include "kortex_driver/NotificationOptions.h" +#include "kortex_driver/SafetyHandle.h" +#include "kortex_driver/NotificationHandle.h" +#include "kortex_driver/SafetyNotification.h" +#include "kortex_driver/Timestamp.h" +#include "kortex_driver/UserProfileHandle.h" +#include "kortex_driver/Connection.h" +#include "kortex_driver/UARTConfiguration.h" +#include "kortex_driver/UARTDeviceIdentification.h" +#include "kortex_driver/CountryCode.h" + + +int ToRosData(Kinova::Api::Common::DeviceHandle input, kortex_driver::DeviceHandle &output); +int ToRosData(Kinova::Api::Common::Empty input, kortex_driver::Empty &output); +int ToRosData(Kinova::Api::Common::NotificationOptions input, kortex_driver::NotificationOptions &output); +int ToRosData(Kinova::Api::Common::SafetyHandle input, kortex_driver::SafetyHandle &output); +int ToRosData(Kinova::Api::Common::NotificationHandle input, kortex_driver::NotificationHandle &output); +int ToRosData(Kinova::Api::Common::SafetyNotification input, kortex_driver::SafetyNotification &output); +int ToRosData(Kinova::Api::Common::Timestamp input, kortex_driver::Timestamp &output); +int ToRosData(Kinova::Api::Common::UserProfileHandle input, kortex_driver::UserProfileHandle &output); +int ToRosData(Kinova::Api::Common::Connection input, kortex_driver::Connection &output); +int ToRosData(Kinova::Api::Common::UARTConfiguration input, kortex_driver::UARTConfiguration &output); +int ToRosData(Kinova::Api::Common::UARTDeviceIdentification input, kortex_driver::UARTDeviceIdentification &output); +int ToRosData(Kinova::Api::Common::CountryCode input, kortex_driver::CountryCode &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_proto_converter.h new file mode 100644 index 0000000..6b19dd0 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_proto_converter.h @@ -0,0 +1,83 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_CONTROLCONFIG_PROTO_CONVERTER_H_ +#define _KORTEX_CONTROLCONFIG_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/GravityVector.h" +#include "kortex_driver/ControlConfig_Position.h" +#include "kortex_driver/PayloadInformation.h" +#include "kortex_driver/CartesianTransform.h" +#include "kortex_driver/ToolConfiguration.h" +#include "kortex_driver/ControlConfigurationNotification.h" +#include "kortex_driver/CartesianReferenceFrameInfo.h" +#include "kortex_driver/TwistLinearSoftLimit.h" +#include "kortex_driver/TwistAngularSoftLimit.h" +#include "kortex_driver/JointSpeedSoftLimits.h" +#include "kortex_driver/JointAccelerationSoftLimits.h" +#include "kortex_driver/KinematicLimits.h" +#include "kortex_driver/KinematicLimitsList.h" +#include "kortex_driver/DesiredSpeeds.h" +#include "kortex_driver/LinearTwist.h" +#include "kortex_driver/AngularTwist.h" +#include "kortex_driver/ControlConfig_JointSpeeds.h" +#include "kortex_driver/ControlConfig_ControlModeInformation.h" + + +int ToProtoData(kortex_driver::GravityVector input, Kinova::Api::ControlConfig::GravityVector *output); +int ToProtoData(kortex_driver::ControlConfig_Position input, Kinova::Api::ControlConfig::Position *output); +int ToProtoData(kortex_driver::PayloadInformation input, Kinova::Api::ControlConfig::PayloadInformation *output); +int ToProtoData(kortex_driver::CartesianTransform input, Kinova::Api::ControlConfig::CartesianTransform *output); +int ToProtoData(kortex_driver::ToolConfiguration input, Kinova::Api::ControlConfig::ToolConfiguration *output); +int ToProtoData(kortex_driver::ControlConfigurationNotification input, Kinova::Api::ControlConfig::ControlConfigurationNotification *output); +int ToProtoData(kortex_driver::CartesianReferenceFrameInfo input, Kinova::Api::ControlConfig::CartesianReferenceFrameInfo *output); +int ToProtoData(kortex_driver::TwistLinearSoftLimit input, Kinova::Api::ControlConfig::TwistLinearSoftLimit *output); +int ToProtoData(kortex_driver::TwistAngularSoftLimit input, Kinova::Api::ControlConfig::TwistAngularSoftLimit *output); +int ToProtoData(kortex_driver::JointSpeedSoftLimits input, Kinova::Api::ControlConfig::JointSpeedSoftLimits *output); +int ToProtoData(kortex_driver::JointAccelerationSoftLimits input, Kinova::Api::ControlConfig::JointAccelerationSoftLimits *output); +int ToProtoData(kortex_driver::KinematicLimits input, Kinova::Api::ControlConfig::KinematicLimits *output); +int ToProtoData(kortex_driver::KinematicLimitsList input, Kinova::Api::ControlConfig::KinematicLimitsList *output); +int ToProtoData(kortex_driver::DesiredSpeeds input, Kinova::Api::ControlConfig::DesiredSpeeds *output); +int ToProtoData(kortex_driver::LinearTwist input, Kinova::Api::ControlConfig::LinearTwist *output); +int ToProtoData(kortex_driver::AngularTwist input, Kinova::Api::ControlConfig::AngularTwist *output); +int ToProtoData(kortex_driver::ControlConfig_JointSpeeds input, Kinova::Api::ControlConfig::JointSpeeds *output); +int ToProtoData(kortex_driver::ControlConfig_ControlModeInformation input, Kinova::Api::ControlConfig::ControlModeInformation *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_ros_converter.h new file mode 100644 index 0000000..6fd389f --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_ros_converter.h @@ -0,0 +1,83 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_CONTROLCONFIG_ROS_CONVERTER_H_ +#define _KORTEX_CONTROLCONFIG_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/GravityVector.h" +#include "kortex_driver/ControlConfig_Position.h" +#include "kortex_driver/PayloadInformation.h" +#include "kortex_driver/CartesianTransform.h" +#include "kortex_driver/ToolConfiguration.h" +#include "kortex_driver/ControlConfigurationNotification.h" +#include "kortex_driver/CartesianReferenceFrameInfo.h" +#include "kortex_driver/TwistLinearSoftLimit.h" +#include "kortex_driver/TwistAngularSoftLimit.h" +#include "kortex_driver/JointSpeedSoftLimits.h" +#include "kortex_driver/JointAccelerationSoftLimits.h" +#include "kortex_driver/KinematicLimits.h" +#include "kortex_driver/KinematicLimitsList.h" +#include "kortex_driver/DesiredSpeeds.h" +#include "kortex_driver/LinearTwist.h" +#include "kortex_driver/AngularTwist.h" +#include "kortex_driver/ControlConfig_JointSpeeds.h" +#include "kortex_driver/ControlConfig_ControlModeInformation.h" + + +int ToRosData(Kinova::Api::ControlConfig::GravityVector input, kortex_driver::GravityVector &output); +int ToRosData(Kinova::Api::ControlConfig::Position input, kortex_driver::ControlConfig_Position &output); +int ToRosData(Kinova::Api::ControlConfig::PayloadInformation input, kortex_driver::PayloadInformation &output); +int ToRosData(Kinova::Api::ControlConfig::CartesianTransform input, kortex_driver::CartesianTransform &output); +int ToRosData(Kinova::Api::ControlConfig::ToolConfiguration input, kortex_driver::ToolConfiguration &output); +int ToRosData(Kinova::Api::ControlConfig::ControlConfigurationNotification input, kortex_driver::ControlConfigurationNotification &output); +int ToRosData(Kinova::Api::ControlConfig::CartesianReferenceFrameInfo input, kortex_driver::CartesianReferenceFrameInfo &output); +int ToRosData(Kinova::Api::ControlConfig::TwistLinearSoftLimit input, kortex_driver::TwistLinearSoftLimit &output); +int ToRosData(Kinova::Api::ControlConfig::TwistAngularSoftLimit input, kortex_driver::TwistAngularSoftLimit &output); +int ToRosData(Kinova::Api::ControlConfig::JointSpeedSoftLimits input, kortex_driver::JointSpeedSoftLimits &output); +int ToRosData(Kinova::Api::ControlConfig::JointAccelerationSoftLimits input, kortex_driver::JointAccelerationSoftLimits &output); +int ToRosData(Kinova::Api::ControlConfig::KinematicLimits input, kortex_driver::KinematicLimits &output); +int ToRosData(Kinova::Api::ControlConfig::KinematicLimitsList input, kortex_driver::KinematicLimitsList &output); +int ToRosData(Kinova::Api::ControlConfig::DesiredSpeeds input, kortex_driver::DesiredSpeeds &output); +int ToRosData(Kinova::Api::ControlConfig::LinearTwist input, kortex_driver::LinearTwist &output); +int ToRosData(Kinova::Api::ControlConfig::AngularTwist input, kortex_driver::AngularTwist &output); +int ToRosData(Kinova::Api::ControlConfig::JointSpeeds input, kortex_driver::ControlConfig_JointSpeeds &output); +int ToRosData(Kinova::Api::ControlConfig::ControlModeInformation input, kortex_driver::ControlConfig_ControlModeInformation &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_services.h new file mode 100644 index 0000000..e4adde3 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/controlconfig_services.h @@ -0,0 +1,71 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_CONTROLCONFIG_ROBOT_SERVICES_H_ +#define _KORTEX_CONTROLCONFIG_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/controlconfig_services_interface.h" + +#include +#include + +using namespace std; + +class ControlConfigRobotServices : public IControlConfigServices +{ + public: + ControlConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::ControlConfig::ControlConfigClient* controlconfig, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool SetGravityVector(kortex_driver::SetGravityVector::Request &req, kortex_driver::SetGravityVector::Response &res) override; + virtual bool GetGravityVector(kortex_driver::GetGravityVector::Request &req, kortex_driver::GetGravityVector::Response &res) override; + virtual bool SetPayloadInformation(kortex_driver::SetPayloadInformation::Request &req, kortex_driver::SetPayloadInformation::Response &res) override; + virtual bool GetPayloadInformation(kortex_driver::GetPayloadInformation::Request &req, kortex_driver::GetPayloadInformation::Response &res) override; + virtual bool SetToolConfiguration(kortex_driver::SetToolConfiguration::Request &req, kortex_driver::SetToolConfiguration::Response &res) override; + virtual bool GetToolConfiguration(kortex_driver::GetToolConfiguration::Request &req, kortex_driver::GetToolConfiguration::Response &res) override; + virtual bool OnNotificationControlConfigurationTopic(kortex_driver::OnNotificationControlConfigurationTopic::Request &req, kortex_driver::OnNotificationControlConfigurationTopic::Response &res) override; + virtual void cb_ControlConfigurationTopic(Kinova::Api::ControlConfig::ControlConfigurationNotification notif) override; + virtual bool ControlConfig_Unsubscribe(kortex_driver::ControlConfig_Unsubscribe::Request &req, kortex_driver::ControlConfig_Unsubscribe::Response &res) override; + virtual bool SetCartesianReferenceFrame(kortex_driver::SetCartesianReferenceFrame::Request &req, kortex_driver::SetCartesianReferenceFrame::Response &res) override; + virtual bool GetCartesianReferenceFrame(kortex_driver::GetCartesianReferenceFrame::Request &req, kortex_driver::GetCartesianReferenceFrame::Response &res) override; + virtual bool ControlConfig_GetControlMode(kortex_driver::ControlConfig_GetControlMode::Request &req, kortex_driver::ControlConfig_GetControlMode::Response &res) override; + virtual bool SetJointSpeedSoftLimits(kortex_driver::SetJointSpeedSoftLimits::Request &req, kortex_driver::SetJointSpeedSoftLimits::Response &res) override; + virtual bool SetTwistLinearSoftLimit(kortex_driver::SetTwistLinearSoftLimit::Request &req, kortex_driver::SetTwistLinearSoftLimit::Response &res) override; + virtual bool SetTwistAngularSoftLimit(kortex_driver::SetTwistAngularSoftLimit::Request &req, kortex_driver::SetTwistAngularSoftLimit::Response &res) override; + virtual bool SetJointAccelerationSoftLimits(kortex_driver::SetJointAccelerationSoftLimits::Request &req, kortex_driver::SetJointAccelerationSoftLimits::Response &res) override; + virtual bool GetKinematicHardLimits(kortex_driver::GetKinematicHardLimits::Request &req, kortex_driver::GetKinematicHardLimits::Response &res) override; + virtual bool GetKinematicSoftLimits(kortex_driver::GetKinematicSoftLimits::Request &req, kortex_driver::GetKinematicSoftLimits::Response &res) override; + virtual bool GetAllKinematicSoftLimits(kortex_driver::GetAllKinematicSoftLimits::Request &req, kortex_driver::GetAllKinematicSoftLimits::Response &res) override; + virtual bool SetDesiredLinearTwist(kortex_driver::SetDesiredLinearTwist::Request &req, kortex_driver::SetDesiredLinearTwist::Response &res) override; + virtual bool SetDesiredAngularTwist(kortex_driver::SetDesiredAngularTwist::Request &req, kortex_driver::SetDesiredAngularTwist::Response &res) override; + virtual bool SetDesiredJointSpeeds(kortex_driver::SetDesiredJointSpeeds::Request &req, kortex_driver::SetDesiredJointSpeeds::Response &res) override; + virtual bool GetDesiredSpeeds(kortex_driver::GetDesiredSpeeds::Request &req, kortex_driver::GetDesiredSpeeds::Response &res) override; + virtual bool ResetGravityVector(kortex_driver::ResetGravityVector::Request &req, kortex_driver::ResetGravityVector::Response &res) override; + virtual bool ResetPayloadInformation(kortex_driver::ResetPayloadInformation::Request &req, kortex_driver::ResetPayloadInformation::Response &res) override; + virtual bool ResetToolConfiguration(kortex_driver::ResetToolConfiguration::Request &req, kortex_driver::ResetToolConfiguration::Response &res) override; + virtual bool ResetJointSpeedSoftLimits(kortex_driver::ResetJointSpeedSoftLimits::Request &req, kortex_driver::ResetJointSpeedSoftLimits::Response &res) override; + virtual bool ResetTwistLinearSoftLimit(kortex_driver::ResetTwistLinearSoftLimit::Request &req, kortex_driver::ResetTwistLinearSoftLimit::Response &res) override; + virtual bool ResetTwistAngularSoftLimit(kortex_driver::ResetTwistAngularSoftLimit::Request &req, kortex_driver::ResetTwistAngularSoftLimit::Response &res) override; + virtual bool ResetJointAccelerationSoftLimits(kortex_driver::ResetJointAccelerationSoftLimits::Request &req, kortex_driver::ResetJointAccelerationSoftLimits::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::ControlConfig::ControlConfigClient* m_controlconfig; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_proto_converter.h new file mode 100644 index 0000000..6744825 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_proto_converter.h @@ -0,0 +1,97 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICECONFIG_PROTO_CONVERTER_H_ +#define _KORTEX_DEVICECONFIG_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/DeviceType.h" +#include "kortex_driver/RunMode.h" +#include "kortex_driver/FirmwareVersion.h" +#include "kortex_driver/BootloaderVersion.h" +#include "kortex_driver/ModelNumber.h" +#include "kortex_driver/PartNumber.h" +#include "kortex_driver/SerialNumber.h" +#include "kortex_driver/MACAddress.h" +#include "kortex_driver/IPv4Settings.h" +#include "kortex_driver/PartNumberRevision.h" +#include "kortex_driver/PowerOnSelfTestResult.h" +#include "kortex_driver/RebootRqst.h" +#include "kortex_driver/SafetyInformation.h" +#include "kortex_driver/SafetyInformationList.h" +#include "kortex_driver/SafetyEnable.h" +#include "kortex_driver/SafetyThreshold.h" +#include "kortex_driver/SafetyConfiguration.h" +#include "kortex_driver/SafetyConfigurationList.h" +#include "kortex_driver/SafetyStatus.h" +#include "kortex_driver/CalibrationParameter.h" +#include "kortex_driver/Calibration.h" +#include "kortex_driver/CalibrationElement.h" +#include "kortex_driver/CalibrationResult.h" +#include "kortex_driver/DeviceConfig_CapSenseConfig.h" +#include "kortex_driver/CapSenseRegister.h" + + +int ToProtoData(kortex_driver::DeviceType input, Kinova::Api::DeviceConfig::DeviceType *output); +int ToProtoData(kortex_driver::RunMode input, Kinova::Api::DeviceConfig::RunMode *output); +int ToProtoData(kortex_driver::FirmwareVersion input, Kinova::Api::DeviceConfig::FirmwareVersion *output); +int ToProtoData(kortex_driver::BootloaderVersion input, Kinova::Api::DeviceConfig::BootloaderVersion *output); +int ToProtoData(kortex_driver::ModelNumber input, Kinova::Api::DeviceConfig::ModelNumber *output); +int ToProtoData(kortex_driver::PartNumber input, Kinova::Api::DeviceConfig::PartNumber *output); +int ToProtoData(kortex_driver::SerialNumber input, Kinova::Api::DeviceConfig::SerialNumber *output); +int ToProtoData(kortex_driver::MACAddress input, Kinova::Api::DeviceConfig::MACAddress *output); +int ToProtoData(kortex_driver::IPv4Settings input, Kinova::Api::DeviceConfig::IPv4Settings *output); +int ToProtoData(kortex_driver::PartNumberRevision input, Kinova::Api::DeviceConfig::PartNumberRevision *output); +int ToProtoData(kortex_driver::PowerOnSelfTestResult input, Kinova::Api::DeviceConfig::PowerOnSelfTestResult *output); +int ToProtoData(kortex_driver::RebootRqst input, Kinova::Api::DeviceConfig::RebootRqst *output); +int ToProtoData(kortex_driver::SafetyInformation input, Kinova::Api::DeviceConfig::SafetyInformation *output); +int ToProtoData(kortex_driver::SafetyInformationList input, Kinova::Api::DeviceConfig::SafetyInformationList *output); +int ToProtoData(kortex_driver::SafetyEnable input, Kinova::Api::DeviceConfig::SafetyEnable *output); +int ToProtoData(kortex_driver::SafetyThreshold input, Kinova::Api::DeviceConfig::SafetyThreshold *output); +int ToProtoData(kortex_driver::SafetyConfiguration input, Kinova::Api::DeviceConfig::SafetyConfiguration *output); +int ToProtoData(kortex_driver::SafetyConfigurationList input, Kinova::Api::DeviceConfig::SafetyConfigurationList *output); +int ToProtoData(kortex_driver::SafetyStatus input, Kinova::Api::DeviceConfig::SafetyStatus *output); +int ToProtoData(kortex_driver::CalibrationParameter input, Kinova::Api::DeviceConfig::CalibrationParameter *output); +int ToProtoData(kortex_driver::Calibration input, Kinova::Api::DeviceConfig::Calibration *output); +int ToProtoData(kortex_driver::CalibrationElement input, Kinova::Api::DeviceConfig::CalibrationElement *output); +int ToProtoData(kortex_driver::CalibrationResult input, Kinova::Api::DeviceConfig::CalibrationResult *output); +int ToProtoData(kortex_driver::DeviceConfig_CapSenseConfig input, Kinova::Api::DeviceConfig::CapSenseConfig *output); +int ToProtoData(kortex_driver::CapSenseRegister input, Kinova::Api::DeviceConfig::CapSenseRegister *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_ros_converter.h new file mode 100644 index 0000000..9dbe819 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_ros_converter.h @@ -0,0 +1,97 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICECONFIG_ROS_CONVERTER_H_ +#define _KORTEX_DEVICECONFIG_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/DeviceType.h" +#include "kortex_driver/RunMode.h" +#include "kortex_driver/FirmwareVersion.h" +#include "kortex_driver/BootloaderVersion.h" +#include "kortex_driver/ModelNumber.h" +#include "kortex_driver/PartNumber.h" +#include "kortex_driver/SerialNumber.h" +#include "kortex_driver/MACAddress.h" +#include "kortex_driver/IPv4Settings.h" +#include "kortex_driver/PartNumberRevision.h" +#include "kortex_driver/PowerOnSelfTestResult.h" +#include "kortex_driver/RebootRqst.h" +#include "kortex_driver/SafetyInformation.h" +#include "kortex_driver/SafetyInformationList.h" +#include "kortex_driver/SafetyEnable.h" +#include "kortex_driver/SafetyThreshold.h" +#include "kortex_driver/SafetyConfiguration.h" +#include "kortex_driver/SafetyConfigurationList.h" +#include "kortex_driver/SafetyStatus.h" +#include "kortex_driver/CalibrationParameter.h" +#include "kortex_driver/Calibration.h" +#include "kortex_driver/CalibrationElement.h" +#include "kortex_driver/CalibrationResult.h" +#include "kortex_driver/DeviceConfig_CapSenseConfig.h" +#include "kortex_driver/CapSenseRegister.h" + + +int ToRosData(Kinova::Api::DeviceConfig::DeviceType input, kortex_driver::DeviceType &output); +int ToRosData(Kinova::Api::DeviceConfig::RunMode input, kortex_driver::RunMode &output); +int ToRosData(Kinova::Api::DeviceConfig::FirmwareVersion input, kortex_driver::FirmwareVersion &output); +int ToRosData(Kinova::Api::DeviceConfig::BootloaderVersion input, kortex_driver::BootloaderVersion &output); +int ToRosData(Kinova::Api::DeviceConfig::ModelNumber input, kortex_driver::ModelNumber &output); +int ToRosData(Kinova::Api::DeviceConfig::PartNumber input, kortex_driver::PartNumber &output); +int ToRosData(Kinova::Api::DeviceConfig::SerialNumber input, kortex_driver::SerialNumber &output); +int ToRosData(Kinova::Api::DeviceConfig::MACAddress input, kortex_driver::MACAddress &output); +int ToRosData(Kinova::Api::DeviceConfig::IPv4Settings input, kortex_driver::IPv4Settings &output); +int ToRosData(Kinova::Api::DeviceConfig::PartNumberRevision input, kortex_driver::PartNumberRevision &output); +int ToRosData(Kinova::Api::DeviceConfig::PowerOnSelfTestResult input, kortex_driver::PowerOnSelfTestResult &output); +int ToRosData(Kinova::Api::DeviceConfig::RebootRqst input, kortex_driver::RebootRqst &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyInformation input, kortex_driver::SafetyInformation &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyInformationList input, kortex_driver::SafetyInformationList &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyEnable input, kortex_driver::SafetyEnable &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyThreshold input, kortex_driver::SafetyThreshold &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyConfiguration input, kortex_driver::SafetyConfiguration &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyConfigurationList input, kortex_driver::SafetyConfigurationList &output); +int ToRosData(Kinova::Api::DeviceConfig::SafetyStatus input, kortex_driver::SafetyStatus &output); +int ToRosData(Kinova::Api::DeviceConfig::CalibrationParameter input, kortex_driver::CalibrationParameter &output); +int ToRosData(Kinova::Api::DeviceConfig::Calibration input, kortex_driver::Calibration &output); +int ToRosData(Kinova::Api::DeviceConfig::CalibrationElement input, kortex_driver::CalibrationElement &output); +int ToRosData(Kinova::Api::DeviceConfig::CalibrationResult input, kortex_driver::CalibrationResult &output); +int ToRosData(Kinova::Api::DeviceConfig::CapSenseConfig input, kortex_driver::DeviceConfig_CapSenseConfig &output); +int ToRosData(Kinova::Api::DeviceConfig::CapSenseRegister input, kortex_driver::CapSenseRegister &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_services.h new file mode 100644 index 0000000..fb87a13 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/deviceconfig_services.h @@ -0,0 +1,74 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICECONFIG_ROBOT_SERVICES_H_ +#define _KORTEX_DEVICECONFIG_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/deviceconfig_services_interface.h" + +#include +#include + +using namespace std; + +class DeviceConfigRobotServices : public IDeviceConfigServices +{ + public: + DeviceConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::DeviceConfig::DeviceConfigClient* deviceconfig, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool GetRunMode(kortex_driver::GetRunMode::Request &req, kortex_driver::GetRunMode::Response &res) override; + virtual bool SetRunMode(kortex_driver::SetRunMode::Request &req, kortex_driver::SetRunMode::Response &res) override; + virtual bool GetDeviceType(kortex_driver::GetDeviceType::Request &req, kortex_driver::GetDeviceType::Response &res) override; + virtual bool GetFirmwareVersion(kortex_driver::GetFirmwareVersion::Request &req, kortex_driver::GetFirmwareVersion::Response &res) override; + virtual bool GetBootloaderVersion(kortex_driver::GetBootloaderVersion::Request &req, kortex_driver::GetBootloaderVersion::Response &res) override; + virtual bool GetModelNumber(kortex_driver::GetModelNumber::Request &req, kortex_driver::GetModelNumber::Response &res) override; + virtual bool GetPartNumber(kortex_driver::GetPartNumber::Request &req, kortex_driver::GetPartNumber::Response &res) override; + virtual bool GetSerialNumber(kortex_driver::GetSerialNumber::Request &req, kortex_driver::GetSerialNumber::Response &res) override; + virtual bool GetMACAddress(kortex_driver::GetMACAddress::Request &req, kortex_driver::GetMACAddress::Response &res) override; + virtual bool GetIPv4Settings(kortex_driver::GetIPv4Settings::Request &req, kortex_driver::GetIPv4Settings::Response &res) override; + virtual bool SetIPv4Settings(kortex_driver::SetIPv4Settings::Request &req, kortex_driver::SetIPv4Settings::Response &res) override; + virtual bool GetPartNumberRevision(kortex_driver::GetPartNumberRevision::Request &req, kortex_driver::GetPartNumberRevision::Response &res) override; + virtual bool RebootRequest(kortex_driver::RebootRequest::Request &req, kortex_driver::RebootRequest::Response &res) override; + virtual bool SetSafetyEnable(kortex_driver::SetSafetyEnable::Request &req, kortex_driver::SetSafetyEnable::Response &res) override; + virtual bool SetSafetyErrorThreshold(kortex_driver::SetSafetyErrorThreshold::Request &req, kortex_driver::SetSafetyErrorThreshold::Response &res) override; + virtual bool SetSafetyWarningThreshold(kortex_driver::SetSafetyWarningThreshold::Request &req, kortex_driver::SetSafetyWarningThreshold::Response &res) override; + virtual bool SetSafetyConfiguration(kortex_driver::SetSafetyConfiguration::Request &req, kortex_driver::SetSafetyConfiguration::Response &res) override; + virtual bool GetSafetyConfiguration(kortex_driver::GetSafetyConfiguration::Request &req, kortex_driver::GetSafetyConfiguration::Response &res) override; + virtual bool GetSafetyInformation(kortex_driver::GetSafetyInformation::Request &req, kortex_driver::GetSafetyInformation::Response &res) override; + virtual bool GetSafetyEnable(kortex_driver::GetSafetyEnable::Request &req, kortex_driver::GetSafetyEnable::Response &res) override; + virtual bool GetSafetyStatus(kortex_driver::GetSafetyStatus::Request &req, kortex_driver::GetSafetyStatus::Response &res) override; + virtual bool ClearAllSafetyStatus(kortex_driver::ClearAllSafetyStatus::Request &req, kortex_driver::ClearAllSafetyStatus::Response &res) override; + virtual bool ClearSafetyStatus(kortex_driver::ClearSafetyStatus::Request &req, kortex_driver::ClearSafetyStatus::Response &res) override; + virtual bool GetAllSafetyConfiguration(kortex_driver::GetAllSafetyConfiguration::Request &req, kortex_driver::GetAllSafetyConfiguration::Response &res) override; + virtual bool GetAllSafetyInformation(kortex_driver::GetAllSafetyInformation::Request &req, kortex_driver::GetAllSafetyInformation::Response &res) override; + virtual bool ResetSafetyDefaults(kortex_driver::ResetSafetyDefaults::Request &req, kortex_driver::ResetSafetyDefaults::Response &res) override; + virtual bool OnNotificationSafetyTopic(kortex_driver::OnNotificationSafetyTopic::Request &req, kortex_driver::OnNotificationSafetyTopic::Response &res) override; + virtual void cb_SafetyTopic(Kinova::Api::Common::SafetyNotification notif) override; + virtual bool ExecuteCalibration(kortex_driver::ExecuteCalibration::Request &req, kortex_driver::ExecuteCalibration::Response &res) override; + virtual bool GetCalibrationResult(kortex_driver::GetCalibrationResult::Request &req, kortex_driver::GetCalibrationResult::Response &res) override; + virtual bool StopCalibration(kortex_driver::StopCalibration::Request &req, kortex_driver::StopCalibration::Response &res) override; + virtual bool DeviceConfig_SetCapSenseConfig(kortex_driver::DeviceConfig_SetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_SetCapSenseConfig::Response &res) override; + virtual bool DeviceConfig_GetCapSenseConfig(kortex_driver::DeviceConfig_GetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_GetCapSenseConfig::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::DeviceConfig::DeviceConfigClient* m_deviceconfig; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_proto_converter.h new file mode 100644 index 0000000..42e63e7 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_proto_converter.h @@ -0,0 +1,49 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICEMANAGER_PROTO_CONVERTER_H_ +#define _KORTEX_DEVICEMANAGER_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/DeviceHandles.h" + + +int ToProtoData(kortex_driver::DeviceHandles input, Kinova::Api::DeviceManager::DeviceHandles *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_ros_converter.h new file mode 100644 index 0000000..3847a80 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_ros_converter.h @@ -0,0 +1,49 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICEMANAGER_ROS_CONVERTER_H_ +#define _KORTEX_DEVICEMANAGER_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/DeviceHandles.h" + + +int ToRosData(Kinova::Api::DeviceManager::DeviceHandles input, kortex_driver::DeviceHandles &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_services.h new file mode 100644 index 0000000..26443ec --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/devicemanager_services.h @@ -0,0 +1,42 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICEMANAGER_ROBOT_SERVICES_H_ +#define _KORTEX_DEVICEMANAGER_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/devicemanager_services_interface.h" + +#include +#include + +using namespace std; + +class DeviceManagerRobotServices : public IDeviceManagerServices +{ + public: + DeviceManagerRobotServices(ros::NodeHandle& node_handle, Kinova::Api::DeviceManager::DeviceManagerClient* devicemanager, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool ReadAllDevices(kortex_driver::ReadAllDevices::Request &req, kortex_driver::ReadAllDevices::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::DeviceManager::DeviceManagerClient* m_devicemanager; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/grippercyclic_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/grippercyclic_proto_converter.h new file mode 100644 index 0000000..9a696f5 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/grippercyclic_proto_converter.h @@ -0,0 +1,61 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_GRIPPERCYCLIC_PROTO_CONVERTER_H_ +#define _KORTEX_GRIPPERCYCLIC_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/GripperCyclic_MessageId.h" +#include "kortex_driver/MotorCommand.h" +#include "kortex_driver/GripperCyclic_Command.h" +#include "kortex_driver/MotorFeedback.h" +#include "kortex_driver/GripperCyclic_Feedback.h" +#include "kortex_driver/CustomDataUnit.h" +#include "kortex_driver/GripperCyclic_CustomData.h" + + +int ToProtoData(kortex_driver::GripperCyclic_MessageId input, Kinova::Api::GripperCyclic::MessageId *output); +int ToProtoData(kortex_driver::MotorCommand input, Kinova::Api::GripperCyclic::MotorCommand *output); +int ToProtoData(kortex_driver::GripperCyclic_Command input, Kinova::Api::GripperCyclic::Command *output); +int ToProtoData(kortex_driver::MotorFeedback input, Kinova::Api::GripperCyclic::MotorFeedback *output); +int ToProtoData(kortex_driver::GripperCyclic_Feedback input, Kinova::Api::GripperCyclic::Feedback *output); +int ToProtoData(kortex_driver::CustomDataUnit input, Kinova::Api::GripperCyclic::CustomDataUnit *output); +int ToProtoData(kortex_driver::GripperCyclic_CustomData input, Kinova::Api::GripperCyclic::CustomData *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/grippercyclic_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/grippercyclic_ros_converter.h new file mode 100644 index 0000000..a584b91 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/grippercyclic_ros_converter.h @@ -0,0 +1,61 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_GRIPPERCYCLIC_ROS_CONVERTER_H_ +#define _KORTEX_GRIPPERCYCLIC_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/GripperCyclic_MessageId.h" +#include "kortex_driver/MotorCommand.h" +#include "kortex_driver/GripperCyclic_Command.h" +#include "kortex_driver/MotorFeedback.h" +#include "kortex_driver/GripperCyclic_Feedback.h" +#include "kortex_driver/CustomDataUnit.h" +#include "kortex_driver/GripperCyclic_CustomData.h" + + +int ToRosData(Kinova::Api::GripperCyclic::MessageId input, kortex_driver::GripperCyclic_MessageId &output); +int ToRosData(Kinova::Api::GripperCyclic::MotorCommand input, kortex_driver::MotorCommand &output); +int ToRosData(Kinova::Api::GripperCyclic::Command input, kortex_driver::GripperCyclic_Command &output); +int ToRosData(Kinova::Api::GripperCyclic::MotorFeedback input, kortex_driver::MotorFeedback &output); +int ToRosData(Kinova::Api::GripperCyclic::Feedback input, kortex_driver::GripperCyclic_Feedback &output); +int ToRosData(Kinova::Api::GripperCyclic::CustomDataUnit input, kortex_driver::CustomDataUnit &output); +int ToRosData(Kinova::Api::GripperCyclic::CustomData input, kortex_driver::GripperCyclic_CustomData &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_proto_converter.h new file mode 100644 index 0000000..4b201c0 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_proto_converter.h @@ -0,0 +1,71 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCONFIG_PROTO_CONVERTER_H_ +#define _KORTEX_INTERCONNECTCONFIG_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/EthernetDeviceIdentification.h" +#include "kortex_driver/EthernetConfiguration.h" +#include "kortex_driver/GPIOIdentification.h" +#include "kortex_driver/GPIOConfiguration.h" +#include "kortex_driver/GPIOState.h" +#include "kortex_driver/I2CDeviceIdentification.h" +#include "kortex_driver/I2CConfiguration.h" +#include "kortex_driver/I2CReadParameter.h" +#include "kortex_driver/I2CReadRegisterParameter.h" +#include "kortex_driver/I2CWriteParameter.h" +#include "kortex_driver/I2CWriteRegisterParameter.h" +#include "kortex_driver/I2CData.h" + + +int ToProtoData(kortex_driver::EthernetDeviceIdentification input, Kinova::Api::InterconnectConfig::EthernetDeviceIdentification *output); +int ToProtoData(kortex_driver::EthernetConfiguration input, Kinova::Api::InterconnectConfig::EthernetConfiguration *output); +int ToProtoData(kortex_driver::GPIOIdentification input, Kinova::Api::InterconnectConfig::GPIOIdentification *output); +int ToProtoData(kortex_driver::GPIOConfiguration input, Kinova::Api::InterconnectConfig::GPIOConfiguration *output); +int ToProtoData(kortex_driver::GPIOState input, Kinova::Api::InterconnectConfig::GPIOState *output); +int ToProtoData(kortex_driver::I2CDeviceIdentification input, Kinova::Api::InterconnectConfig::I2CDeviceIdentification *output); +int ToProtoData(kortex_driver::I2CConfiguration input, Kinova::Api::InterconnectConfig::I2CConfiguration *output); +int ToProtoData(kortex_driver::I2CReadParameter input, Kinova::Api::InterconnectConfig::I2CReadParameter *output); +int ToProtoData(kortex_driver::I2CReadRegisterParameter input, Kinova::Api::InterconnectConfig::I2CReadRegisterParameter *output); +int ToProtoData(kortex_driver::I2CWriteParameter input, Kinova::Api::InterconnectConfig::I2CWriteParameter *output); +int ToProtoData(kortex_driver::I2CWriteRegisterParameter input, Kinova::Api::InterconnectConfig::I2CWriteRegisterParameter *output); +int ToProtoData(kortex_driver::I2CData input, Kinova::Api::InterconnectConfig::I2CData *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_ros_converter.h new file mode 100644 index 0000000..f155cf6 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_ros_converter.h @@ -0,0 +1,71 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCONFIG_ROS_CONVERTER_H_ +#define _KORTEX_INTERCONNECTCONFIG_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/EthernetDeviceIdentification.h" +#include "kortex_driver/EthernetConfiguration.h" +#include "kortex_driver/GPIOIdentification.h" +#include "kortex_driver/GPIOConfiguration.h" +#include "kortex_driver/GPIOState.h" +#include "kortex_driver/I2CDeviceIdentification.h" +#include "kortex_driver/I2CConfiguration.h" +#include "kortex_driver/I2CReadParameter.h" +#include "kortex_driver/I2CReadRegisterParameter.h" +#include "kortex_driver/I2CWriteParameter.h" +#include "kortex_driver/I2CWriteRegisterParameter.h" +#include "kortex_driver/I2CData.h" + + +int ToRosData(Kinova::Api::InterconnectConfig::EthernetDeviceIdentification input, kortex_driver::EthernetDeviceIdentification &output); +int ToRosData(Kinova::Api::InterconnectConfig::EthernetConfiguration input, kortex_driver::EthernetConfiguration &output); +int ToRosData(Kinova::Api::InterconnectConfig::GPIOIdentification input, kortex_driver::GPIOIdentification &output); +int ToRosData(Kinova::Api::InterconnectConfig::GPIOConfiguration input, kortex_driver::GPIOConfiguration &output); +int ToRosData(Kinova::Api::InterconnectConfig::GPIOState input, kortex_driver::GPIOState &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CDeviceIdentification input, kortex_driver::I2CDeviceIdentification &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CConfiguration input, kortex_driver::I2CConfiguration &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CReadParameter input, kortex_driver::I2CReadParameter &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CReadRegisterParameter input, kortex_driver::I2CReadRegisterParameter &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CWriteParameter input, kortex_driver::I2CWriteParameter &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CWriteRegisterParameter input, kortex_driver::I2CWriteRegisterParameter &output); +int ToRosData(Kinova::Api::InterconnectConfig::I2CData input, kortex_driver::I2CData &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_services.h new file mode 100644 index 0000000..a4f360e --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectconfig_services.h @@ -0,0 +1,55 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCONFIG_ROBOT_SERVICES_H_ +#define _KORTEX_INTERCONNECTCONFIG_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/interconnectconfig_services_interface.h" + +#include +#include + +using namespace std; + +class InterconnectConfigRobotServices : public IInterconnectConfigServices +{ + public: + InterconnectConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::InterconnectConfig::InterconnectConfigClient* interconnectconfig, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool GetUARTConfiguration(kortex_driver::GetUARTConfiguration::Request &req, kortex_driver::GetUARTConfiguration::Response &res) override; + virtual bool SetUARTConfiguration(kortex_driver::SetUARTConfiguration::Request &req, kortex_driver::SetUARTConfiguration::Response &res) override; + virtual bool GetEthernetConfiguration(kortex_driver::GetEthernetConfiguration::Request &req, kortex_driver::GetEthernetConfiguration::Response &res) override; + virtual bool SetEthernetConfiguration(kortex_driver::SetEthernetConfiguration::Request &req, kortex_driver::SetEthernetConfiguration::Response &res) override; + virtual bool GetGPIOConfiguration(kortex_driver::GetGPIOConfiguration::Request &req, kortex_driver::GetGPIOConfiguration::Response &res) override; + virtual bool SetGPIOConfiguration(kortex_driver::SetGPIOConfiguration::Request &req, kortex_driver::SetGPIOConfiguration::Response &res) override; + virtual bool GetGPIOState(kortex_driver::GetGPIOState::Request &req, kortex_driver::GetGPIOState::Response &res) override; + virtual bool SetGPIOState(kortex_driver::SetGPIOState::Request &req, kortex_driver::SetGPIOState::Response &res) override; + virtual bool GetI2CConfiguration(kortex_driver::GetI2CConfiguration::Request &req, kortex_driver::GetI2CConfiguration::Response &res) override; + virtual bool SetI2CConfiguration(kortex_driver::SetI2CConfiguration::Request &req, kortex_driver::SetI2CConfiguration::Response &res) override; + virtual bool I2CRead(kortex_driver::I2CRead::Request &req, kortex_driver::I2CRead::Response &res) override; + virtual bool I2CReadRegister(kortex_driver::I2CReadRegister::Request &req, kortex_driver::I2CReadRegister::Response &res) override; + virtual bool I2CWrite(kortex_driver::I2CWrite::Request &req, kortex_driver::I2CWrite::Response &res) override; + virtual bool I2CWriteRegister(kortex_driver::I2CWriteRegister::Request &req, kortex_driver::I2CWriteRegister::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::InterconnectConfig::InterconnectConfigClient* m_interconnectconfig; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectcyclic_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectcyclic_proto_converter.h new file mode 100644 index 0000000..ad838be --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectcyclic_proto_converter.h @@ -0,0 +1,55 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCYCLIC_PROTO_CONVERTER_H_ +#define _KORTEX_INTERCONNECTCYCLIC_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/InterconnectCyclic_MessageId.h" +#include "kortex_driver/InterconnectCyclic_Command.h" +#include "kortex_driver/InterconnectCyclic_Feedback.h" +#include "kortex_driver/InterconnectCyclic_CustomData.h" + + +int ToProtoData(kortex_driver::InterconnectCyclic_MessageId input, Kinova::Api::InterconnectCyclic::MessageId *output); +int ToProtoData(kortex_driver::InterconnectCyclic_Command input, Kinova::Api::InterconnectCyclic::Command *output); +int ToProtoData(kortex_driver::InterconnectCyclic_Feedback input, Kinova::Api::InterconnectCyclic::Feedback *output); +int ToProtoData(kortex_driver::InterconnectCyclic_CustomData input, Kinova::Api::InterconnectCyclic::CustomData *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectcyclic_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectcyclic_ros_converter.h new file mode 100644 index 0000000..eefda5c --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/interconnectcyclic_ros_converter.h @@ -0,0 +1,55 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCYCLIC_ROS_CONVERTER_H_ +#define _KORTEX_INTERCONNECTCYCLIC_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/InterconnectCyclic_MessageId.h" +#include "kortex_driver/InterconnectCyclic_Command.h" +#include "kortex_driver/InterconnectCyclic_Feedback.h" +#include "kortex_driver/InterconnectCyclic_CustomData.h" + + +int ToRosData(Kinova::Api::InterconnectCyclic::MessageId input, kortex_driver::InterconnectCyclic_MessageId &output); +int ToRosData(Kinova::Api::InterconnectCyclic::Command input, kortex_driver::InterconnectCyclic_Command &output); +int ToRosData(Kinova::Api::InterconnectCyclic::Feedback input, kortex_driver::InterconnectCyclic_Feedback &output); +int ToRosData(Kinova::Api::InterconnectCyclic::CustomData input, kortex_driver::InterconnectCyclic_CustomData &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/productconfiguration_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/productconfiguration_proto_converter.h new file mode 100644 index 0000000..c40b896 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/productconfiguration_proto_converter.h @@ -0,0 +1,51 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_PRODUCTCONFIGURATION_PROTO_CONVERTER_H_ +#define _KORTEX_PRODUCTCONFIGURATION_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + + +#include "kortex_driver/CompleteProductConfiguration.h" +#include "kortex_driver/ProductConfigurationEndEffectorType.h" + + +int ToProtoData(kortex_driver::CompleteProductConfiguration input, Kinova::Api::ProductConfiguration::CompleteProductConfiguration *output); +int ToProtoData(kortex_driver::ProductConfigurationEndEffectorType input, Kinova::Api::ProductConfiguration::ProductConfigurationEndEffectorType *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/productconfiguration_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/productconfiguration_ros_converter.h new file mode 100644 index 0000000..757cc52 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/productconfiguration_ros_converter.h @@ -0,0 +1,51 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_PRODUCTCONFIGURATION_ROS_CONVERTER_H_ +#define _KORTEX_PRODUCTCONFIGURATION_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + + +#include "kortex_driver/CompleteProductConfiguration.h" +#include "kortex_driver/ProductConfigurationEndEffectorType.h" + + +int ToRosData(Kinova::Api::ProductConfiguration::CompleteProductConfiguration input, kortex_driver::CompleteProductConfiguration &output); +int ToRosData(Kinova::Api::ProductConfiguration::ProductConfigurationEndEffectorType input, kortex_driver::ProductConfigurationEndEffectorType &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_proto_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_proto_converter.h new file mode 100644 index 0000000..ed757cd --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_proto_converter.h @@ -0,0 +1,79 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_VISIONCONFIG_PROTO_CONVERTER_H_ +#define _KORTEX_VISIONCONFIG_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" + + +#include "kortex_driver/SensorSettings.h" +#include "kortex_driver/SensorIdentifier.h" +#include "kortex_driver/IntrinsicProfileIdentifier.h" +#include "kortex_driver/OptionIdentifier.h" +#include "kortex_driver/OptionValue.h" +#include "kortex_driver/OptionInformation.h" +#include "kortex_driver/SensorFocusAction.h" +#include "kortex_driver/FocusPoint.h" +#include "kortex_driver/ManualFocus.h" +#include "kortex_driver/VisionNotification.h" +#include "kortex_driver/IntrinsicParameters.h" +#include "kortex_driver/DistortionCoefficients.h" +#include "kortex_driver/ExtrinsicParameters.h" +#include "kortex_driver/VisionConfig_RotationMatrix.h" +#include "kortex_driver/VisionConfig_RotationMatrixRow.h" +#include "kortex_driver/TranslationVector.h" + + +int ToProtoData(kortex_driver::SensorSettings input, Kinova::Api::VisionConfig::SensorSettings *output); +int ToProtoData(kortex_driver::SensorIdentifier input, Kinova::Api::VisionConfig::SensorIdentifier *output); +int ToProtoData(kortex_driver::IntrinsicProfileIdentifier input, Kinova::Api::VisionConfig::IntrinsicProfileIdentifier *output); +int ToProtoData(kortex_driver::OptionIdentifier input, Kinova::Api::VisionConfig::OptionIdentifier *output); +int ToProtoData(kortex_driver::OptionValue input, Kinova::Api::VisionConfig::OptionValue *output); +int ToProtoData(kortex_driver::OptionInformation input, Kinova::Api::VisionConfig::OptionInformation *output); +int ToProtoData(kortex_driver::SensorFocusAction input, Kinova::Api::VisionConfig::SensorFocusAction *output); +int ToProtoData(kortex_driver::FocusPoint input, Kinova::Api::VisionConfig::FocusPoint *output); +int ToProtoData(kortex_driver::ManualFocus input, Kinova::Api::VisionConfig::ManualFocus *output); +int ToProtoData(kortex_driver::VisionNotification input, Kinova::Api::VisionConfig::VisionNotification *output); +int ToProtoData(kortex_driver::IntrinsicParameters input, Kinova::Api::VisionConfig::IntrinsicParameters *output); +int ToProtoData(kortex_driver::DistortionCoefficients input, Kinova::Api::VisionConfig::DistortionCoefficients *output); +int ToProtoData(kortex_driver::ExtrinsicParameters input, Kinova::Api::VisionConfig::ExtrinsicParameters *output); +int ToProtoData(kortex_driver::VisionConfig_RotationMatrix input, Kinova::Api::VisionConfig::RotationMatrix *output); +int ToProtoData(kortex_driver::VisionConfig_RotationMatrixRow input, Kinova::Api::VisionConfig::RotationMatrixRow *output); +int ToProtoData(kortex_driver::TranslationVector input, Kinova::Api::VisionConfig::TranslationVector *output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_ros_converter.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_ros_converter.h new file mode 100644 index 0000000..3d4a961 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_ros_converter.h @@ -0,0 +1,79 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_VISIONCONFIG_ROS_CONVERTER_H_ +#define _KORTEX_VISIONCONFIG_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include + +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" + + +#include "kortex_driver/SensorSettings.h" +#include "kortex_driver/SensorIdentifier.h" +#include "kortex_driver/IntrinsicProfileIdentifier.h" +#include "kortex_driver/OptionIdentifier.h" +#include "kortex_driver/OptionValue.h" +#include "kortex_driver/OptionInformation.h" +#include "kortex_driver/SensorFocusAction.h" +#include "kortex_driver/FocusPoint.h" +#include "kortex_driver/ManualFocus.h" +#include "kortex_driver/VisionNotification.h" +#include "kortex_driver/IntrinsicParameters.h" +#include "kortex_driver/DistortionCoefficients.h" +#include "kortex_driver/ExtrinsicParameters.h" +#include "kortex_driver/VisionConfig_RotationMatrix.h" +#include "kortex_driver/VisionConfig_RotationMatrixRow.h" +#include "kortex_driver/TranslationVector.h" + + +int ToRosData(Kinova::Api::VisionConfig::SensorSettings input, kortex_driver::SensorSettings &output); +int ToRosData(Kinova::Api::VisionConfig::SensorIdentifier input, kortex_driver::SensorIdentifier &output); +int ToRosData(Kinova::Api::VisionConfig::IntrinsicProfileIdentifier input, kortex_driver::IntrinsicProfileIdentifier &output); +int ToRosData(Kinova::Api::VisionConfig::OptionIdentifier input, kortex_driver::OptionIdentifier &output); +int ToRosData(Kinova::Api::VisionConfig::OptionValue input, kortex_driver::OptionValue &output); +int ToRosData(Kinova::Api::VisionConfig::OptionInformation input, kortex_driver::OptionInformation &output); +int ToRosData(Kinova::Api::VisionConfig::SensorFocusAction input, kortex_driver::SensorFocusAction &output); +int ToRosData(Kinova::Api::VisionConfig::FocusPoint input, kortex_driver::FocusPoint &output); +int ToRosData(Kinova::Api::VisionConfig::ManualFocus input, kortex_driver::ManualFocus &output); +int ToRosData(Kinova::Api::VisionConfig::VisionNotification input, kortex_driver::VisionNotification &output); +int ToRosData(Kinova::Api::VisionConfig::IntrinsicParameters input, kortex_driver::IntrinsicParameters &output); +int ToRosData(Kinova::Api::VisionConfig::DistortionCoefficients input, kortex_driver::DistortionCoefficients &output); +int ToRosData(Kinova::Api::VisionConfig::ExtrinsicParameters input, kortex_driver::ExtrinsicParameters &output); +int ToRosData(Kinova::Api::VisionConfig::RotationMatrix input, kortex_driver::VisionConfig_RotationMatrix &output); +int ToRosData(Kinova::Api::VisionConfig::RotationMatrixRow input, kortex_driver::VisionConfig_RotationMatrixRow &output); +int ToRosData(Kinova::Api::VisionConfig::TranslationVector input, kortex_driver::TranslationVector &output); + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_services.h new file mode 100644 index 0000000..32e0129 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/robot/visionconfig_services.h @@ -0,0 +1,54 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_VISIONCONFIG_ROBOT_SERVICES_H_ +#define _KORTEX_VISIONCONFIG_ROBOT_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/visionconfig_services_interface.h" + +#include +#include + +using namespace std; + +class VisionConfigRobotServices : public IVisionConfigServices +{ + public: + VisionConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::VisionConfig::VisionConfigClient* visionconfig, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + virtual bool SetSensorSettings(kortex_driver::SetSensorSettings::Request &req, kortex_driver::SetSensorSettings::Response &res) override; + virtual bool GetSensorSettings(kortex_driver::GetSensorSettings::Request &req, kortex_driver::GetSensorSettings::Response &res) override; + virtual bool GetOptionValue(kortex_driver::GetOptionValue::Request &req, kortex_driver::GetOptionValue::Response &res) override; + virtual bool SetOptionValue(kortex_driver::SetOptionValue::Request &req, kortex_driver::SetOptionValue::Response &res) override; + virtual bool GetOptionInformation(kortex_driver::GetOptionInformation::Request &req, kortex_driver::GetOptionInformation::Response &res) override; + virtual bool OnNotificationVisionTopic(kortex_driver::OnNotificationVisionTopic::Request &req, kortex_driver::OnNotificationVisionTopic::Response &res) override; + virtual void cb_VisionTopic(Kinova::Api::VisionConfig::VisionNotification notif) override; + virtual bool DoSensorFocusAction(kortex_driver::DoSensorFocusAction::Request &req, kortex_driver::DoSensorFocusAction::Response &res) override; + virtual bool GetIntrinsicParameters(kortex_driver::GetIntrinsicParameters::Request &req, kortex_driver::GetIntrinsicParameters::Response &res) override; + virtual bool GetIntrinsicParametersProfile(kortex_driver::GetIntrinsicParametersProfile::Request &req, kortex_driver::GetIntrinsicParametersProfile::Response &res) override; + virtual bool SetIntrinsicParameters(kortex_driver::SetIntrinsicParameters::Request &req, kortex_driver::SetIntrinsicParameters::Response &res) override; + virtual bool GetExtrinsicParameters(kortex_driver::GetExtrinsicParameters::Request &req, kortex_driver::GetExtrinsicParameters::Response &res) override; + virtual bool SetExtrinsicParameters(kortex_driver::SetExtrinsicParameters::Request &req, kortex_driver::SetExtrinsicParameters::Response &res) override; + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + Kinova::Api::VisionConfig::VisionConfigClient* m_visionconfig; +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/actuatorconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/actuatorconfig_services.h new file mode 100644 index 0000000..0a04e42 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/actuatorconfig_services.h @@ -0,0 +1,73 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_ACTUATORCONFIG_SIMULATION_SERVICES_H_ +#define _KORTEX_ACTUATORCONFIG_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/actuatorconfig_services_interface.h" + +using namespace std; + +class ActuatorConfigSimulationServices : public IActuatorConfigServices +{ + public: + ActuatorConfigSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function GetAxisOffsetsHandler = nullptr; + virtual bool GetAxisOffsets(kortex_driver::GetAxisOffsets::Request &req, kortex_driver::GetAxisOffsets::Response &res) override; + std::function SetAxisOffsetsHandler = nullptr; + virtual bool SetAxisOffsets(kortex_driver::SetAxisOffsets::Request &req, kortex_driver::SetAxisOffsets::Response &res) override; + std::function SetTorqueOffsetHandler = nullptr; + virtual bool SetTorqueOffset(kortex_driver::SetTorqueOffset::Request &req, kortex_driver::SetTorqueOffset::Response &res) override; + std::function ActuatorConfig_GetControlModeHandler = nullptr; + virtual bool ActuatorConfig_GetControlMode(kortex_driver::ActuatorConfig_GetControlMode::Request &req, kortex_driver::ActuatorConfig_GetControlMode::Response &res) override; + std::function SetControlModeHandler = nullptr; + virtual bool SetControlMode(kortex_driver::SetControlMode::Request &req, kortex_driver::SetControlMode::Response &res) override; + std::function GetActivatedControlLoopHandler = nullptr; + virtual bool GetActivatedControlLoop(kortex_driver::GetActivatedControlLoop::Request &req, kortex_driver::GetActivatedControlLoop::Response &res) override; + std::function SetActivatedControlLoopHandler = nullptr; + virtual bool SetActivatedControlLoop(kortex_driver::SetActivatedControlLoop::Request &req, kortex_driver::SetActivatedControlLoop::Response &res) override; + std::function GetControlLoopParametersHandler = nullptr; + virtual bool GetControlLoopParameters(kortex_driver::GetControlLoopParameters::Request &req, kortex_driver::GetControlLoopParameters::Response &res) override; + std::function SetControlLoopParametersHandler = nullptr; + virtual bool SetControlLoopParameters(kortex_driver::SetControlLoopParameters::Request &req, kortex_driver::SetControlLoopParameters::Response &res) override; + std::function SelectCustomDataHandler = nullptr; + virtual bool SelectCustomData(kortex_driver::SelectCustomData::Request &req, kortex_driver::SelectCustomData::Response &res) override; + std::function GetSelectedCustomDataHandler = nullptr; + virtual bool GetSelectedCustomData(kortex_driver::GetSelectedCustomData::Request &req, kortex_driver::GetSelectedCustomData::Response &res) override; + std::function SetCommandModeHandler = nullptr; + virtual bool SetCommandMode(kortex_driver::SetCommandMode::Request &req, kortex_driver::SetCommandMode::Response &res) override; + std::function ActuatorConfig_ClearFaultsHandler = nullptr; + virtual bool ActuatorConfig_ClearFaults(kortex_driver::ActuatorConfig_ClearFaults::Request &req, kortex_driver::ActuatorConfig_ClearFaults::Response &res) override; + std::function SetServoingHandler = nullptr; + virtual bool SetServoing(kortex_driver::SetServoing::Request &req, kortex_driver::SetServoing::Response &res) override; + std::function MoveToPositionHandler = nullptr; + virtual bool MoveToPosition(kortex_driver::MoveToPosition::Request &req, kortex_driver::MoveToPosition::Response &res) override; + std::function GetCommandModeHandler = nullptr; + virtual bool GetCommandMode(kortex_driver::GetCommandMode::Request &req, kortex_driver::GetCommandMode::Response &res) override; + std::function GetServoingHandler = nullptr; + virtual bool GetServoing(kortex_driver::GetServoing::Request &req, kortex_driver::GetServoing::Response &res) override; + std::function GetTorqueOffsetHandler = nullptr; + virtual bool GetTorqueOffset(kortex_driver::GetTorqueOffset::Request &req, kortex_driver::GetTorqueOffset::Response &res) override; + std::function SetCoggingFeedforwardModeHandler = nullptr; + virtual bool SetCoggingFeedforwardMode(kortex_driver::SetCoggingFeedforwardMode::Request &req, kortex_driver::SetCoggingFeedforwardMode::Response &res) override; + std::function GetCoggingFeedforwardModeHandler = nullptr; + virtual bool GetCoggingFeedforwardMode(kortex_driver::GetCoggingFeedforwardMode::Request &req, kortex_driver::GetCoggingFeedforwardMode::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/base_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/base_services.h new file mode 100644 index 0000000..6556675 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/base_services.h @@ -0,0 +1,335 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_BASE_SIMULATION_SERVICES_H_ +#define _KORTEX_BASE_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/base_services_interface.h" + +using namespace std; + +class BaseSimulationServices : public IBaseServices +{ + public: + BaseSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function CreateUserProfileHandler = nullptr; + virtual bool CreateUserProfile(kortex_driver::CreateUserProfile::Request &req, kortex_driver::CreateUserProfile::Response &res) override; + std::function UpdateUserProfileHandler = nullptr; + virtual bool UpdateUserProfile(kortex_driver::UpdateUserProfile::Request &req, kortex_driver::UpdateUserProfile::Response &res) override; + std::function ReadUserProfileHandler = nullptr; + virtual bool ReadUserProfile(kortex_driver::ReadUserProfile::Request &req, kortex_driver::ReadUserProfile::Response &res) override; + std::function DeleteUserProfileHandler = nullptr; + virtual bool DeleteUserProfile(kortex_driver::DeleteUserProfile::Request &req, kortex_driver::DeleteUserProfile::Response &res) override; + std::function ReadAllUserProfilesHandler = nullptr; + virtual bool ReadAllUserProfiles(kortex_driver::ReadAllUserProfiles::Request &req, kortex_driver::ReadAllUserProfiles::Response &res) override; + std::function ReadAllUsersHandler = nullptr; + virtual bool ReadAllUsers(kortex_driver::ReadAllUsers::Request &req, kortex_driver::ReadAllUsers::Response &res) override; + std::function ChangePasswordHandler = nullptr; + virtual bool ChangePassword(kortex_driver::ChangePassword::Request &req, kortex_driver::ChangePassword::Response &res) override; + std::function CreateSequenceHandler = nullptr; + virtual bool CreateSequence(kortex_driver::CreateSequence::Request &req, kortex_driver::CreateSequence::Response &res) override; + std::function UpdateSequenceHandler = nullptr; + virtual bool UpdateSequence(kortex_driver::UpdateSequence::Request &req, kortex_driver::UpdateSequence::Response &res) override; + std::function ReadSequenceHandler = nullptr; + virtual bool ReadSequence(kortex_driver::ReadSequence::Request &req, kortex_driver::ReadSequence::Response &res) override; + std::function DeleteSequenceHandler = nullptr; + virtual bool DeleteSequence(kortex_driver::DeleteSequence::Request &req, kortex_driver::DeleteSequence::Response &res) override; + std::function ReadAllSequencesHandler = nullptr; + virtual bool ReadAllSequences(kortex_driver::ReadAllSequences::Request &req, kortex_driver::ReadAllSequences::Response &res) override; + std::function PlaySequenceHandler = nullptr; + virtual bool PlaySequence(kortex_driver::PlaySequence::Request &req, kortex_driver::PlaySequence::Response &res) override; + std::function PlayAdvancedSequenceHandler = nullptr; + virtual bool PlayAdvancedSequence(kortex_driver::PlayAdvancedSequence::Request &req, kortex_driver::PlayAdvancedSequence::Response &res) override; + std::function StopSequenceHandler = nullptr; + virtual bool StopSequence(kortex_driver::StopSequence::Request &req, kortex_driver::StopSequence::Response &res) override; + std::function PauseSequenceHandler = nullptr; + virtual bool PauseSequence(kortex_driver::PauseSequence::Request &req, kortex_driver::PauseSequence::Response &res) override; + std::function ResumeSequenceHandler = nullptr; + virtual bool ResumeSequence(kortex_driver::ResumeSequence::Request &req, kortex_driver::ResumeSequence::Response &res) override; + std::function CreateProtectionZoneHandler = nullptr; + virtual bool CreateProtectionZone(kortex_driver::CreateProtectionZone::Request &req, kortex_driver::CreateProtectionZone::Response &res) override; + std::function UpdateProtectionZoneHandler = nullptr; + virtual bool UpdateProtectionZone(kortex_driver::UpdateProtectionZone::Request &req, kortex_driver::UpdateProtectionZone::Response &res) override; + std::function ReadProtectionZoneHandler = nullptr; + virtual bool ReadProtectionZone(kortex_driver::ReadProtectionZone::Request &req, kortex_driver::ReadProtectionZone::Response &res) override; + std::function DeleteProtectionZoneHandler = nullptr; + virtual bool DeleteProtectionZone(kortex_driver::DeleteProtectionZone::Request &req, kortex_driver::DeleteProtectionZone::Response &res) override; + std::function ReadAllProtectionZonesHandler = nullptr; + virtual bool ReadAllProtectionZones(kortex_driver::ReadAllProtectionZones::Request &req, kortex_driver::ReadAllProtectionZones::Response &res) override; + std::function CreateMappingHandler = nullptr; + virtual bool CreateMapping(kortex_driver::CreateMapping::Request &req, kortex_driver::CreateMapping::Response &res) override; + std::function ReadMappingHandler = nullptr; + virtual bool ReadMapping(kortex_driver::ReadMapping::Request &req, kortex_driver::ReadMapping::Response &res) override; + std::function UpdateMappingHandler = nullptr; + virtual bool UpdateMapping(kortex_driver::UpdateMapping::Request &req, kortex_driver::UpdateMapping::Response &res) override; + std::function DeleteMappingHandler = nullptr; + virtual bool DeleteMapping(kortex_driver::DeleteMapping::Request &req, kortex_driver::DeleteMapping::Response &res) override; + std::function ReadAllMappingsHandler = nullptr; + virtual bool ReadAllMappings(kortex_driver::ReadAllMappings::Request &req, kortex_driver::ReadAllMappings::Response &res) override; + std::function CreateMapHandler = nullptr; + virtual bool CreateMap(kortex_driver::CreateMap::Request &req, kortex_driver::CreateMap::Response &res) override; + std::function ReadMapHandler = nullptr; + virtual bool ReadMap(kortex_driver::ReadMap::Request &req, kortex_driver::ReadMap::Response &res) override; + std::function UpdateMapHandler = nullptr; + virtual bool UpdateMap(kortex_driver::UpdateMap::Request &req, kortex_driver::UpdateMap::Response &res) override; + std::function DeleteMapHandler = nullptr; + virtual bool DeleteMap(kortex_driver::DeleteMap::Request &req, kortex_driver::DeleteMap::Response &res) override; + std::function ReadAllMapsHandler = nullptr; + virtual bool ReadAllMaps(kortex_driver::ReadAllMaps::Request &req, kortex_driver::ReadAllMaps::Response &res) override; + std::function ActivateMapHandler = nullptr; + virtual bool ActivateMap(kortex_driver::ActivateMap::Request &req, kortex_driver::ActivateMap::Response &res) override; + std::function CreateActionHandler = nullptr; + virtual bool CreateAction(kortex_driver::CreateAction::Request &req, kortex_driver::CreateAction::Response &res) override; + std::function ReadActionHandler = nullptr; + virtual bool ReadAction(kortex_driver::ReadAction::Request &req, kortex_driver::ReadAction::Response &res) override; + std::function ReadAllActionsHandler = nullptr; + virtual bool ReadAllActions(kortex_driver::ReadAllActions::Request &req, kortex_driver::ReadAllActions::Response &res) override; + std::function DeleteActionHandler = nullptr; + virtual bool DeleteAction(kortex_driver::DeleteAction::Request &req, kortex_driver::DeleteAction::Response &res) override; + std::function UpdateActionHandler = nullptr; + virtual bool UpdateAction(kortex_driver::UpdateAction::Request &req, kortex_driver::UpdateAction::Response &res) override; + std::function ExecuteActionFromReferenceHandler = nullptr; + virtual bool ExecuteActionFromReference(kortex_driver::ExecuteActionFromReference::Request &req, kortex_driver::ExecuteActionFromReference::Response &res) override; + std::function ExecuteActionHandler = nullptr; + virtual bool ExecuteAction(kortex_driver::ExecuteAction::Request &req, kortex_driver::ExecuteAction::Response &res) override; + std::function PauseActionHandler = nullptr; + virtual bool PauseAction(kortex_driver::PauseAction::Request &req, kortex_driver::PauseAction::Response &res) override; + std::function StopActionHandler = nullptr; + virtual bool StopAction(kortex_driver::StopAction::Request &req, kortex_driver::StopAction::Response &res) override; + std::function ResumeActionHandler = nullptr; + virtual bool ResumeAction(kortex_driver::ResumeAction::Request &req, kortex_driver::ResumeAction::Response &res) override; + std::function GetIPv4ConfigurationHandler = nullptr; + virtual bool GetIPv4Configuration(kortex_driver::GetIPv4Configuration::Request &req, kortex_driver::GetIPv4Configuration::Response &res) override; + std::function SetIPv4ConfigurationHandler = nullptr; + virtual bool SetIPv4Configuration(kortex_driver::SetIPv4Configuration::Request &req, kortex_driver::SetIPv4Configuration::Response &res) override; + std::function SetCommunicationInterfaceEnableHandler = nullptr; + virtual bool SetCommunicationInterfaceEnable(kortex_driver::SetCommunicationInterfaceEnable::Request &req, kortex_driver::SetCommunicationInterfaceEnable::Response &res) override; + std::function IsCommunicationInterfaceEnableHandler = nullptr; + virtual bool IsCommunicationInterfaceEnable(kortex_driver::IsCommunicationInterfaceEnable::Request &req, kortex_driver::IsCommunicationInterfaceEnable::Response &res) override; + std::function GetAvailableWifiHandler = nullptr; + virtual bool GetAvailableWifi(kortex_driver::GetAvailableWifi::Request &req, kortex_driver::GetAvailableWifi::Response &res) override; + std::function GetWifiInformationHandler = nullptr; + virtual bool GetWifiInformation(kortex_driver::GetWifiInformation::Request &req, kortex_driver::GetWifiInformation::Response &res) override; + std::function AddWifiConfigurationHandler = nullptr; + virtual bool AddWifiConfiguration(kortex_driver::AddWifiConfiguration::Request &req, kortex_driver::AddWifiConfiguration::Response &res) override; + std::function DeleteWifiConfigurationHandler = nullptr; + virtual bool DeleteWifiConfiguration(kortex_driver::DeleteWifiConfiguration::Request &req, kortex_driver::DeleteWifiConfiguration::Response &res) override; + std::function GetAllConfiguredWifisHandler = nullptr; + virtual bool GetAllConfiguredWifis(kortex_driver::GetAllConfiguredWifis::Request &req, kortex_driver::GetAllConfiguredWifis::Response &res) override; + std::function ConnectWifiHandler = nullptr; + virtual bool ConnectWifi(kortex_driver::ConnectWifi::Request &req, kortex_driver::ConnectWifi::Response &res) override; + std::function DisconnectWifiHandler = nullptr; + virtual bool DisconnectWifi(kortex_driver::DisconnectWifi::Request &req, kortex_driver::DisconnectWifi::Response &res) override; + std::function GetConnectedWifiInformationHandler = nullptr; + virtual bool GetConnectedWifiInformation(kortex_driver::GetConnectedWifiInformation::Request &req, kortex_driver::GetConnectedWifiInformation::Response &res) override; + std::function Base_UnsubscribeHandler = nullptr; + virtual bool Base_Unsubscribe(kortex_driver::Base_Unsubscribe::Request &req, kortex_driver::Base_Unsubscribe::Response &res) override; + std::function OnNotificationConfigurationChangeTopicHandler = nullptr; + virtual bool OnNotificationConfigurationChangeTopic(kortex_driver::OnNotificationConfigurationChangeTopic::Request &req, kortex_driver::OnNotificationConfigurationChangeTopic::Response &res) override; + virtual void cb_ConfigurationChangeTopic(Kinova::Api::Base::ConfigurationChangeNotification notif) override; + std::function OnNotificationMappingInfoTopicHandler = nullptr; + virtual bool OnNotificationMappingInfoTopic(kortex_driver::OnNotificationMappingInfoTopic::Request &req, kortex_driver::OnNotificationMappingInfoTopic::Response &res) override; + virtual void cb_MappingInfoTopic(Kinova::Api::Base::MappingInfoNotification notif) override; + std::function OnNotificationControlModeTopicHandler = nullptr; + virtual bool OnNotificationControlModeTopic(kortex_driver::OnNotificationControlModeTopic::Request &req, kortex_driver::OnNotificationControlModeTopic::Response &res) override; + virtual void cb_ControlModeTopic(Kinova::Api::Base::ControlModeNotification notif) override; + std::function OnNotificationOperatingModeTopicHandler = nullptr; + virtual bool OnNotificationOperatingModeTopic(kortex_driver::OnNotificationOperatingModeTopic::Request &req, kortex_driver::OnNotificationOperatingModeTopic::Response &res) override; + virtual void cb_OperatingModeTopic(Kinova::Api::Base::OperatingModeNotification notif) override; + std::function OnNotificationSequenceInfoTopicHandler = nullptr; + virtual bool OnNotificationSequenceInfoTopic(kortex_driver::OnNotificationSequenceInfoTopic::Request &req, kortex_driver::OnNotificationSequenceInfoTopic::Response &res) override; + virtual void cb_SequenceInfoTopic(Kinova::Api::Base::SequenceInfoNotification notif) override; + std::function OnNotificationProtectionZoneTopicHandler = nullptr; + virtual bool OnNotificationProtectionZoneTopic(kortex_driver::OnNotificationProtectionZoneTopic::Request &req, kortex_driver::OnNotificationProtectionZoneTopic::Response &res) override; + virtual void cb_ProtectionZoneTopic(Kinova::Api::Base::ProtectionZoneNotification notif) override; + std::function OnNotificationUserTopicHandler = nullptr; + virtual bool OnNotificationUserTopic(kortex_driver::OnNotificationUserTopic::Request &req, kortex_driver::OnNotificationUserTopic::Response &res) override; + virtual void cb_UserTopic(Kinova::Api::Base::UserNotification notif) override; + std::function OnNotificationControllerTopicHandler = nullptr; + virtual bool OnNotificationControllerTopic(kortex_driver::OnNotificationControllerTopic::Request &req, kortex_driver::OnNotificationControllerTopic::Response &res) override; + virtual void cb_ControllerTopic(Kinova::Api::Base::ControllerNotification notif) override; + std::function OnNotificationActionTopicHandler = nullptr; + virtual bool OnNotificationActionTopic(kortex_driver::OnNotificationActionTopic::Request &req, kortex_driver::OnNotificationActionTopic::Response &res) override; + virtual void cb_ActionTopic(Kinova::Api::Base::ActionNotification notif) override; + std::function OnNotificationRobotEventTopicHandler = nullptr; + virtual bool OnNotificationRobotEventTopic(kortex_driver::OnNotificationRobotEventTopic::Request &req, kortex_driver::OnNotificationRobotEventTopic::Response &res) override; + virtual void cb_RobotEventTopic(Kinova::Api::Base::RobotEventNotification notif) override; + std::function PlayCartesianTrajectoryHandler = nullptr; + virtual bool PlayCartesianTrajectory(kortex_driver::PlayCartesianTrajectory::Request &req, kortex_driver::PlayCartesianTrajectory::Response &res) override; + std::function PlayCartesianTrajectoryPositionHandler = nullptr; + virtual bool PlayCartesianTrajectoryPosition(kortex_driver::PlayCartesianTrajectoryPosition::Request &req, kortex_driver::PlayCartesianTrajectoryPosition::Response &res) override; + std::function PlayCartesianTrajectoryOrientationHandler = nullptr; + virtual bool PlayCartesianTrajectoryOrientation(kortex_driver::PlayCartesianTrajectoryOrientation::Request &req, kortex_driver::PlayCartesianTrajectoryOrientation::Response &res) override; + std::function StopHandler = nullptr; + virtual bool Stop(kortex_driver::Stop::Request &req, kortex_driver::Stop::Response &res) override; + std::function GetMeasuredCartesianPoseHandler = nullptr; + virtual bool GetMeasuredCartesianPose(kortex_driver::GetMeasuredCartesianPose::Request &req, kortex_driver::GetMeasuredCartesianPose::Response &res) override; + std::function SendWrenchCommandHandler = nullptr; + virtual bool SendWrenchCommand(kortex_driver::SendWrenchCommand::Request &req, kortex_driver::SendWrenchCommand::Response &res) override; + std::function SendWrenchJoystickCommandHandler = nullptr; + virtual bool SendWrenchJoystickCommand(kortex_driver::SendWrenchJoystickCommand::Request &req, kortex_driver::SendWrenchJoystickCommand::Response &res) override; + std::function SendTwistJoystickCommandHandler = nullptr; + virtual bool SendTwistJoystickCommand(kortex_driver::SendTwistJoystickCommand::Request &req, kortex_driver::SendTwistJoystickCommand::Response &res) override; + std::function SendTwistCommandHandler = nullptr; + virtual bool SendTwistCommand(kortex_driver::SendTwistCommand::Request &req, kortex_driver::SendTwistCommand::Response &res) override; + std::function PlayJointTrajectoryHandler = nullptr; + virtual bool PlayJointTrajectory(kortex_driver::PlayJointTrajectory::Request &req, kortex_driver::PlayJointTrajectory::Response &res) override; + std::function PlaySelectedJointTrajectoryHandler = nullptr; + virtual bool PlaySelectedJointTrajectory(kortex_driver::PlaySelectedJointTrajectory::Request &req, kortex_driver::PlaySelectedJointTrajectory::Response &res) override; + std::function GetMeasuredJointAnglesHandler = nullptr; + virtual bool GetMeasuredJointAngles(kortex_driver::GetMeasuredJointAngles::Request &req, kortex_driver::GetMeasuredJointAngles::Response &res) override; + std::function SendJointSpeedsCommandHandler = nullptr; + virtual bool SendJointSpeedsCommand(kortex_driver::SendJointSpeedsCommand::Request &req, kortex_driver::SendJointSpeedsCommand::Response &res) override; + std::function SendSelectedJointSpeedCommandHandler = nullptr; + virtual bool SendSelectedJointSpeedCommand(kortex_driver::SendSelectedJointSpeedCommand::Request &req, kortex_driver::SendSelectedJointSpeedCommand::Response &res) override; + std::function SendGripperCommandHandler = nullptr; + virtual bool SendGripperCommand(kortex_driver::SendGripperCommand::Request &req, kortex_driver::SendGripperCommand::Response &res) override; + std::function GetMeasuredGripperMovementHandler = nullptr; + virtual bool GetMeasuredGripperMovement(kortex_driver::GetMeasuredGripperMovement::Request &req, kortex_driver::GetMeasuredGripperMovement::Response &res) override; + std::function SetAdmittanceHandler = nullptr; + virtual bool SetAdmittance(kortex_driver::SetAdmittance::Request &req, kortex_driver::SetAdmittance::Response &res) override; + std::function SetOperatingModeHandler = nullptr; + virtual bool SetOperatingMode(kortex_driver::SetOperatingMode::Request &req, kortex_driver::SetOperatingMode::Response &res) override; + std::function ApplyEmergencyStopHandler = nullptr; + virtual bool ApplyEmergencyStop(kortex_driver::ApplyEmergencyStop::Request &req, kortex_driver::ApplyEmergencyStop::Response &res) override; + std::function Base_ClearFaultsHandler = nullptr; + virtual bool Base_ClearFaults(kortex_driver::Base_ClearFaults::Request &req, kortex_driver::Base_ClearFaults::Response &res) override; + std::function Base_GetControlModeHandler = nullptr; + virtual bool Base_GetControlMode(kortex_driver::Base_GetControlMode::Request &req, kortex_driver::Base_GetControlMode::Response &res) override; + std::function GetOperatingModeHandler = nullptr; + virtual bool GetOperatingMode(kortex_driver::GetOperatingMode::Request &req, kortex_driver::GetOperatingMode::Response &res) override; + std::function SetServoingModeHandler = nullptr; + virtual bool SetServoingMode(kortex_driver::SetServoingMode::Request &req, kortex_driver::SetServoingMode::Response &res) override; + std::function GetServoingModeHandler = nullptr; + virtual bool GetServoingMode(kortex_driver::GetServoingMode::Request &req, kortex_driver::GetServoingMode::Response &res) override; + std::function OnNotificationServoingModeTopicHandler = nullptr; + virtual bool OnNotificationServoingModeTopic(kortex_driver::OnNotificationServoingModeTopic::Request &req, kortex_driver::OnNotificationServoingModeTopic::Response &res) override; + virtual void cb_ServoingModeTopic(Kinova::Api::Base::ServoingModeNotification notif) override; + std::function RestoreFactorySettingsHandler = nullptr; + virtual bool RestoreFactorySettings(kortex_driver::RestoreFactorySettings::Request &req, kortex_driver::RestoreFactorySettings::Response &res) override; + std::function OnNotificationFactoryTopicHandler = nullptr; + virtual bool OnNotificationFactoryTopic(kortex_driver::OnNotificationFactoryTopic::Request &req, kortex_driver::OnNotificationFactoryTopic::Response &res) override; + virtual void cb_FactoryTopic(Kinova::Api::Base::FactoryNotification notif) override; + std::function GetAllConnectedControllersHandler = nullptr; + virtual bool GetAllConnectedControllers(kortex_driver::GetAllConnectedControllers::Request &req, kortex_driver::GetAllConnectedControllers::Response &res) override; + std::function GetControllerStateHandler = nullptr; + virtual bool GetControllerState(kortex_driver::GetControllerState::Request &req, kortex_driver::GetControllerState::Response &res) override; + std::function GetActuatorCountHandler = nullptr; + virtual bool GetActuatorCount(kortex_driver::GetActuatorCount::Request &req, kortex_driver::GetActuatorCount::Response &res) override; + std::function StartWifiScanHandler = nullptr; + virtual bool StartWifiScan(kortex_driver::StartWifiScan::Request &req, kortex_driver::StartWifiScan::Response &res) override; + std::function GetConfiguredWifiHandler = nullptr; + virtual bool GetConfiguredWifi(kortex_driver::GetConfiguredWifi::Request &req, kortex_driver::GetConfiguredWifi::Response &res) override; + std::function OnNotificationNetworkTopicHandler = nullptr; + virtual bool OnNotificationNetworkTopic(kortex_driver::OnNotificationNetworkTopic::Request &req, kortex_driver::OnNotificationNetworkTopic::Response &res) override; + virtual void cb_NetworkTopic(Kinova::Api::Base::NetworkNotification notif) override; + std::function GetArmStateHandler = nullptr; + virtual bool GetArmState(kortex_driver::GetArmState::Request &req, kortex_driver::GetArmState::Response &res) override; + std::function OnNotificationArmStateTopicHandler = nullptr; + virtual bool OnNotificationArmStateTopic(kortex_driver::OnNotificationArmStateTopic::Request &req, kortex_driver::OnNotificationArmStateTopic::Response &res) override; + virtual void cb_ArmStateTopic(Kinova::Api::Base::ArmStateNotification notif) override; + std::function GetIPv4InformationHandler = nullptr; + virtual bool GetIPv4Information(kortex_driver::GetIPv4Information::Request &req, kortex_driver::GetIPv4Information::Response &res) override; + std::function SetWifiCountryCodeHandler = nullptr; + virtual bool SetWifiCountryCode(kortex_driver::SetWifiCountryCode::Request &req, kortex_driver::SetWifiCountryCode::Response &res) override; + std::function GetWifiCountryCodeHandler = nullptr; + virtual bool GetWifiCountryCode(kortex_driver::GetWifiCountryCode::Request &req, kortex_driver::GetWifiCountryCode::Response &res) override; + std::function Base_SetCapSenseConfigHandler = nullptr; + virtual bool Base_SetCapSenseConfig(kortex_driver::Base_SetCapSenseConfig::Request &req, kortex_driver::Base_SetCapSenseConfig::Response &res) override; + std::function Base_GetCapSenseConfigHandler = nullptr; + virtual bool Base_GetCapSenseConfig(kortex_driver::Base_GetCapSenseConfig::Request &req, kortex_driver::Base_GetCapSenseConfig::Response &res) override; + std::function GetAllJointsSpeedHardLimitationHandler = nullptr; + virtual bool GetAllJointsSpeedHardLimitation(kortex_driver::GetAllJointsSpeedHardLimitation::Request &req, kortex_driver::GetAllJointsSpeedHardLimitation::Response &res) override; + std::function GetAllJointsTorqueHardLimitationHandler = nullptr; + virtual bool GetAllJointsTorqueHardLimitation(kortex_driver::GetAllJointsTorqueHardLimitation::Request &req, kortex_driver::GetAllJointsTorqueHardLimitation::Response &res) override; + std::function GetTwistHardLimitationHandler = nullptr; + virtual bool GetTwistHardLimitation(kortex_driver::GetTwistHardLimitation::Request &req, kortex_driver::GetTwistHardLimitation::Response &res) override; + std::function GetWrenchHardLimitationHandler = nullptr; + virtual bool GetWrenchHardLimitation(kortex_driver::GetWrenchHardLimitation::Request &req, kortex_driver::GetWrenchHardLimitation::Response &res) override; + std::function SendJointSpeedsJoystickCommandHandler = nullptr; + virtual bool SendJointSpeedsJoystickCommand(kortex_driver::SendJointSpeedsJoystickCommand::Request &req, kortex_driver::SendJointSpeedsJoystickCommand::Response &res) override; + std::function SendSelectedJointSpeedJoystickCommandHandler = nullptr; + virtual bool SendSelectedJointSpeedJoystickCommand(kortex_driver::SendSelectedJointSpeedJoystickCommand::Request &req, kortex_driver::SendSelectedJointSpeedJoystickCommand::Response &res) override; + std::function EnableBridgeHandler = nullptr; + virtual bool EnableBridge(kortex_driver::EnableBridge::Request &req, kortex_driver::EnableBridge::Response &res) override; + std::function DisableBridgeHandler = nullptr; + virtual bool DisableBridge(kortex_driver::DisableBridge::Request &req, kortex_driver::DisableBridge::Response &res) override; + std::function GetBridgeListHandler = nullptr; + virtual bool GetBridgeList(kortex_driver::GetBridgeList::Request &req, kortex_driver::GetBridgeList::Response &res) override; + std::function GetBridgeConfigHandler = nullptr; + virtual bool GetBridgeConfig(kortex_driver::GetBridgeConfig::Request &req, kortex_driver::GetBridgeConfig::Response &res) override; + std::function PlayPreComputedJointTrajectoryHandler = nullptr; + virtual bool PlayPreComputedJointTrajectory(kortex_driver::PlayPreComputedJointTrajectory::Request &req, kortex_driver::PlayPreComputedJointTrajectory::Response &res) override; + std::function GetProductConfigurationHandler = nullptr; + virtual bool GetProductConfiguration(kortex_driver::GetProductConfiguration::Request &req, kortex_driver::GetProductConfiguration::Response &res) override; + std::function UpdateEndEffectorTypeConfigurationHandler = nullptr; + virtual bool UpdateEndEffectorTypeConfiguration(kortex_driver::UpdateEndEffectorTypeConfiguration::Request &req, kortex_driver::UpdateEndEffectorTypeConfiguration::Response &res) override; + std::function RestoreFactoryProductConfigurationHandler = nullptr; + virtual bool RestoreFactoryProductConfiguration(kortex_driver::RestoreFactoryProductConfiguration::Request &req, kortex_driver::RestoreFactoryProductConfiguration::Response &res) override; + std::function GetTrajectoryErrorReportHandler = nullptr; + virtual bool GetTrajectoryErrorReport(kortex_driver::GetTrajectoryErrorReport::Request &req, kortex_driver::GetTrajectoryErrorReport::Response &res) override; + std::function GetAllJointsSpeedSoftLimitationHandler = nullptr; + virtual bool GetAllJointsSpeedSoftLimitation(kortex_driver::GetAllJointsSpeedSoftLimitation::Request &req, kortex_driver::GetAllJointsSpeedSoftLimitation::Response &res) override; + std::function GetAllJointsTorqueSoftLimitationHandler = nullptr; + virtual bool GetAllJointsTorqueSoftLimitation(kortex_driver::GetAllJointsTorqueSoftLimitation::Request &req, kortex_driver::GetAllJointsTorqueSoftLimitation::Response &res) override; + std::function GetTwistSoftLimitationHandler = nullptr; + virtual bool GetTwistSoftLimitation(kortex_driver::GetTwistSoftLimitation::Request &req, kortex_driver::GetTwistSoftLimitation::Response &res) override; + std::function GetWrenchSoftLimitationHandler = nullptr; + virtual bool GetWrenchSoftLimitation(kortex_driver::GetWrenchSoftLimitation::Request &req, kortex_driver::GetWrenchSoftLimitation::Response &res) override; + std::function SetControllerConfigurationModeHandler = nullptr; + virtual bool SetControllerConfigurationMode(kortex_driver::SetControllerConfigurationMode::Request &req, kortex_driver::SetControllerConfigurationMode::Response &res) override; + std::function GetControllerConfigurationModeHandler = nullptr; + virtual bool GetControllerConfigurationMode(kortex_driver::GetControllerConfigurationMode::Request &req, kortex_driver::GetControllerConfigurationMode::Response &res) override; + std::function StartTeachingHandler = nullptr; + virtual bool StartTeaching(kortex_driver::StartTeaching::Request &req, kortex_driver::StartTeaching::Response &res) override; + std::function StopTeachingHandler = nullptr; + virtual bool StopTeaching(kortex_driver::StopTeaching::Request &req, kortex_driver::StopTeaching::Response &res) override; + std::function AddSequenceTasksHandler = nullptr; + virtual bool AddSequenceTasks(kortex_driver::AddSequenceTasks::Request &req, kortex_driver::AddSequenceTasks::Response &res) override; + std::function UpdateSequenceTaskHandler = nullptr; + virtual bool UpdateSequenceTask(kortex_driver::UpdateSequenceTask::Request &req, kortex_driver::UpdateSequenceTask::Response &res) override; + std::function SwapSequenceTasksHandler = nullptr; + virtual bool SwapSequenceTasks(kortex_driver::SwapSequenceTasks::Request &req, kortex_driver::SwapSequenceTasks::Response &res) override; + std::function ReadSequenceTaskHandler = nullptr; + virtual bool ReadSequenceTask(kortex_driver::ReadSequenceTask::Request &req, kortex_driver::ReadSequenceTask::Response &res) override; + std::function ReadAllSequenceTasksHandler = nullptr; + virtual bool ReadAllSequenceTasks(kortex_driver::ReadAllSequenceTasks::Request &req, kortex_driver::ReadAllSequenceTasks::Response &res) override; + std::function DeleteSequenceTaskHandler = nullptr; + virtual bool DeleteSequenceTask(kortex_driver::DeleteSequenceTask::Request &req, kortex_driver::DeleteSequenceTask::Response &res) override; + std::function DeleteAllSequenceTasksHandler = nullptr; + virtual bool DeleteAllSequenceTasks(kortex_driver::DeleteAllSequenceTasks::Request &req, kortex_driver::DeleteAllSequenceTasks::Response &res) override; + std::function TakeSnapshotHandler = nullptr; + virtual bool TakeSnapshot(kortex_driver::TakeSnapshot::Request &req, kortex_driver::TakeSnapshot::Response &res) override; + std::function GetFirmwareBundleVersionsHandler = nullptr; + virtual bool GetFirmwareBundleVersions(kortex_driver::GetFirmwareBundleVersions::Request &req, kortex_driver::GetFirmwareBundleVersions::Response &res) override; + std::function MoveSequenceTaskHandler = nullptr; + virtual bool MoveSequenceTask(kortex_driver::MoveSequenceTask::Request &req, kortex_driver::MoveSequenceTask::Response &res) override; + std::function DuplicateMappingHandler = nullptr; + virtual bool DuplicateMapping(kortex_driver::DuplicateMapping::Request &req, kortex_driver::DuplicateMapping::Response &res) override; + std::function DuplicateMapHandler = nullptr; + virtual bool DuplicateMap(kortex_driver::DuplicateMap::Request &req, kortex_driver::DuplicateMap::Response &res) override; + std::function SetControllerConfigurationHandler = nullptr; + virtual bool SetControllerConfiguration(kortex_driver::SetControllerConfiguration::Request &req, kortex_driver::SetControllerConfiguration::Response &res) override; + std::function GetControllerConfigurationHandler = nullptr; + virtual bool GetControllerConfiguration(kortex_driver::GetControllerConfiguration::Request &req, kortex_driver::GetControllerConfiguration::Response &res) override; + std::function GetAllControllerConfigurationsHandler = nullptr; + virtual bool GetAllControllerConfigurations(kortex_driver::GetAllControllerConfigurations::Request &req, kortex_driver::GetAllControllerConfigurations::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/controlconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/controlconfig_services.h new file mode 100644 index 0000000..30a8738 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/controlconfig_services.h @@ -0,0 +1,92 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_CONTROLCONFIG_SIMULATION_SERVICES_H_ +#define _KORTEX_CONTROLCONFIG_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/controlconfig_services_interface.h" + +using namespace std; + +class ControlConfigSimulationServices : public IControlConfigServices +{ + public: + ControlConfigSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function SetGravityVectorHandler = nullptr; + virtual bool SetGravityVector(kortex_driver::SetGravityVector::Request &req, kortex_driver::SetGravityVector::Response &res) override; + std::function GetGravityVectorHandler = nullptr; + virtual bool GetGravityVector(kortex_driver::GetGravityVector::Request &req, kortex_driver::GetGravityVector::Response &res) override; + std::function SetPayloadInformationHandler = nullptr; + virtual bool SetPayloadInformation(kortex_driver::SetPayloadInformation::Request &req, kortex_driver::SetPayloadInformation::Response &res) override; + std::function GetPayloadInformationHandler = nullptr; + virtual bool GetPayloadInformation(kortex_driver::GetPayloadInformation::Request &req, kortex_driver::GetPayloadInformation::Response &res) override; + std::function SetToolConfigurationHandler = nullptr; + virtual bool SetToolConfiguration(kortex_driver::SetToolConfiguration::Request &req, kortex_driver::SetToolConfiguration::Response &res) override; + std::function GetToolConfigurationHandler = nullptr; + virtual bool GetToolConfiguration(kortex_driver::GetToolConfiguration::Request &req, kortex_driver::GetToolConfiguration::Response &res) override; + std::function OnNotificationControlConfigurationTopicHandler = nullptr; + virtual bool OnNotificationControlConfigurationTopic(kortex_driver::OnNotificationControlConfigurationTopic::Request &req, kortex_driver::OnNotificationControlConfigurationTopic::Response &res) override; + virtual void cb_ControlConfigurationTopic(Kinova::Api::ControlConfig::ControlConfigurationNotification notif) override; + std::function ControlConfig_UnsubscribeHandler = nullptr; + virtual bool ControlConfig_Unsubscribe(kortex_driver::ControlConfig_Unsubscribe::Request &req, kortex_driver::ControlConfig_Unsubscribe::Response &res) override; + std::function SetCartesianReferenceFrameHandler = nullptr; + virtual bool SetCartesianReferenceFrame(kortex_driver::SetCartesianReferenceFrame::Request &req, kortex_driver::SetCartesianReferenceFrame::Response &res) override; + std::function GetCartesianReferenceFrameHandler = nullptr; + virtual bool GetCartesianReferenceFrame(kortex_driver::GetCartesianReferenceFrame::Request &req, kortex_driver::GetCartesianReferenceFrame::Response &res) override; + std::function ControlConfig_GetControlModeHandler = nullptr; + virtual bool ControlConfig_GetControlMode(kortex_driver::ControlConfig_GetControlMode::Request &req, kortex_driver::ControlConfig_GetControlMode::Response &res) override; + std::function SetJointSpeedSoftLimitsHandler = nullptr; + virtual bool SetJointSpeedSoftLimits(kortex_driver::SetJointSpeedSoftLimits::Request &req, kortex_driver::SetJointSpeedSoftLimits::Response &res) override; + std::function SetTwistLinearSoftLimitHandler = nullptr; + virtual bool SetTwistLinearSoftLimit(kortex_driver::SetTwistLinearSoftLimit::Request &req, kortex_driver::SetTwistLinearSoftLimit::Response &res) override; + std::function SetTwistAngularSoftLimitHandler = nullptr; + virtual bool SetTwistAngularSoftLimit(kortex_driver::SetTwistAngularSoftLimit::Request &req, kortex_driver::SetTwistAngularSoftLimit::Response &res) override; + std::function SetJointAccelerationSoftLimitsHandler = nullptr; + virtual bool SetJointAccelerationSoftLimits(kortex_driver::SetJointAccelerationSoftLimits::Request &req, kortex_driver::SetJointAccelerationSoftLimits::Response &res) override; + std::function GetKinematicHardLimitsHandler = nullptr; + virtual bool GetKinematicHardLimits(kortex_driver::GetKinematicHardLimits::Request &req, kortex_driver::GetKinematicHardLimits::Response &res) override; + std::function GetKinematicSoftLimitsHandler = nullptr; + virtual bool GetKinematicSoftLimits(kortex_driver::GetKinematicSoftLimits::Request &req, kortex_driver::GetKinematicSoftLimits::Response &res) override; + std::function GetAllKinematicSoftLimitsHandler = nullptr; + virtual bool GetAllKinematicSoftLimits(kortex_driver::GetAllKinematicSoftLimits::Request &req, kortex_driver::GetAllKinematicSoftLimits::Response &res) override; + std::function SetDesiredLinearTwistHandler = nullptr; + virtual bool SetDesiredLinearTwist(kortex_driver::SetDesiredLinearTwist::Request &req, kortex_driver::SetDesiredLinearTwist::Response &res) override; + std::function SetDesiredAngularTwistHandler = nullptr; + virtual bool SetDesiredAngularTwist(kortex_driver::SetDesiredAngularTwist::Request &req, kortex_driver::SetDesiredAngularTwist::Response &res) override; + std::function SetDesiredJointSpeedsHandler = nullptr; + virtual bool SetDesiredJointSpeeds(kortex_driver::SetDesiredJointSpeeds::Request &req, kortex_driver::SetDesiredJointSpeeds::Response &res) override; + std::function GetDesiredSpeedsHandler = nullptr; + virtual bool GetDesiredSpeeds(kortex_driver::GetDesiredSpeeds::Request &req, kortex_driver::GetDesiredSpeeds::Response &res) override; + std::function ResetGravityVectorHandler = nullptr; + virtual bool ResetGravityVector(kortex_driver::ResetGravityVector::Request &req, kortex_driver::ResetGravityVector::Response &res) override; + std::function ResetPayloadInformationHandler = nullptr; + virtual bool ResetPayloadInformation(kortex_driver::ResetPayloadInformation::Request &req, kortex_driver::ResetPayloadInformation::Response &res) override; + std::function ResetToolConfigurationHandler = nullptr; + virtual bool ResetToolConfiguration(kortex_driver::ResetToolConfiguration::Request &req, kortex_driver::ResetToolConfiguration::Response &res) override; + std::function ResetJointSpeedSoftLimitsHandler = nullptr; + virtual bool ResetJointSpeedSoftLimits(kortex_driver::ResetJointSpeedSoftLimits::Request &req, kortex_driver::ResetJointSpeedSoftLimits::Response &res) override; + std::function ResetTwistLinearSoftLimitHandler = nullptr; + virtual bool ResetTwistLinearSoftLimit(kortex_driver::ResetTwistLinearSoftLimit::Request &req, kortex_driver::ResetTwistLinearSoftLimit::Response &res) override; + std::function ResetTwistAngularSoftLimitHandler = nullptr; + virtual bool ResetTwistAngularSoftLimit(kortex_driver::ResetTwistAngularSoftLimit::Request &req, kortex_driver::ResetTwistAngularSoftLimit::Response &res) override; + std::function ResetJointAccelerationSoftLimitsHandler = nullptr; + virtual bool ResetJointAccelerationSoftLimits(kortex_driver::ResetJointAccelerationSoftLimits::Request &req, kortex_driver::ResetJointAccelerationSoftLimits::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/deviceconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/deviceconfig_services.h new file mode 100644 index 0000000..d047b45 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/deviceconfig_services.h @@ -0,0 +1,98 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICECONFIG_SIMULATION_SERVICES_H_ +#define _KORTEX_DEVICECONFIG_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/deviceconfig_services_interface.h" + +using namespace std; + +class DeviceConfigSimulationServices : public IDeviceConfigServices +{ + public: + DeviceConfigSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function GetRunModeHandler = nullptr; + virtual bool GetRunMode(kortex_driver::GetRunMode::Request &req, kortex_driver::GetRunMode::Response &res) override; + std::function SetRunModeHandler = nullptr; + virtual bool SetRunMode(kortex_driver::SetRunMode::Request &req, kortex_driver::SetRunMode::Response &res) override; + std::function GetDeviceTypeHandler = nullptr; + virtual bool GetDeviceType(kortex_driver::GetDeviceType::Request &req, kortex_driver::GetDeviceType::Response &res) override; + std::function GetFirmwareVersionHandler = nullptr; + virtual bool GetFirmwareVersion(kortex_driver::GetFirmwareVersion::Request &req, kortex_driver::GetFirmwareVersion::Response &res) override; + std::function GetBootloaderVersionHandler = nullptr; + virtual bool GetBootloaderVersion(kortex_driver::GetBootloaderVersion::Request &req, kortex_driver::GetBootloaderVersion::Response &res) override; + std::function GetModelNumberHandler = nullptr; + virtual bool GetModelNumber(kortex_driver::GetModelNumber::Request &req, kortex_driver::GetModelNumber::Response &res) override; + std::function GetPartNumberHandler = nullptr; + virtual bool GetPartNumber(kortex_driver::GetPartNumber::Request &req, kortex_driver::GetPartNumber::Response &res) override; + std::function GetSerialNumberHandler = nullptr; + virtual bool GetSerialNumber(kortex_driver::GetSerialNumber::Request &req, kortex_driver::GetSerialNumber::Response &res) override; + std::function GetMACAddressHandler = nullptr; + virtual bool GetMACAddress(kortex_driver::GetMACAddress::Request &req, kortex_driver::GetMACAddress::Response &res) override; + std::function GetIPv4SettingsHandler = nullptr; + virtual bool GetIPv4Settings(kortex_driver::GetIPv4Settings::Request &req, kortex_driver::GetIPv4Settings::Response &res) override; + std::function SetIPv4SettingsHandler = nullptr; + virtual bool SetIPv4Settings(kortex_driver::SetIPv4Settings::Request &req, kortex_driver::SetIPv4Settings::Response &res) override; + std::function GetPartNumberRevisionHandler = nullptr; + virtual bool GetPartNumberRevision(kortex_driver::GetPartNumberRevision::Request &req, kortex_driver::GetPartNumberRevision::Response &res) override; + std::function RebootRequestHandler = nullptr; + virtual bool RebootRequest(kortex_driver::RebootRequest::Request &req, kortex_driver::RebootRequest::Response &res) override; + std::function SetSafetyEnableHandler = nullptr; + virtual bool SetSafetyEnable(kortex_driver::SetSafetyEnable::Request &req, kortex_driver::SetSafetyEnable::Response &res) override; + std::function SetSafetyErrorThresholdHandler = nullptr; + virtual bool SetSafetyErrorThreshold(kortex_driver::SetSafetyErrorThreshold::Request &req, kortex_driver::SetSafetyErrorThreshold::Response &res) override; + std::function SetSafetyWarningThresholdHandler = nullptr; + virtual bool SetSafetyWarningThreshold(kortex_driver::SetSafetyWarningThreshold::Request &req, kortex_driver::SetSafetyWarningThreshold::Response &res) override; + std::function SetSafetyConfigurationHandler = nullptr; + virtual bool SetSafetyConfiguration(kortex_driver::SetSafetyConfiguration::Request &req, kortex_driver::SetSafetyConfiguration::Response &res) override; + std::function GetSafetyConfigurationHandler = nullptr; + virtual bool GetSafetyConfiguration(kortex_driver::GetSafetyConfiguration::Request &req, kortex_driver::GetSafetyConfiguration::Response &res) override; + std::function GetSafetyInformationHandler = nullptr; + virtual bool GetSafetyInformation(kortex_driver::GetSafetyInformation::Request &req, kortex_driver::GetSafetyInformation::Response &res) override; + std::function GetSafetyEnableHandler = nullptr; + virtual bool GetSafetyEnable(kortex_driver::GetSafetyEnable::Request &req, kortex_driver::GetSafetyEnable::Response &res) override; + std::function GetSafetyStatusHandler = nullptr; + virtual bool GetSafetyStatus(kortex_driver::GetSafetyStatus::Request &req, kortex_driver::GetSafetyStatus::Response &res) override; + std::function ClearAllSafetyStatusHandler = nullptr; + virtual bool ClearAllSafetyStatus(kortex_driver::ClearAllSafetyStatus::Request &req, kortex_driver::ClearAllSafetyStatus::Response &res) override; + std::function ClearSafetyStatusHandler = nullptr; + virtual bool ClearSafetyStatus(kortex_driver::ClearSafetyStatus::Request &req, kortex_driver::ClearSafetyStatus::Response &res) override; + std::function GetAllSafetyConfigurationHandler = nullptr; + virtual bool GetAllSafetyConfiguration(kortex_driver::GetAllSafetyConfiguration::Request &req, kortex_driver::GetAllSafetyConfiguration::Response &res) override; + std::function GetAllSafetyInformationHandler = nullptr; + virtual bool GetAllSafetyInformation(kortex_driver::GetAllSafetyInformation::Request &req, kortex_driver::GetAllSafetyInformation::Response &res) override; + std::function ResetSafetyDefaultsHandler = nullptr; + virtual bool ResetSafetyDefaults(kortex_driver::ResetSafetyDefaults::Request &req, kortex_driver::ResetSafetyDefaults::Response &res) override; + std::function OnNotificationSafetyTopicHandler = nullptr; + virtual bool OnNotificationSafetyTopic(kortex_driver::OnNotificationSafetyTopic::Request &req, kortex_driver::OnNotificationSafetyTopic::Response &res) override; + virtual void cb_SafetyTopic(Kinova::Api::Common::SafetyNotification notif) override; + std::function ExecuteCalibrationHandler = nullptr; + virtual bool ExecuteCalibration(kortex_driver::ExecuteCalibration::Request &req, kortex_driver::ExecuteCalibration::Response &res) override; + std::function GetCalibrationResultHandler = nullptr; + virtual bool GetCalibrationResult(kortex_driver::GetCalibrationResult::Request &req, kortex_driver::GetCalibrationResult::Response &res) override; + std::function StopCalibrationHandler = nullptr; + virtual bool StopCalibration(kortex_driver::StopCalibration::Request &req, kortex_driver::StopCalibration::Response &res) override; + std::function DeviceConfig_SetCapSenseConfigHandler = nullptr; + virtual bool DeviceConfig_SetCapSenseConfig(kortex_driver::DeviceConfig_SetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_SetCapSenseConfig::Response &res) override; + std::function DeviceConfig_GetCapSenseConfigHandler = nullptr; + virtual bool DeviceConfig_GetCapSenseConfig(kortex_driver::DeviceConfig_GetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_GetCapSenseConfig::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/devicemanager_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/devicemanager_services.h new file mode 100644 index 0000000..0c45ae7 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/devicemanager_services.h @@ -0,0 +1,35 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_DEVICEMANAGER_SIMULATION_SERVICES_H_ +#define _KORTEX_DEVICEMANAGER_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/devicemanager_services_interface.h" + +using namespace std; + +class DeviceManagerSimulationServices : public IDeviceManagerServices +{ + public: + DeviceManagerSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function ReadAllDevicesHandler = nullptr; + virtual bool ReadAllDevices(kortex_driver::ReadAllDevices::Request &req, kortex_driver::ReadAllDevices::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/interconnectconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/interconnectconfig_services.h new file mode 100644 index 0000000..1053941 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/interconnectconfig_services.h @@ -0,0 +1,61 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_INTERCONNECTCONFIG_SIMULATION_SERVICES_H_ +#define _KORTEX_INTERCONNECTCONFIG_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/interconnectconfig_services_interface.h" + +using namespace std; + +class InterconnectConfigSimulationServices : public IInterconnectConfigServices +{ + public: + InterconnectConfigSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function GetUARTConfigurationHandler = nullptr; + virtual bool GetUARTConfiguration(kortex_driver::GetUARTConfiguration::Request &req, kortex_driver::GetUARTConfiguration::Response &res) override; + std::function SetUARTConfigurationHandler = nullptr; + virtual bool SetUARTConfiguration(kortex_driver::SetUARTConfiguration::Request &req, kortex_driver::SetUARTConfiguration::Response &res) override; + std::function GetEthernetConfigurationHandler = nullptr; + virtual bool GetEthernetConfiguration(kortex_driver::GetEthernetConfiguration::Request &req, kortex_driver::GetEthernetConfiguration::Response &res) override; + std::function SetEthernetConfigurationHandler = nullptr; + virtual bool SetEthernetConfiguration(kortex_driver::SetEthernetConfiguration::Request &req, kortex_driver::SetEthernetConfiguration::Response &res) override; + std::function GetGPIOConfigurationHandler = nullptr; + virtual bool GetGPIOConfiguration(kortex_driver::GetGPIOConfiguration::Request &req, kortex_driver::GetGPIOConfiguration::Response &res) override; + std::function SetGPIOConfigurationHandler = nullptr; + virtual bool SetGPIOConfiguration(kortex_driver::SetGPIOConfiguration::Request &req, kortex_driver::SetGPIOConfiguration::Response &res) override; + std::function GetGPIOStateHandler = nullptr; + virtual bool GetGPIOState(kortex_driver::GetGPIOState::Request &req, kortex_driver::GetGPIOState::Response &res) override; + std::function SetGPIOStateHandler = nullptr; + virtual bool SetGPIOState(kortex_driver::SetGPIOState::Request &req, kortex_driver::SetGPIOState::Response &res) override; + std::function GetI2CConfigurationHandler = nullptr; + virtual bool GetI2CConfiguration(kortex_driver::GetI2CConfiguration::Request &req, kortex_driver::GetI2CConfiguration::Response &res) override; + std::function SetI2CConfigurationHandler = nullptr; + virtual bool SetI2CConfiguration(kortex_driver::SetI2CConfiguration::Request &req, kortex_driver::SetI2CConfiguration::Response &res) override; + std::function I2CReadHandler = nullptr; + virtual bool I2CRead(kortex_driver::I2CRead::Request &req, kortex_driver::I2CRead::Response &res) override; + std::function I2CReadRegisterHandler = nullptr; + virtual bool I2CReadRegister(kortex_driver::I2CReadRegister::Request &req, kortex_driver::I2CReadRegister::Response &res) override; + std::function I2CWriteHandler = nullptr; + virtual bool I2CWrite(kortex_driver::I2CWrite::Request &req, kortex_driver::I2CWrite::Response &res) override; + std::function I2CWriteRegisterHandler = nullptr; + virtual bool I2CWriteRegister(kortex_driver::I2CWriteRegister::Request &req, kortex_driver::I2CWriteRegister::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/visionconfig_services.h b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/visionconfig_services.h new file mode 100644 index 0000000..c98151f --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/generated/simulation/visionconfig_services.h @@ -0,0 +1,58 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_VISIONCONFIG_SIMULATION_SERVICES_H_ +#define _KORTEX_VISIONCONFIG_SIMULATION_SERVICES_H_ + +#include "kortex_driver/generated/interfaces/visionconfig_services_interface.h" + +using namespace std; + +class VisionConfigSimulationServices : public IVisionConfigServices +{ + public: + VisionConfigSimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; + std::function SetSensorSettingsHandler = nullptr; + virtual bool SetSensorSettings(kortex_driver::SetSensorSettings::Request &req, kortex_driver::SetSensorSettings::Response &res) override; + std::function GetSensorSettingsHandler = nullptr; + virtual bool GetSensorSettings(kortex_driver::GetSensorSettings::Request &req, kortex_driver::GetSensorSettings::Response &res) override; + std::function GetOptionValueHandler = nullptr; + virtual bool GetOptionValue(kortex_driver::GetOptionValue::Request &req, kortex_driver::GetOptionValue::Response &res) override; + std::function SetOptionValueHandler = nullptr; + virtual bool SetOptionValue(kortex_driver::SetOptionValue::Request &req, kortex_driver::SetOptionValue::Response &res) override; + std::function GetOptionInformationHandler = nullptr; + virtual bool GetOptionInformation(kortex_driver::GetOptionInformation::Request &req, kortex_driver::GetOptionInformation::Response &res) override; + std::function OnNotificationVisionTopicHandler = nullptr; + virtual bool OnNotificationVisionTopic(kortex_driver::OnNotificationVisionTopic::Request &req, kortex_driver::OnNotificationVisionTopic::Response &res) override; + virtual void cb_VisionTopic(Kinova::Api::VisionConfig::VisionNotification notif) override; + std::function DoSensorFocusActionHandler = nullptr; + virtual bool DoSensorFocusAction(kortex_driver::DoSensorFocusAction::Request &req, kortex_driver::DoSensorFocusAction::Response &res) override; + std::function GetIntrinsicParametersHandler = nullptr; + virtual bool GetIntrinsicParameters(kortex_driver::GetIntrinsicParameters::Request &req, kortex_driver::GetIntrinsicParameters::Response &res) override; + std::function GetIntrinsicParametersProfileHandler = nullptr; + virtual bool GetIntrinsicParametersProfile(kortex_driver::GetIntrinsicParametersProfile::Request &req, kortex_driver::GetIntrinsicParametersProfile::Response &res) override; + std::function SetIntrinsicParametersHandler = nullptr; + virtual bool SetIntrinsicParameters(kortex_driver::SetIntrinsicParameters::Request &req, kortex_driver::SetIntrinsicParameters::Response &res) override; + std::function GetExtrinsicParametersHandler = nullptr; + virtual bool GetExtrinsicParameters(kortex_driver::GetExtrinsicParameters::Request &req, kortex_driver::GetExtrinsicParameters::Response &res) override; + std::function SetExtrinsicParametersHandler = nullptr; + virtual bool SetExtrinsicParameters(kortex_driver::SetExtrinsicParameters::Request &req, kortex_driver::SetExtrinsicParameters::Response &res) override; + +}; +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_arm_driver.h b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_arm_driver.h new file mode 100644 index 0000000..e15da23 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_arm_driver.h @@ -0,0 +1,170 @@ +#ifndef _KORTEX_ARM_DRIVER_H_ +#define _KORTEX_ARM_DRIVER_H_ + +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include +#include + +#include + +#include "SessionManager.h" +#include "TransportClientTcp.h" +#include "TransportClientUdp.h" +#include "RouterClient.h" + +#include "ActuatorConfigClientRpc.h" +#include "BaseClientRpc.h" +#include "DeviceConfigClientRpc.h" +#include "DeviceManagerClientRpc.h" +#include "InterconnectConfigClientRpc.h" +#include "VisionConfigClientRpc.h" +#include "BaseCyclicClientRpc.h" +#include "SessionManager.h" + +#include "kortex_driver/non-generated/kortex_math_util.h" + +#include "kortex_driver/BaseCyclic_Feedback.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" + +#include "kortex_driver/generated/robot/actuatorconfig_services.h" +#include "kortex_driver/generated/robot/base_services.h" +#include "kortex_driver/generated/robot/deviceconfig_services.h" +#include "kortex_driver/generated/robot/devicemanager_services.h" +#include "kortex_driver/generated/robot/interconnectconfig_services.h" +#include "kortex_driver/generated/robot/visionconfig_services.h" +#include "kortex_driver/generated/robot/controlconfig_services.h" + +#include "kortex_driver/generated/simulation/actuatorconfig_services.h" +#include "kortex_driver/generated/simulation/base_services.h" +#include "kortex_driver/generated/simulation/deviceconfig_services.h" +#include "kortex_driver/generated/simulation/devicemanager_services.h" +#include "kortex_driver/generated/simulation/interconnectconfig_services.h" +#include "kortex_driver/generated/simulation/visionconfig_services.h" +#include "kortex_driver/generated/simulation/controlconfig_services.h" + +#include "kortex_driver/non-generated/pre_computed_joint_trajectory_action_server.h" +#include "kortex_driver/non-generated/robotiq_gripper_command_action_server.h" +#include "kortex_driver/non-generated/kortex_subscribers.h" +#include "kortex_driver/non-generated/kortex_arm_simulation.h" + +#define TCP_PORT 10000 +#define UDP_PORT 10001 + +#define MAX_CONSECUTIVE_TIMEOUTS_BEFORE_SHUTDOWN 3 + +#define GREEN_COLOR_CONSOLE "\033[92m" +#define RESET_COLOR_CONSOLE "\033[0m" + +class KortexArmDriver +{ + public: + KortexArmDriver() = delete; + KortexArmDriver(ros::NodeHandle nh); + ~KortexArmDriver(); + + void parseRosArguments(); + void initApi(); + void verifyProductConfiguration(); + void initSubscribers(); + void initRosServices(); + void startActionServers(); + + private: + + ros::NodeHandle m_node_handle; + + // False if in simulation + bool m_is_real_robot; + std::unique_ptr m_simulator; + + // Api options + std::string m_ip_address; + std::string m_username; + std::string m_password; + bool m_use_hard_limits; + int m_cyclic_data_publish_rate; + int m_api_rpc_timeout_ms; + int m_api_session_inactivity_timeout_ms; + int m_api_connection_inactivity_timeout_ms; + + // Product configuration and ROS params related to the hardware + std::string m_arm_name; + std::vector m_arm_joint_names; + + std::string m_gripper_name; + std::string m_prefix; + std::vector m_gripper_joint_names; + std::vector m_gripper_joint_limits_min; + std::vector m_gripper_joint_limits_max; + + int m_degrees_of_freedom; + + bool m_is_interconnect_module_present; + int m_interconnect_device_id; + + bool m_is_vision_module_present; + int m_vision_device_id; + + // Kortex Api objects + Kinova::Api::TransportClientTcp* m_tcp_transport; + Kinova::Api::TransportClientUdp* m_udp_transport; + + Kinova::Api::RouterClient* m_tcp_router; + Kinova::Api::RouterClient* m_udp_router; + + Kinova::Api::ActuatorConfig::ActuatorConfigClient* m_actuator_config; + Kinova::Api::Base::BaseClient* m_base; + Kinova::Api::ControlConfig::ControlConfigClient* m_control_config; + Kinova::Api::DeviceConfig::DeviceConfigClient* m_device_config; + Kinova::Api::DeviceManager::DeviceManagerClient* m_device_manager; + Kinova::Api::InterconnectConfig::InterconnectConfigClient* m_interconnect_config; + Kinova::Api::VisionConfig::VisionConfigClient* m_vision_config; + Kinova::Api::BaseCyclic::BaseCyclicClient* m_base_cyclic; + Kinova::Api::SessionManager* m_tcp_session_manager; + Kinova::Api::SessionManager* m_udp_session_manager; + + // ROS ServiceProxy's + IActuatorConfigServices* m_actuator_config_ros_services; + IBaseServices* m_base_ros_services; + IControlConfigServices* m_control_config_ros_services; + IDeviceConfigServices* m_device_config_ros_services; + IDeviceManagerServices* m_device_manager_ros_services; + IInterconnectConfigServices* m_interconnect_config_ros_services; + IVisionConfigServices* m_vision_config_ros_services; + + // Action servers + PreComputedJointTrajectoryActionServer* m_action_server_follow_joint_trajectory; + RobotiqGripperCommandActionServer* m_action_server_gripper_command; + + // Topic subscribers + KortexSubscribers* m_topic_subscribers; + + // ROS and thread objects to publish the feedback from the robot + bool m_node_is_running; + int m_consecutive_base_cyclic_timeouts; + std::mutex m_is_trajectory_running_lock; + std::thread m_publish_feedback_thread; + ros::Publisher m_pub_base_feedback; + ros::Publisher m_pub_joint_state; + KortexMathUtil m_math_util; + + // Private methods + bool isGripperPresent(); + void setAngularTrajectorySoftLimitsToMax(); + void publishRobotFeedback(); + void publishSimulationFeedback(); + void registerSimulationHandlers(); +}; + +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h new file mode 100644 index 0000000..21a0aa1 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_arm_simulation.h @@ -0,0 +1,211 @@ +#ifndef _KORTEX_ARM_SIMULATION_H_ +#define _KORTEX_ARM_SIMULATION_H_ + +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2020 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +// ROS +#include +#include +#include +#include +#include +#include + +// MoveIt +#include + +// KDL +#include +#include +#include +#include +#include + +// Standard +#include +#include +#include +#include + +// Kortex +#include "kortex_driver/non-generated/kortex_math_util.h" + +#include "kortex_driver/ActionType.h" +#include "kortex_driver/KortexError.h" +#include "kortex_driver/BaseCyclic_Feedback.h" + +#include "kortex_driver/CreateAction.h" +#include "kortex_driver/ReadAction.h" +#include "kortex_driver/ReadAllActions.h" +#include "kortex_driver/DeleteAction.h" +#include "kortex_driver/UpdateAction.h" +#include "kortex_driver/ExecuteActionFromReference.h" +#include "kortex_driver/ExecuteAction.h" +#include "kortex_driver/PauseAction.h" +#include "kortex_driver/StopAction.h" +#include "kortex_driver/ResumeAction.h" + +#include "kortex_driver/PlayCartesianTrajectory.h" +#include "kortex_driver/Stop.h" +#include "kortex_driver/GetMeasuredCartesianPose.h" +#include "kortex_driver/SendTwistCommand.h" +#include "kortex_driver/PlayJointTrajectory.h" +#include "kortex_driver/SendJointSpeedsCommand.h" +#include "kortex_driver/SendGripperCommand.h" +#include "kortex_driver/ApplyEmergencyStop.h" + +enum class ControllerType +{ + kTrajectory, // this is for the JointTrajectoryController + kIndividual // this is for the individual JointPositionController's +}; + +class KortexArmSimulation +{ + public: + KortexArmSimulation() = delete; + KortexArmSimulation(ros::NodeHandle& nh); + ~KortexArmSimulation(); + std::unordered_map GetActionsMap() const; + int GetDOF() const {return m_degrees_of_freedom;} + + kortex_driver::BaseCyclic_Feedback GetFeedback(); + + // Handlers for simulated Kortex API functions + // Actions API + kortex_driver::CreateAction::Response CreateAction(const kortex_driver::CreateAction::Request& req); + kortex_driver::ReadAction::Response ReadAction(const kortex_driver::ReadAction::Request& req); + kortex_driver::ReadAllActions::Response ReadAllActions(const kortex_driver::ReadAllActions::Request& req); + kortex_driver::DeleteAction::Response DeleteAction(const kortex_driver::DeleteAction::Request& req); + kortex_driver::UpdateAction::Response UpdateAction(const kortex_driver::UpdateAction::Request& req); + kortex_driver::ExecuteActionFromReference::Response ExecuteActionFromReference(const kortex_driver::ExecuteActionFromReference::Request& req); + kortex_driver::ExecuteAction::Response ExecuteAction(const kortex_driver::ExecuteAction::Request& req); + kortex_driver::StopAction::Response StopAction(const kortex_driver::StopAction::Request& req); + // Other RPCs + kortex_driver::PlayCartesianTrajectory::Response PlayCartesianTrajectory(const kortex_driver::PlayCartesianTrajectory::Request& req); + kortex_driver::SendTwistCommand::Response SendTwistCommand(const kortex_driver::SendTwistCommand::Request& req); + kortex_driver::PlayJointTrajectory::Response PlayJointTrajectory(const kortex_driver::PlayJointTrajectory::Request& req); + kortex_driver::SendJointSpeedsCommand::Response SendJointSpeedsCommand(const kortex_driver::SendJointSpeedsCommand::Request& req); + kortex_driver::SendGripperCommand::Response SendGripperCommand(const kortex_driver::SendGripperCommand::Request& req); + kortex_driver::Stop::Response Stop(const kortex_driver::Stop::Request& req); + kortex_driver::ApplyEmergencyStop::Response ApplyEmergencyStop(const kortex_driver::ApplyEmergencyStop::Request& req); + + private: + // ROS + ros::NodeHandle m_node_handle; + + // Publishers + ros::Publisher m_pub_action_topic; + std::vector m_pub_position_controllers; + + // Subscribers + ros::Subscriber m_sub_joint_trajectory_controller_state; + ros::Subscriber m_sub_joint_state; + ros::Subscriber m_sub_joint_speeds; + ros::Subscriber m_sub_twist; + ros::Subscriber m_sub_clear_faults; + ros::Subscriber m_sub_stop; + ros::Subscriber m_sub_emergency_stop; + + // Service clients + ros::ServiceClient m_client_switch_controllers; + ControllerType m_active_controller_type; + std::vector m_trajectory_controllers_list; + std::vector m_position_controllers_list; + std::vector m_velocity_commands; + kortex_driver::Twist m_twist_command; + + // Action clients + std::unique_ptr> m_follow_joint_trajectory_action_client; + std::unique_ptr> m_gripper_action_client; + + // Namespacing and prefixing information + std::string m_prefix; + std::string m_robot_name; + + // Arm information + std::string m_arm_name; + std::vector m_arm_joint_names; + std::vector m_arm_joint_limits_min; + std::vector m_arm_joint_limits_max; + std::vector m_arm_velocity_max_limits; + std::vector m_arm_acceleration_max_limits; + float m_max_cartesian_twist_linear; + float m_max_cartesian_twist_angular; + float m_max_cartesian_acceleration_linear; + float m_max_cartesian_acceleration_angular; + + // Gripper information + std::string m_gripper_name; + std::vector m_gripper_joint_names; + std::vector m_gripper_joint_limits_max; + std::vector m_gripper_joint_limits_min; + int m_degrees_of_freedom; + + // The indexes of the first arm joint and of the gripper joint in the "joint_states" feedback + int m_first_arm_joint_index; + int m_gripper_joint_index; + + // Action-related + std::unordered_map m_map_actions; + + // Math utility + KortexMathUtil m_math_util; + + // KDL chain, solvers and motions + KDL::Chain m_chain; + std::unique_ptr m_fk_solver; + std::unique_ptr m_ik_pos_solver; + std::unique_ptr m_ik_vel_solver; + std::vector m_velocity_trap_profiles; + + // Threading + std::atomic m_is_action_being_executed; + std::atomic m_action_preempted; + std::atomic m_current_action_type; + std::thread m_action_executor_thread; + + // MoveIt-related + std::unique_ptr m_moveit_arm_interface; + std::unique_ptr m_moveit_gripper_interface; + + // Subscription callbacks and data structures with their mutexes + void cb_joint_states(const sensor_msgs::JointState& state); + sensor_msgs::JointState m_current_state; + bool m_first_state_received; + kortex_driver::BaseCyclic_Feedback m_feedback; + std::mutex m_state_mutex; + + // Helper functions + bool IsGripperPresent() const {return !m_gripper_name.empty();} + void CreateDefaultActions(); + bool SwitchControllerType(ControllerType new_type); + void PlayAction(const kortex_driver::Action& action); + void JoinThreadAndCancelAction(); + kortex_driver::KortexError FillKortexError(uint32_t code, uint32_t subCode, const std::string& description = std::string()) const; + kortex_driver::KortexError ExecuteReachJointAngles(const kortex_driver::Action& action); + kortex_driver::KortexError ExecuteReachPose(const kortex_driver::Action& action); + kortex_driver::KortexError ExecuteSendJointSpeeds(const kortex_driver::Action& action); + kortex_driver::KortexError ExecuteSendTwist(const kortex_driver::Action& action); + kortex_driver::KortexError ExecuteSendGripperCommand(const kortex_driver::Action& action); + kortex_driver::KortexError ExecuteTimeDelay(const kortex_driver::Action& action); + + // Callbacks + void new_joint_speeds_cb(const kortex_driver::Base_JointSpeeds& joint_speeds); + void new_twist_cb(const kortex_driver::TwistCommand& twist); + void clear_faults_cb(const std_msgs::Empty& empty); + void stop_cb(const std_msgs::Empty& empty); + void emergency_stop_cb(const std_msgs::Empty& empty); +}; + +#endif //_KORTEX_ARM_SIMULATION_H_ diff --git a/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h new file mode 100644 index 0000000..59b4c85 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_math_util.h @@ -0,0 +1,37 @@ +#ifndef _KORTEX_MATH_UTIL_H_ +#define _KORTEX_MATH_UTIL_H_ + +/* + * Copyright (c) 2019 Kinova inc. All rights reserved. + * + * This software may be modified and distributed under the + * terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +#include +#include "kortex_driver/Twist.h" + +class KortexMathUtil +{ +public: + KortexMathUtil() {} + ~KortexMathUtil() {} + + static double toRad(double degree); + static double toDeg(double rad); + static int getNumberOfTurns(double rad_not_wrapped); + static double wrapRadiansFromMinusPiToPi(double rad_not_wrapped); + static double wrapRadiansFromMinusPiToPi(double rad_not_wrapped, int& number_of_turns); + static double wrapDegreesFromZeroTo360(double deg_not_wrapped); + static double wrapDegreesFromZeroTo360(double deg_not_wrapped, int& number_of_turns); + static double relative_position_from_absolute(double absolute_position, double min_value, double max_value); + static double absolute_position_from_relative(double relative_position, double min_value, double max_value); + + // kortex_driver::Twist helper functions + static kortex_driver::Twist substractTwists(const kortex_driver::Twist& a, const kortex_driver::Twist& b); +}; + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_subscribers.h b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_subscribers.h new file mode 100644 index 0000000..45ed76b --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/kortex_subscribers.h @@ -0,0 +1,55 @@ +#ifndef _KORTEX_SUBSCRIBERS_H_ +#define _KORTEX_SUBSCRIBERS_H_ + +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2020 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include +#include "std_msgs/Empty.h" +#include +#include "BaseClientRpc.h" + +#include "kortex_driver/TwistCommand.h" +#include "kortex_driver/Base_JointSpeeds.h" + +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/non-generated/kortex_math_util.h" + +class KortexSubscribers +{ + +public: + + KortexSubscribers(ros::NodeHandle& node_handle, Kinova::Api::Base::BaseClient* base); + ~KortexSubscribers(); + +private: + + ros::NodeHandle& m_node_handle; + Kinova::Api::Base::BaseClient* m_base; + + // Subscribers + ros::Subscriber m_joint_speeds_sub; + ros::Subscriber m_twist_sub; + ros::Subscriber m_clear_faults_sub; + ros::Subscriber m_stop_sub; + ros::Subscriber m_emergency_stop_sub; + + // Callbacks + void new_joint_speeds_cb(const kortex_driver::Base_JointSpeeds& joint_speeds); + void new_twist_cb(const kortex_driver::TwistCommand& twist); + void clear_faults_cb(const std_msgs::Empty& empty); + void stop_cb(const std_msgs::Empty& empty); + void emergency_stop_cb(const std_msgs::Empty& empty); +}; + +#endif //_KORTEX_SUBSCRIBERS_H_ diff --git a/ros_kortex/kortex_driver/include/kortex_driver/non-generated/pre_computed_joint_trajectory_action_server.h b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/pre_computed_joint_trajectory_action_server.h new file mode 100644 index 0000000..85bcb3b --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/pre_computed_joint_trajectory_action_server.h @@ -0,0 +1,102 @@ +#ifndef _KORTEX_PRE_COMPUTED_JOINT_TRAJECTORY_ACTION_SERVER_H_ +#define _KORTEX_PRE_COMPUTED_JOINT_TRAJECTORY_ACTION_SERVER_H_ + +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include +#include +#include +#include +#include + +#include "BaseClientRpc.h" +#include "BaseCyclicClientRpc.h" +#include "Errors.pb.h" +#include "kortex_driver/non-generated/kortex_math_util.h" + +class PreComputedJointTrajectoryActionServer +{ + public: + + enum ActionServerState + { + INITIALIZING = 0, + IDLE, + PRE_PROCESSING_PENDING, + PRE_PROCESSING_IN_PROGRESS, + TRAJECTORY_EXECUTION_PENDING, + TRAJECTORY_EXECUTION_IN_PROGRESS, + }; + + PreComputedJointTrajectoryActionServer() = delete; + PreComputedJointTrajectoryActionServer(const std::string& server_name, ros::NodeHandle& nh, Kinova::Api::Base::BaseClient* base, Kinova::Api::BaseCyclic::BaseCyclicClient* base_cyclic); + ~PreComputedJointTrajectoryActionServer(); + + ActionServerState getState() {return m_server_state;}; + + const char* actionServerStateNames[int(ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS) + 1] = + { + "INITIALIZING", + "IDLE", + "PRE_PROCESSING_PENDING", + "PRE_PROCESSING_IN_PROGRESS", + "TRAJECTORY_EXECUTION_PENDING", + "TRAJECTORY_EXECUTION_IN_PROGRESS" + }; + + private: + // Members + ros::NodeHandle m_node_handle; + actionlib::ActionServer m_server; + + Kinova::Api::Common::NotificationHandle m_sub_action_notif_handle; + + Kinova::Api::Base::BaseClient* m_base; + Kinova::Api::BaseCyclic::BaseCyclicClient* m_base_cyclic; + + std::string m_server_name; + + control_msgs::FollowJointTrajectoryFeedback m_feedback; + actionlib::ActionServer::GoalHandle m_goal; + std::chrono::system_clock::time_point m_trajectory_start_time; + std::chrono::system_clock::time_point m_trajectory_end_time; + + std::mutex m_server_state_lock; + std::mutex m_action_notification_thread_lock; + ActionServerState m_server_state; + + KortexMathUtil m_math_util; + + // ROS Params + double m_default_goal_time_tolerance; + double m_default_goal_tolerance; + std::vector m_joint_names; + std::string m_prefix; + + // Action Server Callbacks + void goal_received_callback(actionlib::ActionServer::GoalHandle new_goal_handle); + void preempt_received_callback(actionlib::ActionServer::GoalHandle goal_handle); + + // Kortex Notifications Callbacks + void action_notif_callback(Kinova::Api::Base::ActionNotification notif); + + // Private methods + bool is_goal_acceptable(actionlib::ActionServer::GoalHandle goal_handle); + bool is_goal_tolerance_respected(bool enable_prints, bool check_time_tolerance); + void stop_all_movement(); + + void set_server_state(ActionServerState s); + +}; + +#endif diff --git a/ros_kortex/kortex_driver/include/kortex_driver/non-generated/robotiq_gripper_command_action_server.h b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/robotiq_gripper_command_action_server.h new file mode 100644 index 0000000..6eb4394 --- /dev/null +++ b/ros_kortex/kortex_driver/include/kortex_driver/non-generated/robotiq_gripper_command_action_server.h @@ -0,0 +1,86 @@ +#ifndef _KORTEX_ROBOTIQ_GRIPPER_COMMAND_ACTION_SERVER_H_ +#define _KORTEX_ROBOTIQ_GRIPPER_COMMAND_ACTION_SERVER_H_ + +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include +#include +#include +#include +#include +#include + +#include "BaseClientRpc.h" +#include "BaseCyclicClientRpc.h" +#include "Errors.pb.h" + +#include "kortex_math_util.h" + +// Duration timeout for a gripper trajectory (in seconds) +#define GRIPPER_TRAJECTORY_TIME_LIMIT 2.0 + +#define MAX_GRIPPER_RELATIVE_ERROR 0.05 +#define MAX_CONSECUTIVE_POSITION_DIFFERENCE 0.01 +#define MAX_CONSECUTIVE_IDENTICAL_POSITIONS 4 + +class RobotiqGripperCommandActionServer +{ + public: + RobotiqGripperCommandActionServer() = delete; + RobotiqGripperCommandActionServer(const std::string& server_name, const std::string& gripper_joint_name, double gripper_joint_limit_min, double gripper_joint_limit_max, ros::NodeHandle& nh, Kinova::Api::Base::BaseClient* base, Kinova::Api::BaseCyclic::BaseCyclicClient* base_cyclic); + ~RobotiqGripperCommandActionServer(); + + private: + // Members + ros::NodeHandle m_node_handle; + actionlib::ActionServer m_server; + + Kinova::Api::Common::NotificationHandle m_sub_action_notif_handle; + + Kinova::Api::Base::GripperCommand m_cancel_gripper_command; + + Kinova::Api::Base::BaseClient* m_base; + Kinova::Api::BaseCyclic::BaseCyclicClient* m_base_cyclic; + + std::string m_server_name; + + control_msgs::GripperCommandFeedback m_feedback; + actionlib::ActionServer::GoalHandle m_goal; + std::chrono::system_clock::time_point m_trajectory_start_time; + + bool m_is_trajectory_running; + std::mutex m_is_trajectory_running_lock; + std::thread m_gripper_position_polling_thread; + + KortexMathUtil m_math_util; + + // ROS Params + std::string m_gripper_joint_name; + double m_gripper_joint_limit_min; + double m_gripper_joint_limit_max; + + // Action Server Callbacks + void goal_received_callback(actionlib::ActionServer::GoalHandle new_goal_handle); + void preempt_received_callback(actionlib::ActionServer::GoalHandle goal_handle); + + // Polling thread function + void gripper_position_polling_thread(); + + // Private methods + bool is_goal_acceptable(actionlib::ActionServer::GoalHandle goal_handle); + bool is_goal_tolerance_respected(); + void stop_all_movement(); + void join_polling_thread(); +}; + +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/launch/kortex_driver.launch b/ros_kortex/kortex_driver/launch/kortex_driver.launch new file mode 100644 index 0000000..94a644b --- /dev/null +++ b/ros_kortex/kortex_driver/launch/kortex_driver.launch @@ -0,0 +1,170 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [base_feedback/joint_state] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + topics: + - name: /$(arg robot_name)/base_feedback + timeout: 10 + negative: False + - name: /$(arg robot_name)/base_feedback/joint_state + timeout: 10 + negative: False + - name: /$(arg robot_name)/joint_states + timeout: 10 + negative: False + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_driver/launch/kortex_dual_driver.launch b/ros_kortex/kortex_driver/launch/kortex_dual_driver.launch new file mode 100644 index 0000000..0e79d2c --- /dev/null +++ b/ros_kortex/kortex_driver/launch/kortex_dual_driver.launch @@ -0,0 +1,132 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + launch-prefix="gdb -ex run args" + + + + + + + + + + + + + + + + + + + + launch-prefix="gdb -ex run args" + + + + + + + + + + + + + + + + + + + + + + + + [$(arg left_robot_name)/base_feedback/joint_state, $(arg right_robot_name)/base_feedback/joint_state] + + + + + + + + + diff --git a/ros_kortex/kortex_driver/msg/generated/ErrorCodes.msg b/ros_kortex/kortex_driver/msg/generated/ErrorCodes.msg new file mode 100644 index 0000000..d3731e8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/ErrorCodes.msg @@ -0,0 +1,10 @@ + +uint32 ERROR_NONE = 0 + +uint32 ERROR_PROTOCOL_SERVER = 1 + +uint32 ERROR_PROTOCOL_CLIENT = 2 + +uint32 ERROR_DEVICE = 3 + +uint32 ERROR_INTERNAL = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/SubErrorCodes.msg b/ros_kortex/kortex_driver/msg/generated/SubErrorCodes.msg new file mode 100644 index 0000000..a5797ae --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/SubErrorCodes.msg @@ -0,0 +1,194 @@ + +uint32 SUB_ERROR_NONE = 0 + +uint32 METHOD_FAILED = 1 + +uint32 UNIMPLEMENTED = 2 + +uint32 INVALID_PARAM = 3 + +uint32 UNSUPPORTED_SERVICE = 4 + +uint32 UNSUPPORTED_METHOD = 5 + +uint32 TOO_LARGE_ENCODED_FRAME_BUFFER = 6 + +uint32 FRAME_ENCODING_ERR = 7 + +uint32 FRAME_DECODING_ERR = 8 + +uint32 INCOMPATIBLE_HEADER_VERSION = 9 + +uint32 UNSUPPORTED_FRAME_TYPE = 10 + +uint32 UNREGISTERED_NOTIFICATION_RECEIVED = 11 + +uint32 INVALID_SESSION = 12 + +uint32 PAYLOAD_DECODING_ERR = 13 + +uint32 UNREGISTERED_FRAME_RECEIVED = 14 + +uint32 INVALID_PASSWORD = 15 + +uint32 USER_NOT_FOUND = 16 + +uint32 ENTITY_NOT_FOUND = 17 + +uint32 ROBOT_MOVEMENT_IN_PROGRESS = 18 + +uint32 ROBOT_NOT_MOVING = 19 + +uint32 NO_MORE_STORAGE_SPACE = 20 + +uint32 ROBOT_NOT_READY = 21 + +uint32 ROBOT_IN_FAULT = 22 + +uint32 ROBOT_IN_MAINTENANCE = 23 + +uint32 ROBOT_IN_UPDATE_MODE = 24 + +uint32 ROBOT_IN_EMERGENCY_STOP = 25 + +uint32 SINGLE_LEVEL_SERVOING = 26 + +uint32 LOW_LEVEL_SERVOING = 27 + +uint32 MAPPING_GROUP_NON_ROOT = 28 + +uint32 MAPPING_INVALID_GROUP = 29 + +uint32 MAPPING_INVALID_MAP = 30 + +uint32 MAP_GROUP_INVALID_MAP = 31 + +uint32 MAP_GROUP_INVALID_PARENT = 32 + +uint32 MAP_GROUP_INVALID_CHILD = 33 + +uint32 MAP_GROUP_INVALID_MOVE = 34 + +uint32 MAP_IN_USE = 35 + +uint32 WIFI_CONNECT_ERROR = 36 + +uint32 UNSUPPORTED_NETWORK_TYPE = 37 + +uint32 TOO_LARGE_ENCODED_PAYLOAD_BUFFER = 38 + +uint32 UPDATE_PERMISSION_DENIED = 39 + +uint32 DELETE_PERMISSION_DENIED = 40 + +uint32 DATABASE_ERROR = 41 + +uint32 UNSUPPORTED_OPTION = 42 + +uint32 UNSUPPORTED_RESOLUTION = 43 + +uint32 UNSUPPORTED_FRAME_RATE = 44 + +uint32 UNSUPPORTED_BIT_RATE = 45 + +uint32 UNSUPPORTED_ACTION = 46 + +uint32 UNSUPPORTED_FOCUS_ACTION = 47 + +uint32 VALUE_IS_ABOVE_MAXIMUM = 48 + +uint32 VALUE_IS_BELOW_MINIMUM = 49 + +uint32 DEVICE_DISCONNECTED = 50 + +uint32 DEVICE_NOT_READY = 51 + +uint32 INVALID_DEVICE = 52 + +uint32 SAFETY_THRESHOLD_REACHED = 53 + +uint32 INVALID_USER_SESSION_ACCESS = 54 + +uint32 CONTROL_MANUAL_STOP = 55 + +uint32 CONTROL_OUTSIDE_WORKSPACE = 56 + +uint32 CONTROL_ACTUATOR_COUNT_MISMATCH = 57 + +uint32 CONTROL_INVALID_DURATION = 58 + +uint32 CONTROL_INVALID_SPEED = 59 + +uint32 CONTROL_LARGE_SPEED = 60 + +uint32 CONTROL_INVALID_ACCELERATION = 61 + +uint32 CONTROL_INVALID_TIME_STEP = 62 + +uint32 CONTROL_LARGE_SIZE = 63 + +uint32 CONTROL_WRONG_MODE = 64 + +uint32 CONTROL_JOINT_POSITION_LIMIT = 65 + +uint32 CONTROL_NO_FILE_IN_MEMORY = 66 + +uint32 CONTROL_INDEX_OUT_OF_TRAJECTORY = 67 + +uint32 CONTROL_ALREADY_RUNNING = 68 + +uint32 CONTROL_WRONG_STARTING_POINT = 69 + +uint32 CONTROL_CARTESIAN_CANNOT_START = 70 + +uint32 CONTROL_UNDEFINED_CONSTRAINT = 71 + +uint32 CONTROL_UNINITIALIZED = 72 + +uint32 CONTROL_NO_ACTION = 73 + +uint32 CONTROL_UNDEFINED = 74 + +uint32 WRONG_SERVOING_MODE = 75 + +uint32 CONTROL_WRONG_STARTING_SPEED = 76 + +uint32 USERNAME_LENGTH_EXCEEDED = 100 + +uint32 FIRSTNAME_LENGTH_EXCEEDED = 101 + +uint32 LASTNAME_LENGTH_EXCEEDED = 102 + +uint32 PASSWORD_LENGTH_EXCEEDED = 103 + +uint32 USERNAME_ALREADY_EXISTS = 104 + +uint32 USERNAME_EMPTY = 105 + +uint32 PASSWORD_NOT_CHANGED = 106 + +uint32 MAXIMUM_USER_PROFILES_USED = 107 + +uint32 ROUTER_UNVAILABLE = 108 + +uint32 ADDRESS_NOT_IN_VALID_RANGE = 120 + +uint32 ADDRESS_NOT_CONFIGURABLE = 121 + +uint32 SESSION_NOT_IN_CONTROL = 130 + +uint32 METHOD_TIMEOUT = 131 + +uint32 UNSUPPORTED_ROBOT_CONFIGURATION = 132 + +uint32 NVRAM_READ_FAIL = 133 + +uint32 NVRAM_WRITE_FAIL = 134 + +uint32 NETWORK_NO_ADDRESS_ASSIGNED = 135 + +uint32 READ_PERMISSION_DENIED = 136 + +uint32 CONTROLLER_INVALID_MAPPING = 137 + +uint32 ACTION_IN_USE = 138 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ControlMode.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ControlMode.msg new file mode 100644 index 0000000..7f80fdc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ControlMode.msg @@ -0,0 +1,12 @@ + +uint32 NONE = 0 + +uint32 POSITION = 1 + +uint32 VELOCITY = 2 + +uint32 TORQUE = 3 + +uint32 CURRENT = 4 + +uint32 CUSTOM = 5 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ControlModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ControlModeInformation.msg new file mode 100644 index 0000000..713ed37 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ControlModeInformation.msg @@ -0,0 +1,2 @@ + +uint32 control_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_SafetyLimitType.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_SafetyLimitType.msg new file mode 100644 index 0000000..a8d7a17 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_SafetyLimitType.msg @@ -0,0 +1,4 @@ + +uint32 MAXIMAL_LIMIT = 0 + +uint32 MINIMAL_LIMIT = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ActuatorConfig_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/AxisOffsets.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/AxisOffsets.msg new file mode 100644 index 0000000..eb4136d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/AxisOffsets.msg @@ -0,0 +1,3 @@ + +float32 absolute_offset +float32 relative_offset \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/AxisPosition.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/AxisPosition.msg new file mode 100644 index 0000000..95750a0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/AxisPosition.msg @@ -0,0 +1,2 @@ + +float32 position \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/CoggingFeedforwardMode.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/CoggingFeedforwardMode.msg new file mode 100644 index 0000000..2e6d795 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/CoggingFeedforwardMode.msg @@ -0,0 +1,6 @@ + +uint32 FEEDFORWARD_OFF = 0 + +uint32 FEEDFORWARD_ADAPTIVE = 1 + +uint32 FEEDFORWARD_CALIBRATED = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/CoggingFeedforwardModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/CoggingFeedforwardModeInformation.msg new file mode 100644 index 0000000..6fe1630 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/CoggingFeedforwardModeInformation.msg @@ -0,0 +1,2 @@ + +uint32 cogging_feedforward_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/CommandMode.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/CommandMode.msg new file mode 100644 index 0000000..fad4f4d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/CommandMode.msg @@ -0,0 +1,12 @@ + +uint32 CYCLIC = 0 + +uint32 ASYNC_CYCLIC_FLAGS = 1 + +uint32 ASYNC = 2 + +uint32 CYCLIC_JITTERCOMPENSATED_POSITION = 3 + +uint32 CYCLIC_JITTERCOMPENSATED_VELOCITY = 4 + +uint32 CYCLIC_JITTERCOMPENSATED_ACCELERATION = 5 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/CommandModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/CommandModeInformation.msg new file mode 100644 index 0000000..f066818 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/CommandModeInformation.msg @@ -0,0 +1,2 @@ + +uint32 command_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoop.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoop.msg new file mode 100644 index 0000000..715ca4b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoop.msg @@ -0,0 +1,2 @@ + +uint32 control_loop \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoopParameters.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoopParameters.msg new file mode 100644 index 0000000..5cad290 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoopParameters.msg @@ -0,0 +1,7 @@ + +uint32 loop_selection +float32 error_saturation +float32 output_saturation +float32[] kAz +float32[] kBz +float32 error_dead_band \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoopSelection.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoopSelection.msg new file mode 100644 index 0000000..6b62093 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/ControlLoopSelection.msg @@ -0,0 +1,14 @@ + +uint32 RESERVED = 0 + +uint32 JOINT_POSITION = 1 + +uint32 MOTOR_POSITION = 2 + +uint32 JOINT_VELOCITY = 4 + +uint32 MOTOR_VELOCITY = 8 + +uint32 JOINT_TORQUE = 16 + +uint32 MOTOR_CURRENT = 32 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/CustomDataIndex.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/CustomDataIndex.msg new file mode 100644 index 0000000..c7a9b45 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/CustomDataIndex.msg @@ -0,0 +1,190 @@ + +uint32 NO_CUSTOM_DATA_SELECTED = 0 + +uint32 UINT32_TEST_RAMP = 1 + +uint32 UINT32_MOTOR_ENCODER_RAW = 2 + +uint32 UINT32_JOINT_ENCODER_RAW = 3 + +uint32 FLOAT_TEMPERATURE_PHASE_0 = 4 + +uint32 FLOAT_TEMPERATURE_PHASE_1 = 5 + +uint32 FLOAT_TEMPERATURE_PHASE_2 = 6 + +uint32 INT32_TORQUE_SENSOR_RAW_0 = 7 + +uint32 INT32_TORQUE_SENSOR_RAW_1 = 8 + +uint32 INT32_TORQUE_SENSOR_RAW_2 = 9 + +uint32 INT32_TORQUE_SENSOR_RAW_3 = 10 + +uint32 FLOAT_TORQUE_SENSOR_0 = 11 + +uint32 FLOAT_TORQUE_SENSOR_1 = 12 + +uint32 FLOAT_TORQUE_SENSOR_2 = 13 + +uint32 FLOAT_TORQUE_SENSOR_3 = 14 + +uint32 UINT32_MOTOR_ENCODER_RAW_LATCH_ON_INDEX_RISING = 15 + +uint32 UINT32_JOINT_ENCODER_RAW_LATCH_ON_INDEX_RISING = 16 + +uint32 UINT32_ABSOLUTE_POSITION_SENSOR_RAW = 17 + +uint32 FLOAT_ABSOLUTE_POSITION_SENSOR = 18 + +uint32 FLOAT_CONTROL_POSITION_JOINT_REQUESTED = 19 + +uint32 UINT32_JIG_FLAGS = 20 + +uint32 UINT32_TICK_MOTOR_CONTROL = 21 + +uint32 UINT32_TICK_JOINT_CONTROL = 22 + +uint32 UINT32_INDEX_TICK_MOTOR_CONTROL = 23 + +uint32 UINT32_INDEX_TICK_JOINT_CONTROL = 24 + +uint32 FLOAT_ACCELERATION_X = 25 + +uint32 FLOAT_ACCELERATION_Y = 26 + +uint32 FLOAT_ACCELERATION_Z = 27 + +uint32 FLOAT_ANGULAR_RATE_X = 28 + +uint32 FLOAT_ANGULAR_RATE_Y = 29 + +uint32 FLOAT_ANGULAR_RATE_Z = 30 + +uint32 FLOAT_POSITION_MOTOR_CMD = 31 + +uint32 FLOAT_VELOCITY_MOTOR_CMD = 32 + +uint32 FLOAT_POSITION_MOTOR = 33 + +uint32 FLOAT_VELOCITY_MOTOR = 34 + +uint32 UINT32_COMMUNICATIONS_JITTER = 35 + +uint32 FLOAT_TORQUE_AVERAGE = 36 + +uint32 FLOAT_CURRENT_MOTOR = 37 + +uint32 FLOAT_VOLTAGE_DIGITAL = 38 + +uint32 FLOAT_TEMPERATURE_MOTOR_CELSIUS = 39 + +uint32 FLOAT_TEMPERATURE_CORE_CELSIUS = 40 + +uint32 UINT32_FAULT_A = 41 + +uint32 UINT32_FAULT_B = 42 + +uint32 UINT32_WARNING_A = 43 + +uint32 UINT32_WARNING_B = 44 + +uint32 FLOAT_POSITION_FROM_HALLS = 45 + +uint32 FLOAT_PHASE_CURRENT_0 = 46 + +uint32 FLOAT_PHASE_CURRENT_1 = 47 + +uint32 FLOAT_PHASE_CURRENT_2 = 48 + +uint32 FLOAT_PHASE_PWM_0 = 49 + +uint32 FLOAT_PHASE_PWM_1 = 50 + +uint32 FLOAT_PHASE_PWM_2 = 51 + +uint32 FLOAT_MOTOR_ELECTRICAL_ANGLE = 52 + +uint32 FLOAT_CURRENT_MOTOR_CMD = 53 + +uint32 FLOAT_TORQUE_JOINT_CMD = 54 + +uint32 FLOAT_POSITION_UNWRAPPED = 55 + +uint32 UINT32_HALL_SENSOR_0 = 56 + +uint32 UINT32_HALL_SENSOR_1 = 57 + +uint32 UINT32_HALL_SENSOR_2 = 58 + +uint32 INT32_HALL_SENSOR_SCALED_0 = 59 + +uint32 INT32_HALL_SENSOR_SCALED_1 = 60 + +uint32 INT32_HALL_SENSOR_SCALED_2 = 61 + +uint32 FLOAT_COGGING_COEFFICIENT_A_0 = 62 + +uint32 FLOAT_COGGING_COEFFICIENT_A_1 = 63 + +uint32 FLOAT_COGGING_COEFFICIENT_A_2 = 64 + +uint32 FLOAT_COGGING_COEFFICIENT_A_3 = 65 + +uint32 FLOAT_COGGING_COEFFICIENT_A_4 = 66 + +uint32 FLOAT_COGGING_COEFFICIENT_A_5 = 67 + +uint32 FLOAT_COGGING_COEFFICIENT_A_6 = 68 + +uint32 FLOAT_COGGING_COEFFICIENT_A_7 = 69 + +uint32 FLOAT_COGGING_COEFFICIENT_A_8 = 70 + +uint32 FLOAT_COGGING_COEFFICIENT_A_9 = 71 + +uint32 FLOAT_COGGING_COEFFICIENT_A_10 = 72 + +uint32 FLOAT_COGGING_COEFFICIENT_A_11 = 73 + +uint32 FLOAT_COGGING_COEFFICIENT_A_12 = 74 + +uint32 FLOAT_COGGING_COEFFICIENT_A_13 = 75 + +uint32 FLOAT_COGGING_COEFFICIENT_A_14 = 76 + +uint32 FLOAT_COGGING_COEFFICIENT_A_15 = 77 + +uint32 FLOAT_COGGING_COEFFICIENT_B_0 = 78 + +uint32 FLOAT_COGGING_COEFFICIENT_B_1 = 79 + +uint32 FLOAT_COGGING_COEFFICIENT_B_2 = 80 + +uint32 FLOAT_COGGING_COEFFICIENT_B_3 = 81 + +uint32 FLOAT_COGGING_COEFFICIENT_B_4 = 82 + +uint32 FLOAT_COGGING_COEFFICIENT_B_5 = 83 + +uint32 FLOAT_COGGING_COEFFICIENT_B_6 = 84 + +uint32 FLOAT_COGGING_COEFFICIENT_B_7 = 85 + +uint32 FLOAT_COGGING_COEFFICIENT_B_8 = 86 + +uint32 FLOAT_COGGING_COEFFICIENT_B_9 = 87 + +uint32 FLOAT_COGGING_COEFFICIENT_B_10 = 88 + +uint32 FLOAT_COGGING_COEFFICIENT_B_11 = 89 + +uint32 FLOAT_COGGING_COEFFICIENT_B_12 = 90 + +uint32 FLOAT_COGGING_COEFFICIENT_B_13 = 91 + +uint32 FLOAT_COGGING_COEFFICIENT_B_14 = 92 + +uint32 FLOAT_COGGING_COEFFICIENT_B_15 = 93 + +uint32 FLOAT_CURRENT_COGGING_FEEDFORWARD = 94 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/CustomDataSelection.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/CustomDataSelection.msg new file mode 100644 index 0000000..84a6107 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/CustomDataSelection.msg @@ -0,0 +1,2 @@ + +uint32[] channel \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/EncoderDerivativeParameters.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/EncoderDerivativeParameters.msg new file mode 100644 index 0000000..df323b3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/EncoderDerivativeParameters.msg @@ -0,0 +1,3 @@ + +uint32 max_window_width +float32 min_angle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/FrequencyResponse.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/FrequencyResponse.msg new file mode 100644 index 0000000..957c975 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/FrequencyResponse.msg @@ -0,0 +1,6 @@ + +uint32 loop_selection +float32 min_frequency +float32 max_frequency +float32 amplitude +float32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/LoopSelection.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/LoopSelection.msg new file mode 100644 index 0000000..66fdae0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/LoopSelection.msg @@ -0,0 +1,2 @@ + +uint32 loop_selection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/PositionCommand.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/PositionCommand.msg new file mode 100644 index 0000000..a0477a5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/PositionCommand.msg @@ -0,0 +1,4 @@ + +float32 position +float32 velocity +float32 acceleration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/RampResponse.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/RampResponse.msg new file mode 100644 index 0000000..846abc0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/RampResponse.msg @@ -0,0 +1,5 @@ + +uint32 loop_selection +float32 slope +float32 ramp_delay +float32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/SafetyIdentifierBankA.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/SafetyIdentifierBankA.msg new file mode 100644 index 0000000..8af8dc2 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/SafetyIdentifierBankA.msg @@ -0,0 +1,56 @@ + +uint32 UNSPECIFIED_ACTUATOR_SAFETY_IDENTIFIER_BANK_A = 0 + +uint32 FOLLOWING_ERROR = 1 + +uint32 MAXIMUM_VELOCITY = 2 + +uint32 JOINT_LIMIT_HIGH = 4 + +uint32 JOINT_LIMIT_LOW = 8 + +uint32 STRAIN_GAUGE_MISMATCH = 16 + +uint32 MAXIMUM_TORQUE = 32 + +uint32 UNRELIABLE_ABSOLUTE_POSITION = 64 + +uint32 MAGNETIC_POSITION = 128 + +uint32 HALL_POSITION = 256 + +uint32 HALL_SEQUENCE = 512 + +uint32 INPUT_ENCODER_HALL_MISMATCH = 1024 + +uint32 INPUT_ENCODER_INDEX_MISMATCH = 2048 + +uint32 INPUT_ENCODER_MAGNETIC_MISMATCH = 4096 + +uint32 MAXIMUM_MOTOR_CURRENT = 8192 + +uint32 MOTOR_CURRENT_MISMATCH = 16384 + +uint32 MAXIMUM_VOLTAGE = 32768 + +uint32 MINIMUM_VOLTAGE = 65536 + +uint32 MAXIMUM_MOTOR_TEMPERATURE = 131072 + +uint32 MAXIMUM_CORE_TEMPERATURE = 262144 + +uint32 NON_VOLATILE_MEMORY_CORRUPTED = 524288 + +uint32 MOTOR_DRIVER_FAULT = 1048576 + +uint32 EMERGENCY_LINE_ASSERTED = 2097152 + +uint32 COMMUNICATION_TICK_LOST = 4194304 + +uint32 WATCHDOG_TRIGGERED = 8388608 + +uint32 UNRELIABLE_CAPACITIVE_SENSOR = 16777216 + +uint32 UNEXPECTED_GEAR_RATIO = 33554432 + +uint32 HALL_MAGNETIC_MISMATCH = 67108864 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/Servoing.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/Servoing.msg new file mode 100644 index 0000000..8e3e7a7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/Servoing.msg @@ -0,0 +1,2 @@ + +bool enabled \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/StepResponse.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/StepResponse.msg new file mode 100644 index 0000000..64fa125 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/StepResponse.msg @@ -0,0 +1,5 @@ + +uint32 loop_selection +float32 amplitude +float32 step_delay +float32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/TorqueCalibration.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/TorqueCalibration.msg new file mode 100644 index 0000000..63568bf --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/TorqueCalibration.msg @@ -0,0 +1,5 @@ + +float32 global_gain +float32 global_offset +float32[] gain +float32[] offset \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/TorqueOffset.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/TorqueOffset.msg new file mode 100644 index 0000000..1087bce --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/TorqueOffset.msg @@ -0,0 +1,2 @@ + +float32 torque_offset \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_config/VectorDriveParameters.msg b/ros_kortex/kortex_driver/msg/generated/actuator_config/VectorDriveParameters.msg new file mode 100644 index 0000000..91b822d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_config/VectorDriveParameters.msg @@ -0,0 +1,5 @@ + +float32 kpq +float32 kiq +float32 kpd +float32 kid \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_Command.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_Command.msg new file mode 100644 index 0000000..a81238c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_Command.msg @@ -0,0 +1,7 @@ + +ActuatorCyclic_MessageId command_id +uint32 flags +float32 position +float32 velocity +float32 torque_joint +float32 current_motor \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_CustomData.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_CustomData.msg new file mode 100644 index 0000000..f6f20ed --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_CustomData.msg @@ -0,0 +1,18 @@ + +ActuatorCyclic_MessageId custom_data_id +uint32 custom_data_0 +uint32 custom_data_1 +uint32 custom_data_2 +uint32 custom_data_3 +uint32 custom_data_4 +uint32 custom_data_5 +uint32 custom_data_6 +uint32 custom_data_7 +uint32 custom_data_8 +uint32 custom_data_9 +uint32 custom_data_10 +uint32 custom_data_11 +uint32 custom_data_12 +uint32 custom_data_13 +uint32 custom_data_14 +uint32 custom_data_15 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_Feedback.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_Feedback.msg new file mode 100644 index 0000000..a5737e6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_Feedback.msg @@ -0,0 +1,15 @@ + +ActuatorCyclic_MessageId feedback_id +uint32 status_flags +uint32 jitter_comm +float32 position +float32 velocity +float32 torque +float32 current_motor +float32 voltage +float32 temperature_motor +float32 temperature_core +uint32 fault_bank_a +uint32 fault_bank_b +uint32 warning_bank_a +uint32 warning_bank_b \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_MessageId.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_MessageId.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_MessageId.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/ActuatorCyclic_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/CommandFlags.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/CommandFlags.msg new file mode 100644 index 0000000..2440642 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/CommandFlags.msg @@ -0,0 +1,22 @@ + +uint32 NO_COMMAND = 0 + +uint32 SERVO_ENABLE = 1 + +uint32 BRAKE_DISABLE = 2 + +uint32 CLEAR_MAJOR_FAULT = 4 + +uint32 CLEAR_MINOR_FAULT = 8 + +uint32 PROTECTIVE_STOP = 16 + +uint32 FORCE_BRAKE_RELEASE = 32 + +uint32 IGNORE = 64 + +uint32 LOW_GAINS = 128 + +uint32 LED_0 = 256 + +uint32 LED_1 = 512 diff --git a/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/StatusFlags.msg b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/StatusFlags.msg new file mode 100644 index 0000000..3f62915 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/actuator_cyclic/StatusFlags.msg @@ -0,0 +1,50 @@ + +uint32 UNKNOWN_STATUS = 0 + +uint32 STABILIZED = 16 + +uint32 MOTOR_INDEXED = 32 + +uint32 MOTOR_INDEXING = 64 + +uint32 JOINT_INDEXED = 128 + +uint32 JOINT_INDEXING = 256 + +uint32 HIGH_PRECISION = 512 + +uint32 BRAKING = 1024 + +uint32 SERVOING = 2048 + +uint32 MAJOR_FAULT = 4096 + +uint32 MINOR_FAULT = 8192 + +uint32 CALIBRATED_TORQUE = 16384 + +uint32 CALIBRATED_MAG_SENSOR = 32768 + +uint32 CALIBRATED_ZERO = 65536 + +uint32 GPIO_0 = 131072 + +uint32 GPIO_1 = 262144 + +uint32 CS_QUASI_STATIC_CONTACT = 524288 + +uint32 CS_TRANSIENT_CONTACT = 1048576 + +uint32 VFD_HALL_SYNC = 2097152 + +uint32 VFD_INDEXED = 4194304 + +uint32 DRIVE_BOARD_READY = 8388608 + +uint32 CALIBRATED_CURRENT = 16777216 + +uint32 CALIBRATED_MOTOR = 33554432 + +uint32 SW0_ACTIVE = 67108864 + +uint32 SW1_ACTIVE = 134217728 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Action.msg b/ros_kortex/kortex_driver/msg/generated/base/Action.msg new file mode 100644 index 0000000..e832d63 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Action.msg @@ -0,0 +1,5 @@ + +ActionHandle handle +string name +string application_data +Action_action_parameters oneof_action_parameters \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionEvent.msg new file mode 100644 index 0000000..27e0889 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionEvent.msg @@ -0,0 +1,22 @@ + +uint32 UNSPECIFIED_ACTION_EVENT = 0 + +uint32 ACTION_END = 1 + +uint32 ACTION_ABORT = 2 + +uint32 ACTION_PAUSE = 3 + +uint32 ACTION_START = 4 + +uint32 ACTION_PREPROCESS_START = 5 + +uint32 ACTION_PREPROCESS_ABORT = 6 + +uint32 ACTION_PREPROCESS_END = 7 + +uint32 ACTION_POSTPROCESS_START = 8 + +uint32 ACTION_POSTPROCESS_ABORT = 9 + +uint32 ACTION_POSTPROCESS_END = 10 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionExecutionState.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionExecutionState.msg new file mode 100644 index 0000000..9994e7f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionExecutionState.msg @@ -0,0 +1,3 @@ + +uint32 action_event +ActionHandle handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionHandle.msg new file mode 100644 index 0000000..723cdcd --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionHandle.msg @@ -0,0 +1,4 @@ + +uint32 identifier +uint32 action_type +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionList.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionList.msg new file mode 100644 index 0000000..cec55d4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionList.msg @@ -0,0 +1,2 @@ + +Action[] action_list \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionNotification.msg new file mode 100644 index 0000000..097c002 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionNotification.msg @@ -0,0 +1,7 @@ + +uint32 action_event +ActionHandle handle +Timestamp timestamp +UserProfileHandle user_handle +uint32 abort_details +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionNotificationList.msg new file mode 100644 index 0000000..8ba0600 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionNotificationList.msg @@ -0,0 +1,2 @@ + +ActionNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActionType.msg b/ros_kortex/kortex_driver/msg/generated/base/ActionType.msg new file mode 100644 index 0000000..d9afad2 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActionType.msg @@ -0,0 +1,42 @@ + +uint32 UNSPECIFIED_ACTION = 0 + +uint32 SEND_TWIST_COMMAND = 1 + +uint32 SEND_WRENCH_COMMAND = 2 + +uint32 SEND_JOINT_SPEEDS = 4 + +uint32 REACH_POSE = 6 + +uint32 REACH_JOINT_ANGLES = 7 + +uint32 TOGGLE_ADMITTANCE_MODE = 13 + +uint32 SNAPSHOT = 14 + +uint32 SWITCH_CONTROL_MAPPING = 16 + +uint32 NAVIGATE_JOINTS = 17 + +uint32 NAVIGATE_MAPPINGS = 18 + +uint32 CHANGE_TWIST = 22 + +uint32 CHANGE_JOINT_SPEEDS = 23 + +uint32 CHANGE_WRENCH = 25 + +uint32 APPLY_EMERGENCY_STOP = 28 + +uint32 CLEAR_FAULTS = 29 + +uint32 TIME_DELAY = 31 + +uint32 EXECUTE_ACTION = 32 + +uint32 SEND_GRIPPER_COMMAND = 33 + +uint32 STOP_ACTION = 35 + +uint32 PLAY_PRE_COMPUTED_TRAJECTORY = 39 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Action_action_parameters.msg b/ros_kortex/kortex_driver/msg/generated/base/Action_action_parameters.msg new file mode 100644 index 0000000..a5a2853 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Action_action_parameters.msg @@ -0,0 +1,21 @@ + +TwistCommand[] send_twist_command +WrenchCommand[] send_wrench_command +Base_JointSpeeds[] send_joint_speeds +ConstrainedPose[] reach_pose +ConstrainedJointAngles[] reach_joint_angles +uint32[] toggle_admittance_mode +Snapshot[] snapshot +SwitchControlMapping[] switch_control_mapping +uint32[] navigate_joints +uint32[] navigate_mappings +ChangeTwist[] change_twist +ChangeJointSpeeds[] change_joint_speeds +ChangeWrench[] change_wrench +EmergencyStop[] apply_emergency_stop +Faults[] clear_faults +Delay[] delay +ActionHandle[] execute_action +GripperCommand[] send_gripper_command +Base_Stop[] stop_action +PreComputedJointTrajectory[] play_pre_computed_trajectory \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActivateMapHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/ActivateMapHandle.msg new file mode 100644 index 0000000..32c0e0c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActivateMapHandle.msg @@ -0,0 +1,4 @@ + +MappingHandle mapping_handle +MapGroupHandle map_group_handle +MapHandle map_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ActuatorInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/ActuatorInformation.msg new file mode 100644 index 0000000..1f71357 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ActuatorInformation.msg @@ -0,0 +1,2 @@ + +uint32 count \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Admittance.msg b/ros_kortex/kortex_driver/msg/generated/base/Admittance.msg new file mode 100644 index 0000000..66e0c52 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Admittance.msg @@ -0,0 +1,2 @@ + +uint32 admittance_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/AdmittanceMode.msg b/ros_kortex/kortex_driver/msg/generated/base/AdmittanceMode.msg new file mode 100644 index 0000000..95037f2 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/AdmittanceMode.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_ADMITTANCE_MODE = 0 + +uint32 CARTESIAN = 1 + +uint32 JOINT = 2 + +uint32 NULL_SPACE = 3 + +uint32 DISABLED = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/AdvancedSequenceHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/AdvancedSequenceHandle.msg new file mode 100644 index 0000000..850ec7f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/AdvancedSequenceHandle.msg @@ -0,0 +1,3 @@ + +SequenceHandle handle +bool in_loop \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/AppendActionInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/AppendActionInformation.msg new file mode 100644 index 0000000..1cbde10 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/AppendActionInformation.msg @@ -0,0 +1,3 @@ + +SequenceHandle sequence_handle +Action action \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ArmStateInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/ArmStateInformation.msg new file mode 100644 index 0000000..75f77cc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ArmStateInformation.msg @@ -0,0 +1,3 @@ + +uint32 active_state +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ArmStateNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ArmStateNotification.msg new file mode 100644 index 0000000..d000f24 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ArmStateNotification.msg @@ -0,0 +1,4 @@ + +uint32 active_state +Timestamp timestamp +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/BackupEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/BackupEvent.msg new file mode 100644 index 0000000..28f21b3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BackupEvent.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_BACKUP_EVENT = 0 + +uint32 BACKUP_RESTORED = 1 + +uint32 BACKUP_UPLOADED = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_CapSenseConfig.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_CapSenseConfig.msg new file mode 100644 index 0000000..83b1f55 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_CapSenseConfig.msg @@ -0,0 +1,7 @@ + +uint32 identifier +uint32 mode +float32 threshold_a +float32 threshold_b +float32 sensitivity_a +float32 sensitivity_b \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_CapSenseMode.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_CapSenseMode.msg new file mode 100644 index 0000000..5a7abc4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_CapSenseMode.msg @@ -0,0 +1,12 @@ + +uint32 RESERVED = 0 + +uint32 INACTIVE = 1 + +uint32 ACTIVE_AUTO_THRESHOLD = 2 + +uint32 ACTIVE_NOISE_ATT = 4 + +uint32 ACTIVE_NORMAL = 5 + +uint32 CONFIGURATION = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_ControlMode.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_ControlMode.msg new file mode 100644 index 0000000..0ded911 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_ControlMode.msg @@ -0,0 +1,22 @@ + +uint32 UNSPECIFIED_CONTROL_MODE = 0 + +uint32 ANGULAR_JOYSTICK = 1 + +uint32 CARTESIAN_JOYSTICK = 2 + +uint32 ANGULAR_TRAJECTORY = 4 + +uint32 CARTESIAN_TRAJECTORY = 5 + +uint32 CARTESIAN_ADMITTANCE = 6 + +uint32 JOINT_ADMITTANCE = 7 + +uint32 NULL_SPACE_ADMITTANCE = 8 + +uint32 FORCE_CONTROL = 10 + +uint32 FORCE_CONTROL_MOTION_RESTRICTED = 11 + +uint32 IDLE = 13 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_ControlModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_ControlModeInformation.msg new file mode 100644 index 0000000..6342d92 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_ControlModeInformation.msg @@ -0,0 +1,2 @@ + +uint32 mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_JointSpeeds.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_JointSpeeds.msg new file mode 100644 index 0000000..6bb7881 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_JointSpeeds.msg @@ -0,0 +1,3 @@ + +JointSpeed[] joint_speeds +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_Position.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_Position.msg new file mode 100644 index 0000000..678ce63 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_Position.msg @@ -0,0 +1,4 @@ + +float32 x +float32 y +float32 z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_RotationMatrix.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_RotationMatrix.msg new file mode 100644 index 0000000..2dd0265 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_RotationMatrix.msg @@ -0,0 +1,4 @@ + +Base_RotationMatrixRow row1 +Base_RotationMatrixRow row2 +Base_RotationMatrixRow row3 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_RotationMatrixRow.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_RotationMatrixRow.msg new file mode 100644 index 0000000..a389a4e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_RotationMatrixRow.msg @@ -0,0 +1,4 @@ + +float32 column1 +float32 column2 +float32 column3 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_SafetyIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_SafetyIdentifier.msg new file mode 100644 index 0000000..b33eefb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_SafetyIdentifier.msg @@ -0,0 +1,64 @@ + +uint32 UNSPECIFIED_BASE_SAFETY_IDENTIFIER = 0 + +uint32 FIRMWARE_UPDATE_FAILURE = 1 + +uint32 EXTERNAL_COMMUNICATION_ERROR = 2 + +uint32 MAXIMUM_AMBIENT_TEMPERATURE = 4 + +uint32 MAXIMUM_CORE_TEMPERATURE = 8 + +uint32 JOINT_FAULT = 16 + +uint32 CYCLIC_DATA_JITTER = 32 + +uint32 REACHED_MAXIMUM_EVENT_LOGS = 64 + +uint32 NO_KINEMATICS_SUPPORT = 128 + +uint32 ABOVE_MAXIMUM_DOF = 256 + +uint32 NETWORK_ERROR = 512 + +uint32 UNABLE_TO_REACH_POSE = 1024 + +uint32 JOINT_DETECTION_ERROR = 2048 + +uint32 NETWORK_INITIALIZATION_ERROR = 4096 + +uint32 MAXIMUM_CURRENT = 8192 + +uint32 MAXIMUM_VOLTAGE = 16384 + +uint32 MINIMUM_VOLTAGE = 32768 + +uint32 MAXIMUM_END_EFFECTOR_TRANSLATION_VELOCITY = 65536 + +uint32 MAXIMUM_END_EFFECTOR_ORIENTATION_VELOCITY = 131072 + +uint32 MAXIMUM_END_EFFECTOR_TRANSLATION_ACCELERATION = 262144 + +uint32 MAXIMUM_END_EFFECTOR_ORIENTATION_ACCELERATION = 524288 + +uint32 MAXIMUM_END_EFFECTOR_TRANSLATION_FORCE = 1048576 + +uint32 MAXIMUM_END_EFFECTOR_ORIENTATION_FORCE = 2097152 + +uint32 MAXIMUM_END_EFFECTOR_PAYLOAD = 4194304 + +uint32 EMERGENCY_STOP_ACTIVATED = 8388608 + +uint32 EMERGENCY_LINE_ACTIVATED = 16777216 + +uint32 INRUSH_CURRENT_LIMITER_FAULT = 33554432 + +uint32 NVRAM_CORRUPTED = 67108864 + +uint32 INCOMPATIBLE_FIRMWARE_VERSION = 134217728 + +uint32 POWERON_SELF_TEST_FAILURE = 268435456 + +uint32 DISCRETE_INPUT_STUCK_ACTIVE = 536870912 + +uint32 ARM_INTO_ILLEGAL_POSITION = 1073741824 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Base_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Base_Stop.msg b/ros_kortex/kortex_driver/msg/generated/base/Base_Stop.msg new file mode 100644 index 0000000..e69de29 diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgeConfig.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgeConfig.msg new file mode 100644 index 0000000..e3b6f51 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgeConfig.msg @@ -0,0 +1,5 @@ + +uint32 device_identifier +uint32 bridgetype +BridgePortConfig port_config +BridgeIdentifier bridge_id \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgeIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgeIdentifier.msg new file mode 100644 index 0000000..13dd187 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgeIdentifier.msg @@ -0,0 +1,2 @@ + +uint32 bridge_id \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgeList.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgeList.msg new file mode 100644 index 0000000..dfb210e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgeList.msg @@ -0,0 +1,2 @@ + +BridgeConfig[] bridgeConfig \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgePortConfig.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgePortConfig.msg new file mode 100644 index 0000000..af1940c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgePortConfig.msg @@ -0,0 +1,3 @@ + +uint32 target_port +uint32 out_port \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgeResult.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgeResult.msg new file mode 100644 index 0000000..c5f383e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgeResult.msg @@ -0,0 +1,3 @@ + +BridgeIdentifier bridge_id +uint32 status \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgeStatus.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgeStatus.msg new file mode 100644 index 0000000..50e6414 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgeStatus.msg @@ -0,0 +1,14 @@ + +uint32 BRIDGE_STATUS_OK = 0 + +uint32 BRIDGE_STATUS_OUTP_UNAVAILABLE = 1 + +uint32 BRIDGE_STATUS_UNKNOWN_DEVID = 2 + +uint32 BRIDGE_STATUS_UNKNOWN_BRIDGE_TYPE = 3 + +uint32 BRIDGE_STATUS_NOT_FOUND = 4 + +uint32 BRIDGE_STATUS_NOT_INITIALIZED = 5 + +uint32 BRIDGE_STATUS_UNKNOWN = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/base/BridgeType.msg b/ros_kortex/kortex_driver/msg/generated/base/BridgeType.msg new file mode 100644 index 0000000..be18919 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/BridgeType.msg @@ -0,0 +1,6 @@ + +uint32 BRIDGE_TYPE_UNSPECIFIED = 0 + +uint32 BRIDGE_TYPE_UART = 1 + +uint32 BRIDGE_TYPE_TELNET = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/CartesianLimitation.msg b/ros_kortex/kortex_driver/msg/generated/base/CartesianLimitation.msg new file mode 100644 index 0000000..110e361 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/CartesianLimitation.msg @@ -0,0 +1,4 @@ + +uint32 type +float32 translation +float32 orientation \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/CartesianLimitationList.msg b/ros_kortex/kortex_driver/msg/generated/base/CartesianLimitationList.msg new file mode 100644 index 0000000..d6ce6bb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/CartesianLimitationList.msg @@ -0,0 +1,2 @@ + +CartesianLimitation[] limitations \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/CartesianSpeed.msg b/ros_kortex/kortex_driver/msg/generated/base/CartesianSpeed.msg new file mode 100644 index 0000000..f8794b7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/CartesianSpeed.msg @@ -0,0 +1,3 @@ + +float32 translation +float32 orientation \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/CartesianTrajectoryConstraint.msg b/ros_kortex/kortex_driver/msg/generated/base/CartesianTrajectoryConstraint.msg new file mode 100644 index 0000000..eb04b73 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/CartesianTrajectoryConstraint.msg @@ -0,0 +1,2 @@ + +CartesianTrajectoryConstraint_type oneof_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/CartesianTrajectoryConstraint_type.msg b/ros_kortex/kortex_driver/msg/generated/base/CartesianTrajectoryConstraint_type.msg new file mode 100644 index 0000000..10e7f9d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/CartesianTrajectoryConstraint_type.msg @@ -0,0 +1,3 @@ + +CartesianSpeed[] speed +uint32[] duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ChangeJointSpeeds.msg b/ros_kortex/kortex_driver/msg/generated/base/ChangeJointSpeeds.msg new file mode 100644 index 0000000..65dac63 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ChangeJointSpeeds.msg @@ -0,0 +1,2 @@ + +Base_JointSpeeds joint_speeds \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ChangeTwist.msg b/ros_kortex/kortex_driver/msg/generated/base/ChangeTwist.msg new file mode 100644 index 0000000..71d333a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ChangeTwist.msg @@ -0,0 +1,3 @@ + +float32 linear +float32 angular \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ChangeWrench.msg b/ros_kortex/kortex_driver/msg/generated/base/ChangeWrench.msg new file mode 100644 index 0000000..1d7a973 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ChangeWrench.msg @@ -0,0 +1,3 @@ + +float32 force +float32 torque \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/CommunicationInterfaceConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/base/CommunicationInterfaceConfiguration.msg new file mode 100644 index 0000000..c79d220 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/CommunicationInterfaceConfiguration.msg @@ -0,0 +1,3 @@ + +uint32 type +bool enable \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotification.msg new file mode 100644 index 0000000..fa8893b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotification.msg @@ -0,0 +1,6 @@ + +uint32 event +Timestamp timestamp +UserProfileHandle user_handle +Connection connection +ConfigurationChangeNotification_configuration_change oneof_configuration_change \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotificationList.msg new file mode 100644 index 0000000..a1952ba --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotificationList.msg @@ -0,0 +1,2 @@ + +ConfigurationChangeNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotification_configuration_change.msg b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotification_configuration_change.msg new file mode 100644 index 0000000..fb45e2d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationChangeNotification_configuration_change.msg @@ -0,0 +1,12 @@ + +SequenceHandle[] sequence_handle +ActionHandle[] action_handle +MappingHandle[] mapping_handle +MapGroupHandle[] map_group_handle +MapHandle[] map_handle +UserProfileHandle[] user_profile_handle +ProtectionZoneHandle[] protection_zone_handle +SafetyHandle[] safety_handle +NetworkHandle[] network_handle +Ssid[] ssid +ControllerHandle[] controller_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConfigurationNotificationEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationNotificationEvent.msg new file mode 100644 index 0000000..dc9dcb1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConfigurationNotificationEvent.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_CONFIGURATION_EVENT = 0 + +uint32 CONFIGURATION_UPDATED = 1 + +uint32 CONFIGURATION_DELETED = 2 + +uint32 CONFIGURATION_DELETED_ALL = 3 + +uint32 CONFIGURATION_CREATED = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConstrainedJointAngle.msg b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedJointAngle.msg new file mode 100644 index 0000000..d93fe84 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedJointAngle.msg @@ -0,0 +1,4 @@ + +uint32 joint_identifier +float32 value +JointTrajectoryConstraint constraint \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConstrainedJointAngles.msg b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedJointAngles.msg new file mode 100644 index 0000000..944fc89 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedJointAngles.msg @@ -0,0 +1,3 @@ + +JointAngles joint_angles +JointTrajectoryConstraint constraint \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConstrainedOrientation.msg b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedOrientation.msg new file mode 100644 index 0000000..51ad615 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedOrientation.msg @@ -0,0 +1,3 @@ + +Orientation target_orientation +CartesianTrajectoryConstraint constraint \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConstrainedPose.msg b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedPose.msg new file mode 100644 index 0000000..63b595e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedPose.msg @@ -0,0 +1,3 @@ + +Pose target_pose +CartesianTrajectoryConstraint constraint \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ConstrainedPosition.msg b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedPosition.msg new file mode 100644 index 0000000..3601acc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ConstrainedPosition.msg @@ -0,0 +1,3 @@ + +Base_Position target_position +CartesianTrajectoryConstraint constraint \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControlModeNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ControlModeNotification.msg new file mode 100644 index 0000000..802d67a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControlModeNotification.msg @@ -0,0 +1,5 @@ + +uint32 control_mode +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControlModeNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ControlModeNotificationList.msg new file mode 100644 index 0000000..ac035c8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControlModeNotificationList.msg @@ -0,0 +1,2 @@ + +ControlModeNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerBehavior.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerBehavior.msg new file mode 100644 index 0000000..cebfc84 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerBehavior.msg @@ -0,0 +1,12 @@ + +uint32 UNSPECIFIED_CONTROLLER_BEHAVIOR = 0 + +uint32 CONTROLLER_BUTTON_DOWN = 1 + +uint32 CONTROLLER_BUTTON_UP = 2 + +uint32 CONTROLLER_AXIS_POSITIVE = 3 + +uint32 CONTROLLER_AXIS_NEGATIVE = 4 + +uint32 CONTROLLER_BUTTON_CLICK = 5 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerConfiguration.msg new file mode 100644 index 0000000..1a99b01 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerConfiguration.msg @@ -0,0 +1,6 @@ + +ControllerHandle handle +string name +MappingHandle active_mapping_handle +string analog_input_identifier_enum +string digital_input_identifier_enum \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerConfigurationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerConfigurationList.msg new file mode 100644 index 0000000..9e00af6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerConfigurationList.msg @@ -0,0 +1,2 @@ + +ControllerConfiguration[] controller_configurations \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerConfigurationMode.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerConfigurationMode.msg new file mode 100644 index 0000000..5304e28 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerConfigurationMode.msg @@ -0,0 +1,2 @@ + +bool enable \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerElementEventType.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementEventType.msg new file mode 100644 index 0000000..b8b60f0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementEventType.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_CONTROLLER_ELEMENT_EVENT = 0 + +uint32 AXIS_MOVED = 1 + +uint32 BUTTON_DOWN = 2 + +uint32 BUTTON_UP = 3 + +uint32 BUTTON_CLICK = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerElementHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementHandle.msg new file mode 100644 index 0000000..c9be3fb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementHandle.msg @@ -0,0 +1,3 @@ + +ControllerHandle controller_handle +ControllerElementHandle_identifier oneof_identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerElementHandle_identifier.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementHandle_identifier.msg new file mode 100644 index 0000000..142ae97 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementHandle_identifier.msg @@ -0,0 +1,3 @@ + +uint32[] button +uint32[] axis \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerElementState.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementState.msg new file mode 100644 index 0000000..ada62b6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerElementState.msg @@ -0,0 +1,4 @@ + +ControllerElementHandle handle +uint32 event_type +float32 axis_value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerEvent.msg new file mode 100644 index 0000000..6dae898 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerEvent.msg @@ -0,0 +1,4 @@ + +uint32 input_type +uint32 behavior +uint32 input_identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerEventType.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerEventType.msg new file mode 100644 index 0000000..e72f156 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerEventType.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_CONTROLLER_EVENT = 0 + +uint32 CONTROLLER_DISCONNECTED = 1 + +uint32 CONTROLLER_CONNECTED = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerHandle.msg new file mode 100644 index 0000000..e77bf89 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerHandle.msg @@ -0,0 +1,3 @@ + +uint32 type +uint32 controller_identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerInputType.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerInputType.msg new file mode 100644 index 0000000..7a448d5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerInputType.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_CONTROLLER_INPUT_TYPE = 0 + +uint32 ANALOG = 1 + +uint32 DIGITAL = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerList.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerList.msg new file mode 100644 index 0000000..d92dc3c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerList.msg @@ -0,0 +1,2 @@ + +ControllerHandle[] handles \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerNotification.msg new file mode 100644 index 0000000..92f0479 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerNotification.msg @@ -0,0 +1,5 @@ + +Timestamp timestamp +UserProfileHandle user_handle +Connection connection +ControllerNotification_state oneof_state \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerNotificationList.msg new file mode 100644 index 0000000..dd78563 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerNotificationList.msg @@ -0,0 +1,2 @@ + +ControllerNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerNotification_state.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerNotification_state.msg new file mode 100644 index 0000000..6ea1711 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerNotification_state.msg @@ -0,0 +1,3 @@ + +ControllerState[] controller_state +ControllerElementState[] controller_element \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerState.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerState.msg new file mode 100644 index 0000000..416d9ec --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerState.msg @@ -0,0 +1,3 @@ + +ControllerHandle handle +uint32 event_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ControllerType.msg b/ros_kortex/kortex_driver/msg/generated/base/ControllerType.msg new file mode 100644 index 0000000..538a75f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ControllerType.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_CONTROLLER_TYPE = 0 + +uint32 XBOX_CONTROLLER = 1 + +uint32 WRIST_CONTROLLER = 2 + +uint32 BASIC_JOYSTICK_CONTROLLER = 3 + +uint32 BASE_GPIO_CONTROLLER = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Delay.msg b/ros_kortex/kortex_driver/msg/generated/base/Delay.msg new file mode 100644 index 0000000..7e50d0f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Delay.msg @@ -0,0 +1,2 @@ + +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/EmergencyStop.msg b/ros_kortex/kortex_driver/msg/generated/base/EmergencyStop.msg new file mode 100644 index 0000000..e69de29 diff --git a/ros_kortex/kortex_driver/msg/generated/base/EventIdSequenceInfoNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/EventIdSequenceInfoNotification.msg new file mode 100644 index 0000000..3ed7c6e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/EventIdSequenceInfoNotification.msg @@ -0,0 +1,14 @@ + +uint32 UNSPECIFIED_SEQUENCE_EVENT = 0 + +uint32 SEQUENCE_COMPLETED = 1 + +uint32 SEQUENCE_ABORTED = 2 + +uint32 SEQUENCE_PAUSED = 3 + +uint32 SEQUENCE_TASK_STARTED = 4 + +uint32 SEQUENCE_TASK_COMPLETED = 5 + +uint32 SEQUENCE_STARTED = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/base/FactoryEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/FactoryEvent.msg new file mode 100644 index 0000000..ec57bf7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/FactoryEvent.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_FACTORY_EVENT = 0 + +uint32 FACTORY_DEFAULT_RESTORED = 1 + +uint32 NETWORK_FACTORY_DEFAULT_RESTORED = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/FactoryNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/FactoryNotification.msg new file mode 100644 index 0000000..3863572 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/FactoryNotification.msg @@ -0,0 +1,5 @@ + +uint32 event +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Faults.msg b/ros_kortex/kortex_driver/msg/generated/base/Faults.msg new file mode 100644 index 0000000..e69de29 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Finger.msg b/ros_kortex/kortex_driver/msg/generated/base/Finger.msg new file mode 100644 index 0000000..e641006 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Finger.msg @@ -0,0 +1,3 @@ + +uint32 finger_identifier +float32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/FirmwareBundleVersions.msg b/ros_kortex/kortex_driver/msg/generated/base/FirmwareBundleVersions.msg new file mode 100644 index 0000000..b4605a5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/FirmwareBundleVersions.msg @@ -0,0 +1,3 @@ + +string main_bundle_version +FirmwareComponentVersion[] components_versions \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/FirmwareComponentVersion.msg b/ros_kortex/kortex_driver/msg/generated/base/FirmwareComponentVersion.msg new file mode 100644 index 0000000..b7da303 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/FirmwareComponentVersion.msg @@ -0,0 +1,4 @@ + +string name +string version +uint32 device_id \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/FullIPv4Configuration.msg b/ros_kortex/kortex_driver/msg/generated/base/FullIPv4Configuration.msg new file mode 100644 index 0000000..e742d68 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/FullIPv4Configuration.msg @@ -0,0 +1,3 @@ + +NetworkHandle handle +IPv4Configuration ipv4_configuration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/FullUserProfile.msg b/ros_kortex/kortex_driver/msg/generated/base/FullUserProfile.msg new file mode 100644 index 0000000..62dab01 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/FullUserProfile.msg @@ -0,0 +1,3 @@ + +UserProfile user_profile +string password \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Gen3GpioPinId.msg b/ros_kortex/kortex_driver/msg/generated/base/Gen3GpioPinId.msg new file mode 100644 index 0000000..c5dea1d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Gen3GpioPinId.msg @@ -0,0 +1,26 @@ + +uint32 UNSPECIFIED_PIN = 0 + +uint32 GPIO_PIN_B = 1 + +uint32 GPIO_PIN_C = 2 + +uint32 GPIO_PIN_D = 3 + +uint32 GPIO_PIN_E = 4 + +uint32 GPIO_PIN_G = 5 + +uint32 GPIO_PIN_H = 6 + +uint32 GPIO_PIN_I = 7 + +uint32 GPIO_PIN_K = 8 + +uint32 GPIO_PIN_N = 9 + +uint32 GPIO_PIN_O = 10 + +uint32 GPIO_PIN_S = 11 + +uint32 GPIO_PIN_T = 12 diff --git a/ros_kortex/kortex_driver/msg/generated/base/GpioBehavior.msg b/ros_kortex/kortex_driver/msg/generated/base/GpioBehavior.msg new file mode 100644 index 0000000..08a5d62 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/GpioBehavior.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_GPIO_BEHAVIOR = 0 + +uint32 GPIO_FALLING = 1 + +uint32 GPIO_RISING = 2 + +uint32 GPIO_PULSE_LOW = 3 + +uint32 GPIO_PULSE_HIGH = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/GpioEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/GpioEvent.msg new file mode 100644 index 0000000..6dae898 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/GpioEvent.msg @@ -0,0 +1,4 @@ + +uint32 input_type +uint32 behavior +uint32 input_identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Gripper.msg b/ros_kortex/kortex_driver/msg/generated/base/Gripper.msg new file mode 100644 index 0000000..71f808f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Gripper.msg @@ -0,0 +1,2 @@ + +Finger[] finger \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/GripperCommand.msg b/ros_kortex/kortex_driver/msg/generated/base/GripperCommand.msg new file mode 100644 index 0000000..b105fb7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/GripperCommand.msg @@ -0,0 +1,4 @@ + +uint32 mode +Gripper gripper +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/GripperMode.msg b/ros_kortex/kortex_driver/msg/generated/base/GripperMode.msg new file mode 100644 index 0000000..db6b728 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/GripperMode.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_GRIPPER_MODE = 0 + +uint32 GRIPPER_FORCE = 1 + +uint32 GRIPPER_SPEED = 2 + +uint32 GRIPPER_POSITION = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/base/GripperRequest.msg b/ros_kortex/kortex_driver/msg/generated/base/GripperRequest.msg new file mode 100644 index 0000000..6342d92 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/GripperRequest.msg @@ -0,0 +1,2 @@ + +uint32 mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/IPv4Configuration.msg b/ros_kortex/kortex_driver/msg/generated/base/IPv4Configuration.msg new file mode 100644 index 0000000..c8785c9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/IPv4Configuration.msg @@ -0,0 +1,5 @@ + +uint32 ip_address +uint32 subnet_mask +uint32 default_gateway +bool dhcp_enabled \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/IPv4Information.msg b/ros_kortex/kortex_driver/msg/generated/base/IPv4Information.msg new file mode 100644 index 0000000..30fe098 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/IPv4Information.msg @@ -0,0 +1,4 @@ + +uint32 ip_address +uint32 subnet_mask +uint32 default_gateway \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointAngle.msg b/ros_kortex/kortex_driver/msg/generated/base/JointAngle.msg new file mode 100644 index 0000000..3222a0b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointAngle.msg @@ -0,0 +1,3 @@ + +uint32 joint_identifier +float32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointAngles.msg b/ros_kortex/kortex_driver/msg/generated/base/JointAngles.msg new file mode 100644 index 0000000..cbb0ec1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointAngles.msg @@ -0,0 +1,2 @@ + +JointAngle[] joint_angles \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointLimitation.msg b/ros_kortex/kortex_driver/msg/generated/base/JointLimitation.msg new file mode 100644 index 0000000..635aaa5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointLimitation.msg @@ -0,0 +1,4 @@ + +uint32 joint_identifier +uint32 type +float32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointNavigationDirection.msg b/ros_kortex/kortex_driver/msg/generated/base/JointNavigationDirection.msg new file mode 100644 index 0000000..274085f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointNavigationDirection.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_JOINT_NAVIGATION_DIRECTION = 0 + +uint32 JOINT_NEXT = 1 + +uint32 JOINT_PREVIOUS = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointSpeed.msg b/ros_kortex/kortex_driver/msg/generated/base/JointSpeed.msg new file mode 100644 index 0000000..44d3651 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointSpeed.msg @@ -0,0 +1,4 @@ + +uint32 joint_identifier +float32 value +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointTorque.msg b/ros_kortex/kortex_driver/msg/generated/base/JointTorque.msg new file mode 100644 index 0000000..44d3651 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointTorque.msg @@ -0,0 +1,4 @@ + +uint32 joint_identifier +float32 value +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointTorques.msg b/ros_kortex/kortex_driver/msg/generated/base/JointTorques.msg new file mode 100644 index 0000000..7294fa5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointTorques.msg @@ -0,0 +1,3 @@ + +JointTorque[] joint_torques +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointTrajectoryConstraint.msg b/ros_kortex/kortex_driver/msg/generated/base/JointTrajectoryConstraint.msg new file mode 100644 index 0000000..5ec8ddf --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointTrajectoryConstraint.msg @@ -0,0 +1,3 @@ + +uint32 type +float32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointTrajectoryConstraintType.msg b/ros_kortex/kortex_driver/msg/generated/base/JointTrajectoryConstraintType.msg new file mode 100644 index 0000000..22b3399 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointTrajectoryConstraintType.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_JOINT_CONSTRAINT = 0 + +uint32 JOINT_CONSTRAINT_DURATION = 1 + +uint32 JOINT_CONSTRAINT_SPEED = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/JointsLimitationsList.msg b/ros_kortex/kortex_driver/msg/generated/base/JointsLimitationsList.msg new file mode 100644 index 0000000..26d8264 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/JointsLimitationsList.msg @@ -0,0 +1,2 @@ + +JointLimitation[] joints_limitations \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/LedState.msg b/ros_kortex/kortex_driver/msg/generated/base/LedState.msg new file mode 100644 index 0000000..93fc79a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/LedState.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_LED_STATE = 0 + +uint32 LED_OFF = 1 + +uint32 LED_PULSE = 2 + +uint32 LED_ON = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/base/LimitationType.msg b/ros_kortex/kortex_driver/msg/generated/base/LimitationType.msg new file mode 100644 index 0000000..c6ddcb2 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/LimitationType.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_LIMITATION = 0 + +uint32 FORCE_LIMITATION = 1 + +uint32 ACCELERATION_LIMITATION = 2 + +uint32 VELOCITY_LIMITATION = 3 + +uint32 TORQUE_LIMITATION = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Map.msg b/ros_kortex/kortex_driver/msg/generated/base/Map.msg new file mode 100644 index 0000000..d463147 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Map.msg @@ -0,0 +1,4 @@ + +MapHandle handle +string name +MapElement[] elements \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapElement.msg b/ros_kortex/kortex_driver/msg/generated/base/MapElement.msg new file mode 100644 index 0000000..4cf42f5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapElement.msg @@ -0,0 +1,4 @@ + +MapEvent event +Action action +string name \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/MapEvent.msg new file mode 100644 index 0000000..b1e135d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapEvent.msg @@ -0,0 +1,3 @@ + +string name +MapEvent_events oneof_events \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapEvent_events.msg b/ros_kortex/kortex_driver/msg/generated/base/MapEvent_events.msg new file mode 100644 index 0000000..07b41be --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapEvent_events.msg @@ -0,0 +1,4 @@ + +SafetyEvent[] safety_event +GpioEvent[] gpio_event +ControllerEvent[] controller_event \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapGroup.msg b/ros_kortex/kortex_driver/msg/generated/base/MapGroup.msg new file mode 100644 index 0000000..f9f22cf --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapGroup.msg @@ -0,0 +1,8 @@ + +MapGroupHandle group_handle +string name +MappingHandle related_mapping_handle +MapGroupHandle parent_group_handle +MapGroupHandle[] children_map_group_handles +MapHandle[] map_handles +string application_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapGroupHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/MapGroupHandle.msg new file mode 100644 index 0000000..4d2b97e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapGroupHandle.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapGroupList.msg b/ros_kortex/kortex_driver/msg/generated/base/MapGroupList.msg new file mode 100644 index 0000000..faa782a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapGroupList.msg @@ -0,0 +1,2 @@ + +MapGroup[] map_groups \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/MapHandle.msg new file mode 100644 index 0000000..4d2b97e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapHandle.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MapList.msg b/ros_kortex/kortex_driver/msg/generated/base/MapList.msg new file mode 100644 index 0000000..2a28605 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MapList.msg @@ -0,0 +1,2 @@ + +Map[] map_list \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Mapping.msg b/ros_kortex/kortex_driver/msg/generated/base/Mapping.msg new file mode 100644 index 0000000..ca26029 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Mapping.msg @@ -0,0 +1,9 @@ + +MappingHandle handle +string name +uint32 controller_identifier +MapGroupHandle active_map_group_handle +MapGroupHandle[] map_group_handles +MapHandle active_map_handle +MapHandle[] map_handles +string application_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MappingHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/MappingHandle.msg new file mode 100644 index 0000000..4d2b97e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MappingHandle.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MappingInfoNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/MappingInfoNotification.msg new file mode 100644 index 0000000..164791e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MappingInfoNotification.msg @@ -0,0 +1,7 @@ + +uint32 controller_identifier +MapHandle active_map_handle +Timestamp timestamp +UserProfileHandle user_handle +Connection connection +MappingHandle mapping_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MappingInfoNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/MappingInfoNotificationList.msg new file mode 100644 index 0000000..fd0e5c9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MappingInfoNotificationList.msg @@ -0,0 +1,2 @@ + +MappingInfoNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/MappingList.msg b/ros_kortex/kortex_driver/msg/generated/base/MappingList.msg new file mode 100644 index 0000000..8240022 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/MappingList.msg @@ -0,0 +1,2 @@ + +Mapping[] mappings \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/NavigationDirection.msg b/ros_kortex/kortex_driver/msg/generated/base/NavigationDirection.msg new file mode 100644 index 0000000..93f1c4c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/NavigationDirection.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_NAVIGATION_DIRECTION = 0 + +uint32 NEXT = 1 + +uint32 UP = 2 + +uint32 DOWN = 3 + +uint32 PREVIOUS = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/NetworkEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/NetworkEvent.msg new file mode 100644 index 0000000..217903d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/NetworkEvent.msg @@ -0,0 +1,22 @@ + +uint32 UNSPECIFIED_NETWORK_EVENT = 0 + +uint32 WIFI_CONNECTED = 1 + +uint32 WIFI_DISCONNECTED = 2 + +uint32 WIFI_SCAN_STARTED = 3 + +uint32 WIFI_SCAN_RESULTS = 4 + +uint32 WIFI_SCAN_FAILED = 5 + +uint32 WIFI_NOT_FOUND = 6 + +uint32 WIFI_ASSOC_REJECTED = 7 + +uint32 WIFI_AUTH_WRONG_KEY = 8 + +uint32 WIFI_AUTH_CONN_FAILED = 9 + +uint32 WIFI_AUTH_FAILED = 10 diff --git a/ros_kortex/kortex_driver/msg/generated/base/NetworkHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/NetworkHandle.msg new file mode 100644 index 0000000..5fc901c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/NetworkHandle.msg @@ -0,0 +1,2 @@ + +uint32 type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/NetworkNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/NetworkNotification.msg new file mode 100644 index 0000000..3863572 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/NetworkNotification.msg @@ -0,0 +1,5 @@ + +uint32 event +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/NetworkNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/NetworkNotificationList.msg new file mode 100644 index 0000000..82ef350 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/NetworkNotificationList.msg @@ -0,0 +1,2 @@ + +NetworkNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/NetworkType.msg b/ros_kortex/kortex_driver/msg/generated/base/NetworkType.msg new file mode 100644 index 0000000..3421f3a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/NetworkType.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_NETWORK_TYPE = 0 + +uint32 WIFI = 1 + +uint32 WIRED_ETHERNET = 2 + +uint32 WIRED_MICROUSB = 3 + +uint32 WIRED_USB = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/OperatingMode.msg b/ros_kortex/kortex_driver/msg/generated/base/OperatingMode.msg new file mode 100644 index 0000000..c2fc2bd --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/OperatingMode.msg @@ -0,0 +1,16 @@ + +uint32 UNSPECIFIED_OPERATING_MODE = 0 + +uint32 MAINTENANCE_MODE = 1 + +uint32 UPDATE_MODE = 2 + +uint32 UPDATE_COMPLETED_MODE = 3 + +uint32 UPDATE_FAILED_MODE = 4 + +uint32 SHUTTING_DOWN_MODE = 5 + +uint32 RUN_MODE = 6 + +uint32 UPDATING_DEVICE_MODE = 7 diff --git a/ros_kortex/kortex_driver/msg/generated/base/OperatingModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/OperatingModeInformation.msg new file mode 100644 index 0000000..e2f2da1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/OperatingModeInformation.msg @@ -0,0 +1,3 @@ + +uint32 operating_mode +DeviceHandle device_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/OperatingModeNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/OperatingModeNotification.msg new file mode 100644 index 0000000..379b5bb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/OperatingModeNotification.msg @@ -0,0 +1,6 @@ + +uint32 operating_mode +Timestamp timestamp +UserProfileHandle user_handle +Connection connection +DeviceHandle device_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/OperatingModeNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/OperatingModeNotificationList.msg new file mode 100644 index 0000000..9be52f5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/OperatingModeNotificationList.msg @@ -0,0 +1,2 @@ + +OperatingModeNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Orientation.msg b/ros_kortex/kortex_driver/msg/generated/base/Orientation.msg new file mode 100644 index 0000000..eb1df97 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Orientation.msg @@ -0,0 +1,4 @@ + +float32 theta_x +float32 theta_y +float32 theta_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/PasswordChange.msg b/ros_kortex/kortex_driver/msg/generated/base/PasswordChange.msg new file mode 100644 index 0000000..5aee985 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/PasswordChange.msg @@ -0,0 +1,4 @@ + +UserProfileHandle handle +string old_password +string new_password \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Point.msg b/ros_kortex/kortex_driver/msg/generated/base/Point.msg new file mode 100644 index 0000000..678ce63 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Point.msg @@ -0,0 +1,4 @@ + +float32 x +float32 y +float32 z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Pose.msg b/ros_kortex/kortex_driver/msg/generated/base/Pose.msg new file mode 100644 index 0000000..b1f7d64 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Pose.msg @@ -0,0 +1,7 @@ + +float32 x +float32 y +float32 z +float32 theta_x +float32 theta_y +float32 theta_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/PreComputedJointTrajectory.msg b/ros_kortex/kortex_driver/msg/generated/base/PreComputedJointTrajectory.msg new file mode 100644 index 0000000..7e41abd --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/PreComputedJointTrajectory.msg @@ -0,0 +1,3 @@ + +uint32 mode +PreComputedJointTrajectoryElement[] trajectory_elements \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/PreComputedJointTrajectoryElement.msg b/ros_kortex/kortex_driver/msg/generated/base/PreComputedJointTrajectoryElement.msg new file mode 100644 index 0000000..5c6d51b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/PreComputedJointTrajectoryElement.msg @@ -0,0 +1,5 @@ + +float32[] joint_angles +float32[] joint_speeds +float32[] joint_accelerations +float32 time_from_start \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZone.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZone.msg new file mode 100644 index 0000000..a274e44 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZone.msg @@ -0,0 +1,8 @@ + +ProtectionZoneHandle handle +string name +string application_data +bool is_enabled +ZoneShape shape +CartesianLimitation[] limitations +CartesianLimitation[] envelope_limitations \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneEvent.msg new file mode 100644 index 0000000..382e487 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneEvent.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_PROTECTION_ZONE_EVENT = 0 + +uint32 REACHED = 1 + +uint32 ENTERED = 2 + +uint32 EXITED = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneHandle.msg new file mode 100644 index 0000000..4d2b97e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneHandle.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneInformation.msg new file mode 100644 index 0000000..bff9f62 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneInformation.msg @@ -0,0 +1,2 @@ + +uint32 event \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneList.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneList.msg new file mode 100644 index 0000000..65b2f36 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneList.msg @@ -0,0 +1,2 @@ + +ProtectionZone[] protection_zones \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneNotification.msg new file mode 100644 index 0000000..3b1a88f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneNotification.msg @@ -0,0 +1,6 @@ + +uint32 event +ProtectionZoneHandle handle +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneNotificationList.msg new file mode 100644 index 0000000..516c2ca --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ProtectionZoneNotificationList.msg @@ -0,0 +1,2 @@ + +ProtectionZoneNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Query.msg b/ros_kortex/kortex_driver/msg/generated/base/Query.msg new file mode 100644 index 0000000..9854c41 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Query.msg @@ -0,0 +1,4 @@ + +Timestamp start_timestamp +Timestamp end_timestamp +string username \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/RequestedActionType.msg b/ros_kortex/kortex_driver/msg/generated/base/RequestedActionType.msg new file mode 100644 index 0000000..4378483 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/RequestedActionType.msg @@ -0,0 +1,2 @@ + +uint32 action_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/RobotEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/RobotEvent.msg new file mode 100644 index 0000000..2174cd2 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/RobotEvent.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_ROBOT_EVENT = 0 + +uint32 ARM_CONNECTED = 1 + +uint32 ARM_DISCONNECTED = 2 + +uint32 TOOL_CONNECTED = 5 + +uint32 TOOL_DISCONNECTED = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/base/RobotEventNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/RobotEventNotification.msg new file mode 100644 index 0000000..6cefe76 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/RobotEventNotification.msg @@ -0,0 +1,6 @@ + +uint32 event +DeviceHandle handle +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/RobotEventNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/RobotEventNotificationList.msg new file mode 100644 index 0000000..66e53d9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/RobotEventNotificationList.msg @@ -0,0 +1,2 @@ + +RobotEventNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SafetyEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/SafetyEvent.msg new file mode 100644 index 0000000..cad1284 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SafetyEvent.msg @@ -0,0 +1,2 @@ + +SafetyHandle safety_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SafetyNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/SafetyNotificationList.msg new file mode 100644 index 0000000..ad9ce4c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SafetyNotificationList.msg @@ -0,0 +1,2 @@ + +SafetyNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Sequence.msg b/ros_kortex/kortex_driver/msg/generated/base/Sequence.msg new file mode 100644 index 0000000..c247747 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Sequence.msg @@ -0,0 +1,5 @@ + +SequenceHandle handle +string name +string application_data +SequenceTask[] tasks \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceHandle.msg new file mode 100644 index 0000000..4d2b97e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceHandle.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceInfoNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceInfoNotification.msg new file mode 100644 index 0000000..a20a140 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceInfoNotification.msg @@ -0,0 +1,9 @@ + +uint32 event_identifier +SequenceHandle sequence_handle +uint32 task_index +uint32 group_identifier +Timestamp timestamp +UserProfileHandle user_handle +uint32 abort_details +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceInfoNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceInfoNotificationList.msg new file mode 100644 index 0000000..6c951de --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceInfoNotificationList.msg @@ -0,0 +1,2 @@ + +SequenceInfoNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceInformation.msg new file mode 100644 index 0000000..12495fd --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceInformation.msg @@ -0,0 +1,4 @@ + +uint32 event_identifier +uint32 task_index +uint32 task_identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceList.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceList.msg new file mode 100644 index 0000000..02d7bb3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceList.msg @@ -0,0 +1,2 @@ + +Sequence[] sequence_list \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTask.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTask.msg new file mode 100644 index 0000000..56aab39 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTask.msg @@ -0,0 +1,4 @@ + +uint32 group_identifier +Action action +string application_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTaskConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTaskConfiguration.msg new file mode 100644 index 0000000..09131f4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTaskConfiguration.msg @@ -0,0 +1,3 @@ + +SequenceTaskHandle sequence_task_handle +SequenceTask sequence_task \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTaskHandle.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTaskHandle.msg new file mode 100644 index 0000000..e79b56b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTaskHandle.msg @@ -0,0 +1,3 @@ + +SequenceHandle sequence_handle +uint32 task_index \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTasks.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasks.msg new file mode 100644 index 0000000..a0ac8d6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasks.msg @@ -0,0 +1,2 @@ + +SequenceTask[] sequence_tasks \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksConfiguration.msg new file mode 100644 index 0000000..2365a72 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksConfiguration.msg @@ -0,0 +1,3 @@ + +SequenceTaskHandle sequence_task_handle +SequenceTask[] sequence_tasks \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksPair.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksPair.msg new file mode 100644 index 0000000..0c73572 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksPair.msg @@ -0,0 +1,4 @@ + +SequenceHandle sequence_handle +uint32 first_task_index +uint32 second_task_index \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksRange.msg b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksRange.msg new file mode 100644 index 0000000..953b07b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SequenceTasksRange.msg @@ -0,0 +1,3 @@ + +uint32 first_task_index +uint32 second_task_index \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ServoingMode.msg b/ros_kortex/kortex_driver/msg/generated/base/ServoingMode.msg new file mode 100644 index 0000000..2dc89b8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ServoingMode.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_SERVOING_MODE = 0 + +uint32 SINGLE_LEVEL_SERVOING = 2 + +uint32 LOW_LEVEL_SERVOING = 3 + +uint32 BYPASS_SERVOING = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ServoingModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/ServoingModeInformation.msg new file mode 100644 index 0000000..8aa2b42 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ServoingModeInformation.msg @@ -0,0 +1,2 @@ + +uint32 servoing_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ServoingModeNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/ServoingModeNotification.msg new file mode 100644 index 0000000..d671533 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ServoingModeNotification.msg @@ -0,0 +1,5 @@ + +uint32 servoing_mode +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ServoingModeNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/ServoingModeNotificationList.msg new file mode 100644 index 0000000..4050557 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ServoingModeNotificationList.msg @@ -0,0 +1,2 @@ + +ServoingModeNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/ShapeType.msg b/ros_kortex/kortex_driver/msg/generated/base/ShapeType.msg new file mode 100644 index 0000000..cc4902f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ShapeType.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_SHAPE = 0 + +uint32 CYLINDER = 1 + +uint32 SPHERE = 2 + +uint32 RECTANGULAR_PRISM = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/base/SignalQuality.msg b/ros_kortex/kortex_driver/msg/generated/base/SignalQuality.msg new file mode 100644 index 0000000..fc5ddf1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SignalQuality.msg @@ -0,0 +1,12 @@ + +uint32 UNSPECIFIED_SIGNAL_QUALITY = 0 + +uint32 POOR = 1 + +uint32 FAIR = 2 + +uint32 GOOD = 3 + +uint32 EXCELLENT = 4 + +uint32 NONE = 5 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Snapshot.msg b/ros_kortex/kortex_driver/msg/generated/base/Snapshot.msg new file mode 100644 index 0000000..f9c62d4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Snapshot.msg @@ -0,0 +1,2 @@ + +uint32 snapshot_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SnapshotType.msg b/ros_kortex/kortex_driver/msg/generated/base/SnapshotType.msg new file mode 100644 index 0000000..6f8978e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SnapshotType.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_SNAPSHOT = 0 + +uint32 CARTESIAN_POSITION_SNAPSHOT = 1 + +uint32 JOINT_POSITION_SNAPSHOT = 2 + +uint32 GRIPPER_SNAPSHOT = 3 + +uint32 COMBINED_SNAPSHOT = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/SoundType.msg b/ros_kortex/kortex_driver/msg/generated/base/SoundType.msg new file mode 100644 index 0000000..cb95ecb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SoundType.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_SOUND_TYPE = 0 + +uint32 BIP_SERIES = 1 + +uint32 SINGLE_BIP = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Ssid.msg b/ros_kortex/kortex_driver/msg/generated/base/Ssid.msg new file mode 100644 index 0000000..8734c7c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Ssid.msg @@ -0,0 +1,2 @@ + +string identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SwitchControlMapping.msg b/ros_kortex/kortex_driver/msg/generated/base/SwitchControlMapping.msg new file mode 100644 index 0000000..0fc02e1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SwitchControlMapping.msg @@ -0,0 +1,4 @@ + +uint32 controller_identifier +MapGroupHandle map_group_handle +MapHandle map_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/SystemTime.msg b/ros_kortex/kortex_driver/msg/generated/base/SystemTime.msg new file mode 100644 index 0000000..2c97341 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/SystemTime.msg @@ -0,0 +1,7 @@ + +uint32 sec +uint32 min +uint32 hour +uint32 mday +uint32 mon +uint32 year \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Timeout.msg b/ros_kortex/kortex_driver/msg/generated/base/Timeout.msg new file mode 100644 index 0000000..129c5a3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Timeout.msg @@ -0,0 +1,2 @@ + +uint32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/TrajectoryContinuityMode.msg b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryContinuityMode.msg new file mode 100644 index 0000000..84a1bb8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryContinuityMode.msg @@ -0,0 +1,8 @@ + +uint32 TRAJECTORY_CONTINUITY_MODE_UNSPECIFIED = 0 + +uint32 TRAJECTORY_CONTINUITY_MODE_POSITION = 1 + +uint32 TRAJECTORY_CONTINUITY_MODE_SPEED = 2 + +uint32 TRAJECTORY_CONTINUITY_MODE_ACCELERATION = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorElement.msg b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorElement.msg new file mode 100644 index 0000000..3898803 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorElement.msg @@ -0,0 +1,8 @@ + +uint32 error_type +uint32 error_identifier +float32 error_value +float32 min_value +float32 max_value +uint32 index +string message \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorIdentifier.msg new file mode 100644 index 0000000..bd684f6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorIdentifier.msg @@ -0,0 +1,12 @@ + +uint32 TRAJECTORY_ERROR_IDENTIFIER_UNSPECIFIED = 0 + +uint32 TRAJECTORY_ERROR_IDENTIFIER_UNAPPLICABLE = 1 + +uint32 TRAJECTORY_ERROR_IDENTIFIER_TIME = 2 + +uint32 TRAJECTORY_ERROR_IDENTIFIER_POSITION = 3 + +uint32 TRAJECTORY_ERROR_IDENTIFIER_VELOCITY = 4 + +uint32 TRAJECTORY_ERROR_IDENTIFIER_ACCELERATION = 5 diff --git a/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorReport.msg b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorReport.msg new file mode 100644 index 0000000..fc262c7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorReport.msg @@ -0,0 +1,2 @@ + +TrajectoryErrorElement[] trajectory_error_elements \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorType.msg b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorType.msg new file mode 100644 index 0000000..612e3b1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TrajectoryErrorType.msg @@ -0,0 +1,40 @@ + +uint32 TRAJECTORY_ERROR_TYPE_UNSPECIFIED = 0 + +uint32 TRAJECTORY_ERROR_TYPE_OUTSIDE_WORKSPACE = 1 + +uint32 TRAJECTORY_ERROR_TYPE_ACTUATOR_COUNT_MISMATCH = 2 + +uint32 TRAJECTORY_ERROR_TYPE_INVALID_DURATION = 3 + +uint32 TRAJECTORY_ERROR_TYPE_ZERO_DISTANCE = 4 + +uint32 TRAJECTORY_ERROR_TYPE_INVALID_SPEED = 5 + +uint32 TRAJECTORY_ERROR_TYPE_LARGE_SPEED = 6 + +uint32 TRAJECTORY_ERROR_TYPE_INVALID_ACCELERATION = 7 + +uint32 TRAJECTORY_ERROR_TYPE_INVALID_TIME_STEP = 8 + +uint32 TRAJECTORY_ERROR_TYPE_LARGE_SIZE = 9 + +uint32 TRAJECTORY_ERROR_TYPE_WRONG_MODE = 10 + +uint32 TRAJECTORY_ERROR_TYPE_JOINT_POSITION_LIMIT = 11 + +uint32 TRAJECTORY_ERROR_TYPE_FILE_ERROR = 12 + +uint32 TRAJECTORY_ERROR_TYPE_NO_FILE_IN_MEMORY = 13 + +uint32 TRAJECTORY_ERROR_TYPE_INDEX_OUT_OF_TRAJ = 14 + +uint32 TRAJECTORY_ERROR_TYPE_ALREADY_RUNNING = 15 + +uint32 TRAJECTORY_ERROR_TYPE_WRONG_STARTING_POINT = 16 + +uint32 TRAJECTORY_ERROR_TYPE_CARTESIAN_CANNOT_START = 17 + +uint32 TRAJECTORY_ERROR_TYPE_WRONG_STARTING_SPEED = 18 + +uint32 TRAJECTORY_ERROR_TYPE_INVALID_POSITION = 19 diff --git a/ros_kortex/kortex_driver/msg/generated/base/TransformationMatrix.msg b/ros_kortex/kortex_driver/msg/generated/base/TransformationMatrix.msg new file mode 100644 index 0000000..e2d42e3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TransformationMatrix.msg @@ -0,0 +1,5 @@ + +TransformationRow r0 +TransformationRow r1 +TransformationRow r2 +TransformationRow r3 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/TransformationRow.msg b/ros_kortex/kortex_driver/msg/generated/base/TransformationRow.msg new file mode 100644 index 0000000..57d1a53 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TransformationRow.msg @@ -0,0 +1,5 @@ + +float32 c0 +float32 c1 +float32 c2 +float32 c3 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/Twist.msg b/ros_kortex/kortex_driver/msg/generated/base/Twist.msg new file mode 100644 index 0000000..482f7a6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Twist.msg @@ -0,0 +1,7 @@ + +float32 linear_x +float32 linear_y +float32 linear_z +float32 angular_x +float32 angular_y +float32 angular_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/TwistCommand.msg b/ros_kortex/kortex_driver/msg/generated/base/TwistCommand.msg new file mode 100644 index 0000000..325d3c7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TwistCommand.msg @@ -0,0 +1,4 @@ + +uint32 reference_frame +Twist twist +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/TwistLimitation.msg b/ros_kortex/kortex_driver/msg/generated/base/TwistLimitation.msg new file mode 100644 index 0000000..71d333a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/TwistLimitation.msg @@ -0,0 +1,3 @@ + +float32 linear +float32 angular \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/UserEvent.msg b/ros_kortex/kortex_driver/msg/generated/base/UserEvent.msg new file mode 100644 index 0000000..84356e0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/UserEvent.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_USER_EVENT = 0 + +uint32 LOGGED_OUT = 1 + +uint32 LOGGED_IN = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/UserList.msg b/ros_kortex/kortex_driver/msg/generated/base/UserList.msg new file mode 100644 index 0000000..2675d7a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/UserList.msg @@ -0,0 +1,2 @@ + +UserProfileHandle[] user_handles \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/UserNotification.msg b/ros_kortex/kortex_driver/msg/generated/base/UserNotification.msg new file mode 100644 index 0000000..81cda4f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/UserNotification.msg @@ -0,0 +1,6 @@ + +uint32 user_event +UserProfileHandle modified_user +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/UserNotificationList.msg b/ros_kortex/kortex_driver/msg/generated/base/UserNotificationList.msg new file mode 100644 index 0000000..38a029c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/UserNotificationList.msg @@ -0,0 +1,2 @@ + +UserNotification[] notifications \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/UserProfile.msg b/ros_kortex/kortex_driver/msg/generated/base/UserProfile.msg new file mode 100644 index 0000000..f210d01 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/UserProfile.msg @@ -0,0 +1,6 @@ + +UserProfileHandle handle +string username +string firstname +string lastname +string application_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/UserProfileList.msg b/ros_kortex/kortex_driver/msg/generated/base/UserProfileList.msg new file mode 100644 index 0000000..121c0ee --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/UserProfileList.msg @@ -0,0 +1,2 @@ + +UserProfile[] user_profiles \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WifiConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/base/WifiConfiguration.msg new file mode 100644 index 0000000..a32e964 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WifiConfiguration.msg @@ -0,0 +1,4 @@ + +Ssid ssid +string security_key +bool connect_automatically \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WifiConfigurationList.msg b/ros_kortex/kortex_driver/msg/generated/base/WifiConfigurationList.msg new file mode 100644 index 0000000..724433a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WifiConfigurationList.msg @@ -0,0 +1,2 @@ + +WifiConfiguration[] wifi_configuration_list \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WifiEncryptionType.msg b/ros_kortex/kortex_driver/msg/generated/base/WifiEncryptionType.msg new file mode 100644 index 0000000..29abf12 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WifiEncryptionType.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_ENCRYPTION = 0 + +uint32 AES_ENCRYPTION = 1 + +uint32 TKIP_ENCRYPTION = 2 + +uint32 WEP_ENCRYPTION = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/base/WifiInformation.msg b/ros_kortex/kortex_driver/msg/generated/base/WifiInformation.msg new file mode 100644 index 0000000..a96899a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WifiInformation.msg @@ -0,0 +1,8 @@ + +Ssid ssid +uint32 security_type +uint32 encryption_type +uint32 signal_quality +int32 signal_strength +uint32 frequency +uint32 channel \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WifiInformationList.msg b/ros_kortex/kortex_driver/msg/generated/base/WifiInformationList.msg new file mode 100644 index 0000000..c6091c3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WifiInformationList.msg @@ -0,0 +1,2 @@ + +WifiInformation[] wifi_information_list \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WifiSecurityType.msg b/ros_kortex/kortex_driver/msg/generated/base/WifiSecurityType.msg new file mode 100644 index 0000000..9f118bc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WifiSecurityType.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_AUTHENTICATION = 0 + +uint32 WEP = 1 + +uint32 WPA2_PERSONAL = 2 + +uint32 WPA_PERSONAL = 4 + +uint32 NO_AUTHENTICATION = 8 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Wrench.msg b/ros_kortex/kortex_driver/msg/generated/base/Wrench.msg new file mode 100644 index 0000000..24b6e5c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Wrench.msg @@ -0,0 +1,7 @@ + +float32 force_x +float32 force_y +float32 force_z +float32 torque_x +float32 torque_y +float32 torque_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WrenchCommand.msg b/ros_kortex/kortex_driver/msg/generated/base/WrenchCommand.msg new file mode 100644 index 0000000..90dd313 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WrenchCommand.msg @@ -0,0 +1,5 @@ + +uint32 reference_frame +uint32 mode +Wrench wrench +uint32 duration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WrenchLimitation.msg b/ros_kortex/kortex_driver/msg/generated/base/WrenchLimitation.msg new file mode 100644 index 0000000..1d7a973 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WrenchLimitation.msg @@ -0,0 +1,3 @@ + +float32 force +float32 torque \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base/WrenchMode.msg b/ros_kortex/kortex_driver/msg/generated/base/WrenchMode.msg new file mode 100644 index 0000000..c60a59f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WrenchMode.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_WRENCH_MODE = 0 + +uint32 WRENCH_RESTRICTED = 1 + +uint32 WRENCH_NORMAL = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/base/WristDigitalInputIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/base/WristDigitalInputIdentifier.msg new file mode 100644 index 0000000..9e8440c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/WristDigitalInputIdentifier.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_WRIST_DIGITAL = 0 + +uint32 WRIST_BUTTON_1 = 1 + +uint32 WRIST_BUTTON_2 = 2 + +uint32 WRIST_BUTTON_BOTH = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Xbox360AnalogInputIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/base/Xbox360AnalogInputIdentifier.msg new file mode 100644 index 0000000..6946dc3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Xbox360AnalogInputIdentifier.msg @@ -0,0 +1,14 @@ + +uint32 UNSPECIFIED_XBOX360_ANALOG = 0 + +uint32 XBOX360_THUMB_LEFT_X = 1 + +uint32 XBOX360_THUMB_LEFT_Y = 2 + +uint32 XBOX360_THUMB_RIGHT_X = 3 + +uint32 XBOX360_THUMB_RIGHT_Y = 4 + +uint32 XBOX360_TRIGGER_LEFT = 5 + +uint32 XBOX360_TRIGGER_RIGHT = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/base/Xbox360DigitalInputIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/base/Xbox360DigitalInputIdentifier.msg new file mode 100644 index 0000000..39e7720 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/Xbox360DigitalInputIdentifier.msg @@ -0,0 +1,30 @@ + +uint32 UNSPECIFIED_XBOX360_DIGITAL = 0 + +uint32 XBOX360_PAD_UP = 1 + +uint32 XBOX360_PAD_DOWN = 2 + +uint32 XBOX360_PAD_LEFT = 3 + +uint32 XBOX360_PAD_RIGHT = 4 + +uint32 XBOX360_FILE_BUTTON_START = 5 + +uint32 XBOX360_DOCUMENT_BUTTON_BACK = 6 + +uint32 XBOX360_LEFT_THUMB_BUTTON = 7 + +uint32 XBOX360_RIGHT_THUMB_BUTTON = 8 + +uint32 XBOX360_LEFT_SHOULDER = 9 + +uint32 XBOX360_RIGHT_SHOULDER = 10 + +uint32 XBOX360_BUTTON_A = 13 + +uint32 XBOX360_BUTTON_B = 14 + +uint32 XBOX360_BUTTON_X = 15 + +uint32 XBOX360_BUTTON_Y = 16 diff --git a/ros_kortex/kortex_driver/msg/generated/base/ZoneShape.msg b/ros_kortex/kortex_driver/msg/generated/base/ZoneShape.msg new file mode 100644 index 0000000..48e3cdc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base/ZoneShape.msg @@ -0,0 +1,6 @@ + +uint32 shape_type +Point origin +Base_RotationMatrix orientation +float32[] dimensions +float32 envelope_thickness \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorCommand.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorCommand.msg new file mode 100644 index 0000000..82cf0a0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorCommand.msg @@ -0,0 +1,7 @@ + +uint32 command_id +uint32 flags +float32 position +float32 velocity +float32 torque_joint +float32 current_motor \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorCustomData.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorCustomData.msg new file mode 100644 index 0000000..9016e82 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorCustomData.msg @@ -0,0 +1,18 @@ + +uint32 command_id +uint32 custom_data_0 +uint32 custom_data_1 +uint32 custom_data_2 +uint32 custom_data_3 +uint32 custom_data_4 +uint32 custom_data_5 +uint32 custom_data_6 +uint32 custom_data_7 +uint32 custom_data_8 +uint32 custom_data_9 +uint32 custom_data_10 +uint32 custom_data_11 +uint32 custom_data_12 +uint32 custom_data_13 +uint32 custom_data_14 +uint32 custom_data_15 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorFeedback.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorFeedback.msg new file mode 100644 index 0000000..3f1c60e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/ActuatorFeedback.msg @@ -0,0 +1,15 @@ + +uint32 command_id +uint32 status_flags +uint32 jitter_comm +float32 position +float32 velocity +float32 torque +float32 current_motor +float32 voltage +float32 temperature_motor +float32 temperature_core +uint32 fault_bank_a +uint32 fault_bank_b +uint32 warning_bank_a +uint32 warning_bank_b \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_Command.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_Command.msg new file mode 100644 index 0000000..78c3873 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_Command.msg @@ -0,0 +1,4 @@ + +uint32 frame_id +ActuatorCommand[] actuators +InterconnectCyclic_Command interconnect \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_CustomData.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_CustomData.msg new file mode 100644 index 0000000..5ea4937 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_CustomData.msg @@ -0,0 +1,12 @@ + +uint32 frame_id +uint32 custom_data_0 +uint32 custom_data_1 +uint32 custom_data_2 +uint32 custom_data_3 +uint32 custom_data_4 +uint32 custom_data_5 +uint32 custom_data_6 +uint32 custom_data_7 +ActuatorCustomData[] actuators_custom_data +InterconnectCyclic_CustomData interconnect_custom_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_Feedback.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_Feedback.msg new file mode 100644 index 0000000..be3a3f9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_Feedback.msg @@ -0,0 +1,5 @@ + +uint32 frame_id +BaseFeedback base +ActuatorFeedback[] actuators +InterconnectCyclic_Feedback interconnect \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseCyclic_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseFeedback.msg b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseFeedback.msg new file mode 100644 index 0000000..9df3559 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/base_cyclic/BaseFeedback.msg @@ -0,0 +1,41 @@ + +uint32 active_state_connection_identifier +uint32 active_state +float32 arm_voltage +float32 arm_current +float32 temperature_cpu +float32 temperature_ambient +float32 imu_acceleration_x +float32 imu_acceleration_y +float32 imu_acceleration_z +float32 imu_angular_velocity_x +float32 imu_angular_velocity_y +float32 imu_angular_velocity_z +float32 tool_pose_x +float32 tool_pose_y +float32 tool_pose_z +float32 tool_pose_theta_x +float32 tool_pose_theta_y +float32 tool_pose_theta_z +float32 tool_twist_linear_x +float32 tool_twist_linear_y +float32 tool_twist_linear_z +float32 tool_twist_angular_x +float32 tool_twist_angular_y +float32 tool_twist_angular_z +float32 tool_external_wrench_force_x +float32 tool_external_wrench_force_y +float32 tool_external_wrench_force_z +float32 tool_external_wrench_torque_x +float32 tool_external_wrench_torque_y +float32 tool_external_wrench_torque_z +uint32 fault_bank_a +uint32 fault_bank_b +uint32 warning_bank_a +uint32 warning_bank_b +float32 commanded_tool_pose_x +float32 commanded_tool_pose_y +float32 commanded_tool_pose_z +float32 commanded_tool_pose_theta_x +float32 commanded_tool_pose_theta_y +float32 commanded_tool_pose_theta_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/ArmState.msg b/ros_kortex/kortex_driver/msg/generated/common/ArmState.msg new file mode 100644 index 0000000..9d9db12 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/ArmState.msg @@ -0,0 +1,22 @@ + +uint32 ARMSTATE_UNSPECIFIED = 0 + +uint32 ARMSTATE_BASE_INITIALIZATION = 1 + +uint32 ARMSTATE_IDLE = 2 + +uint32 ARMSTATE_INITIALIZATION = 3 + +uint32 ARMSTATE_IN_FAULT = 4 + +uint32 ARMSTATE_MAINTENANCE = 5 + +uint32 ARMSTATE_SERVOING_LOW_LEVEL = 6 + +uint32 ARMSTATE_SERVOING_READY = 7 + +uint32 ARMSTATE_SERVOING_PLAYING_SEQUENCE = 8 + +uint32 ARMSTATE_SERVOING_MANUALLY_CONTROLLED = 9 + +uint32 ARMSTATE_RESERVED = 255 diff --git a/ros_kortex/kortex_driver/msg/generated/common/CartesianReferenceFrame.msg b/ros_kortex/kortex_driver/msg/generated/common/CartesianReferenceFrame.msg new file mode 100644 index 0000000..c519008 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/CartesianReferenceFrame.msg @@ -0,0 +1,8 @@ + +uint32 CARTESIAN_REFERENCE_FRAME_UNSPECIFIED = 0 + +uint32 CARTESIAN_REFERENCE_FRAME_MIXED = 1 + +uint32 CARTESIAN_REFERENCE_FRAME_TOOL = 2 + +uint32 CARTESIAN_REFERENCE_FRAME_BASE = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/common/Connection.msg b/ros_kortex/kortex_driver/msg/generated/common/Connection.msg new file mode 100644 index 0000000..6f7f7ab --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/Connection.msg @@ -0,0 +1,4 @@ + +UserProfileHandle user_handle +string connection_information +uint32 connection_identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/CountryCode.msg b/ros_kortex/kortex_driver/msg/generated/common/CountryCode.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/CountryCode.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/CountryCodeIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/common/CountryCodeIdentifier.msg new file mode 100644 index 0000000..65273b2 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/CountryCodeIdentifier.msg @@ -0,0 +1,226 @@ + +uint32 UNSPECIFIED_COUNTRY_CODE = 0 + +uint32 UNITED_ARAB_EMIRATES_AE = 1 + +uint32 ANTIGUA_AND_BARBUDA_AG = 2 + +uint32 ANGUILLA_AI = 3 + +uint32 ALBANIA_AL = 4 + +uint32 AMERICAN_SAMOA_AS = 5 + +uint32 AUSTRIA_AT = 6 + +uint32 AUSTRALIA_AU = 7 + +uint32 ARUBA_AW = 8 + +uint32 AZERBAIJAN_AZ = 9 + +uint32 BOSNIA_AND_HERZEGOVINA_BA = 10 + +uint32 BANGLADESH_BD = 11 + +uint32 BELGIUM_BE = 12 + +uint32 BULGARIA_BG = 13 + +uint32 BAHRAIN_BH = 14 + +uint32 BERMUDA_BM = 15 + +uint32 BRUNEI_DARUSSALAM_BN = 16 + +uint32 BRAZIL_BR = 17 + +uint32 BAHAMAS_BS = 18 + +uint32 BELARUS_BY = 19 + +uint32 SWITZERLAND_CH = 20 + +uint32 CANADA_CA = 21 + +uint32 CHINA_CN = 22 + +uint32 COLOMBIA_CO = 23 + +uint32 COSTA_RICA_CR = 24 + +uint32 CYPRUS_CY = 25 + +uint32 CZECH_REPUBLIC_CZ = 26 + +uint32 GERMANY_DE = 27 + +uint32 DENMARK_DK = 28 + +uint32 ECUADOR_EC = 29 + +uint32 ESTONIA_EE = 30 + +uint32 EGYPT_EG = 31 + +uint32 SPAIN_ES = 32 + +uint32 ETHIOPIA_ET = 33 + +uint32 FINLAND_FI = 34 + +uint32 FRANCE_FR = 35 + +uint32 UNITED_KINGDOM_GB = 36 + +uint32 GRENADA_GD = 37 + +uint32 FRENCH_GUIANA_GF = 38 + +uint32 GUADELOUPE_GP = 39 + +uint32 GREECE_GR = 40 + +uint32 GUATEMALA_GT = 41 + +uint32 GUAM_GU = 42 + +uint32 HONG_KONG_HK = 43 + +uint32 CROATIA_HR = 44 + +uint32 HUNGARY_HU = 45 + +uint32 INDIA_IN = 46 + +uint32 INDONESIA_ID = 47 + +uint32 IRELAND_IE = 48 + +uint32 ISRAEL_IL = 49 + +uint32 ICELAND_IS = 50 + +uint32 ITALY_IT = 51 + +uint32 JORDAN_JO = 52 + +uint32 JAPAN_JP = 53 + +uint32 CAMBODIA_KH = 54 + +uint32 REPUBLIC_OF_KOREA_KR = 55 + +uint32 KUWAIT_KW = 56 + +uint32 CAYMAN_ISLANDS_KY = 57 + +uint32 LAO_PDR_LA = 58 + +uint32 LEBANON_LB = 59 + +uint32 LIECHTENSTEIN_LI = 60 + +uint32 SRI_LANKA_LK = 61 + +uint32 LESOTHO_LS = 62 + +uint32 LITHUANIA_LT = 63 + +uint32 LUXEMBOURG_LU = 64 + +uint32 LATVIA_LV = 65 + +uint32 MOROCCO_MA = 66 + +uint32 MONACO_MC = 67 + +uint32 MOLDOVA_MD = 68 + +uint32 MONTENEGRO_ME = 69 + +uint32 REPUBLIC_OF_MACEDONIA_MK = 70 + +uint32 MONGOLIA_MN = 71 + +uint32 MARTINIQUE_MQ = 72 + +uint32 MAURITANIA_MR = 73 + +uint32 MALTA_MT = 74 + +uint32 MAURITIUS_MU = 75 + +uint32 MALDIVES_MV = 76 + +uint32 MALAWI_MW = 77 + +uint32 MEXICO_MX = 78 + +uint32 MALAYSIA_MY = 79 + +uint32 NICARAGUA_NI = 80 + +uint32 NETHERLANDS_NL = 81 + +uint32 NORWAY_NO = 82 + +uint32 NEW_ZEALAND_NZ = 83 + +uint32 OMAN_OM = 84 + +uint32 PANAMA_PA = 85 + +uint32 PERU_PE = 86 + +uint32 PHILIPPINES_PH = 87 + +uint32 POLAND_PL = 88 + +uint32 PUERTO_RICO_PR = 89 + +uint32 PORTUGAL_PT = 90 + +uint32 PARAGUAY_PY = 91 + +uint32 REUNION_RE = 92 + +uint32 ROMANIA_RO = 93 + +uint32 SERBIA_RS = 94 + +uint32 RUSSIAN_FEDERATION_RU = 95 + +uint32 SWEDEN_SE = 96 + +uint32 SINGAPORE_SI = 97 + +uint32 SLOVAKIA_SK = 98 + +uint32 EL_SALVADOR_SV = 99 + +uint32 THAILAND_TH = 100 + +uint32 TUNISIA_TN = 101 + +uint32 TURKEY_TR = 102 + +uint32 TRINIDAD_AND_TOBAGO_TT = 103 + +uint32 TAIWAN_PROVINCE_OF_CHINA_TW = 104 + +uint32 UKRAINE_UA = 105 + +uint32 UNITED_STATES_US = 106 + +uint32 HOLY_SEE_VATICAN_CITY_STATE_VA = 107 + +uint32 BOLIVARIAN_REPUBLIC_OF_VENEZUELA_VE = 108 + +uint32 BRITISH_VIRGIN_ISLANDS_VG = 109 + +uint32 VIETNAM_VN = 110 + +uint32 MAYOTTE_YT = 111 + +uint32 SOUTH_AFRICA_ZA = 112 diff --git a/ros_kortex/kortex_driver/msg/generated/common/DeviceHandle.msg b/ros_kortex/kortex_driver/msg/generated/common/DeviceHandle.msg new file mode 100644 index 0000000..a1e1083 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/DeviceHandle.msg @@ -0,0 +1,4 @@ + +uint32 device_type +uint32 device_identifier +uint32 order \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/DeviceTypes.msg b/ros_kortex/kortex_driver/msg/generated/common/DeviceTypes.msg new file mode 100644 index 0000000..d2fdf25 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/DeviceTypes.msg @@ -0,0 +1,18 @@ + +uint32 UNSPECIFIED_DEVICE_TYPE = 0 + +uint32 BASE = 1 + +uint32 VISION = 2 + +uint32 BIG_ACTUATOR = 3 + +uint32 SMALL_ACTUATOR = 4 + +uint32 INTERCONNECT = 5 + +uint32 GRIPPER = 6 + +uint32 MEDIUM_ACTUATOR = 7 + +uint32 XBIG_ACTUATOR = 8 diff --git a/ros_kortex/kortex_driver/msg/generated/common/Empty.msg b/ros_kortex/kortex_driver/msg/generated/common/Empty.msg new file mode 100644 index 0000000..e69de29 diff --git a/ros_kortex/kortex_driver/msg/generated/common/NotificationHandle.msg b/ros_kortex/kortex_driver/msg/generated/common/NotificationHandle.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/NotificationHandle.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/NotificationOptions.msg b/ros_kortex/kortex_driver/msg/generated/common/NotificationOptions.msg new file mode 100644 index 0000000..48cb13e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/NotificationOptions.msg @@ -0,0 +1,4 @@ + +uint32 type +uint32 rate_m_sec +float32 threshold_value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/NotificationType.msg b/ros_kortex/kortex_driver/msg/generated/common/NotificationType.msg new file mode 100644 index 0000000..881cd9a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/NotificationType.msg @@ -0,0 +1,8 @@ + +uint32 NOTIFICATION_TYPE_UNSPECIFIED = 0 + +uint32 NOTIFICATION_TYPE_THRESHOLD = 1 + +uint32 NOTIFICATION_TYPE_FIX_RATE = 2 + +uint32 NOTIFICATION_TYPE_EVENT = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/common/Permission.msg b/ros_kortex/kortex_driver/msg/generated/common/Permission.msg new file mode 100644 index 0000000..c5399e9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/Permission.msg @@ -0,0 +1,8 @@ + +uint32 NO_PERMISSION = 0 + +uint32 READ_PERMISSION = 1 + +uint32 UPDATE_PERMISSION = 2 + +uint32 DELETE_PERMISSION = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/common/SafetyHandle.msg b/ros_kortex/kortex_driver/msg/generated/common/SafetyHandle.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/SafetyHandle.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/SafetyNotification.msg b/ros_kortex/kortex_driver/msg/generated/common/SafetyNotification.msg new file mode 100644 index 0000000..f68ba0c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/SafetyNotification.msg @@ -0,0 +1,6 @@ + +SafetyHandle safety_handle +uint32 value +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/SafetyStatusValue.msg b/ros_kortex/kortex_driver/msg/generated/common/SafetyStatusValue.msg new file mode 100644 index 0000000..74ffcfc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/SafetyStatusValue.msg @@ -0,0 +1,8 @@ + +uint32 SAFETY_STATUS_UNSPECIFIED = 0 + +uint32 SAFETY_STATUS_WARNING = 1 + +uint32 SAFETY_STATUS_ERROR = 2 + +uint32 SAFETY_STATUS_NORMAL = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/common/Timestamp.msg b/ros_kortex/kortex_driver/msg/generated/common/Timestamp.msg new file mode 100644 index 0000000..8f08067 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/Timestamp.msg @@ -0,0 +1,3 @@ + +uint32 sec +uint32 usec \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/UARTConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/common/UARTConfiguration.msg new file mode 100644 index 0000000..82ae0c8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UARTConfiguration.msg @@ -0,0 +1,7 @@ + +uint32 port_id +bool enabled +uint32 speed +uint32 word_length +uint32 stop_bits +uint32 parity \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/UARTDeviceIdentification.msg b/ros_kortex/kortex_driver/msg/generated/common/UARTDeviceIdentification.msg new file mode 100644 index 0000000..b0f9559 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UARTDeviceIdentification.msg @@ -0,0 +1,2 @@ + +uint32 port_id \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/common/UARTParity.msg b/ros_kortex/kortex_driver/msg/generated/common/UARTParity.msg new file mode 100644 index 0000000..97e58a8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UARTParity.msg @@ -0,0 +1,8 @@ + +uint32 UART_PARITY_UNSPECIFIED = 0 + +uint32 UART_PARITY_NONE = 1 + +uint32 UART_PARITY_ODD = 2 + +uint32 UART_PARITY_EVEN = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/common/UARTSpeed.msg b/ros_kortex/kortex_driver/msg/generated/common/UARTSpeed.msg new file mode 100644 index 0000000..50f2b87 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UARTSpeed.msg @@ -0,0 +1,32 @@ + +uint32 UART_SPEED_UNSPECIFIED = 0 + +uint32 UART_SPEED_4800 = 1 + +uint32 UART_SPEED_9600 = 2 + +uint32 UART_SPEED_19200 = 3 + +uint32 UART_SPEED_38400 = 4 + +uint32 UART_SPEED_57600 = 5 + +uint32 UART_SPEED_115200 = 6 + +uint32 UART_SPEED_230400 = 7 + +uint32 UART_SPEED_460800 = 8 + +uint32 UART_SPEED_921600 = 9 + +uint32 UART_SPEED_1382400 = 10 + +uint32 UART_SPEED_1612800 = 11 + +uint32 UART_SPEED_1843200 = 12 + +uint32 UART_SPEED_2073600 = 13 + +uint32 UART_SPEED_2188800 = 14 + +uint32 UART_SPEED_2246400 = 15 diff --git a/ros_kortex/kortex_driver/msg/generated/common/UARTStopBits.msg b/ros_kortex/kortex_driver/msg/generated/common/UARTStopBits.msg new file mode 100644 index 0000000..0de6f12 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UARTStopBits.msg @@ -0,0 +1,10 @@ + +uint32 UART_STOP_BITS_UNSPECIFIED = 0 + +uint32 UART_STOP_BITS_0_5 = 1 + +uint32 UART_STOP_BITS_1 = 2 + +uint32 UART_STOP_BITS_1_5 = 3 + +uint32 UART_STOP_BITS_2 = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/common/UARTWordLength.msg b/ros_kortex/kortex_driver/msg/generated/common/UARTWordLength.msg new file mode 100644 index 0000000..e6b2f08 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UARTWordLength.msg @@ -0,0 +1,8 @@ + +uint32 UART_WORD_LENGTH_UNSPECIFIED = 0 + +uint32 UART_WORD_LENGTH_7 = 1 + +uint32 UART_WORD_LENGTH_8 = 2 + +uint32 UART_WORD_LENGTH_9 = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/common/Unit.msg b/ros_kortex/kortex_driver/msg/generated/common/Unit.msg new file mode 100644 index 0000000..c019aeb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/Unit.msg @@ -0,0 +1,28 @@ + +uint32 UNSPECIFIED_UNIT = 0 + +uint32 CELSIUS = 1 + +uint32 AMPERE = 2 + +uint32 VOLT = 3 + +uint32 METER_PER_SECOND = 4 + +uint32 DEGREE_PER_SECOND = 5 + +uint32 METER_PER_SECOND_2 = 6 + +uint32 DEGREE_PER_SECOND_2 = 7 + +uint32 NEWTON = 8 + +uint32 NEWTON_METER = 9 + +uint32 KILOGRAM = 10 + +uint32 DEGREE = 11 + +uint32 TICK = 12 + +uint32 DEGREE_PER_MILLISECOND = 13 diff --git a/ros_kortex/kortex_driver/msg/generated/common/UserProfileHandle.msg b/ros_kortex/kortex_driver/msg/generated/common/UserProfileHandle.msg new file mode 100644 index 0000000..4d2b97e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/common/UserProfileHandle.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 permission \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/AngularTwist.msg b/ros_kortex/kortex_driver/msg/generated/control_config/AngularTwist.msg new file mode 100644 index 0000000..6ea2ee1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/AngularTwist.msg @@ -0,0 +1,2 @@ + +float32 angular \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/CartesianReferenceFrameInfo.msg b/ros_kortex/kortex_driver/msg/generated/control_config/CartesianReferenceFrameInfo.msg new file mode 100644 index 0000000..7aafcc6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/CartesianReferenceFrameInfo.msg @@ -0,0 +1,2 @@ + +uint32 reference_frame \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/CartesianTransform.msg b/ros_kortex/kortex_driver/msg/generated/control_config/CartesianTransform.msg new file mode 100644 index 0000000..b1f7d64 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/CartesianTransform.msg @@ -0,0 +1,7 @@ + +float32 x +float32 y +float32 z +float32 theta_x +float32 theta_y +float32 theta_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ControlMode.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ControlMode.msg new file mode 100644 index 0000000..0ded911 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ControlMode.msg @@ -0,0 +1,22 @@ + +uint32 UNSPECIFIED_CONTROL_MODE = 0 + +uint32 ANGULAR_JOYSTICK = 1 + +uint32 CARTESIAN_JOYSTICK = 2 + +uint32 ANGULAR_TRAJECTORY = 4 + +uint32 CARTESIAN_TRAJECTORY = 5 + +uint32 CARTESIAN_ADMITTANCE = 6 + +uint32 JOINT_ADMITTANCE = 7 + +uint32 NULL_SPACE_ADMITTANCE = 8 + +uint32 FORCE_CONTROL = 10 + +uint32 FORCE_CONTROL_MOTION_RESTRICTED = 11 + +uint32 IDLE = 13 diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ControlModeInformation.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ControlModeInformation.msg new file mode 100644 index 0000000..713ed37 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ControlModeInformation.msg @@ -0,0 +1,2 @@ + +uint32 control_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_JointSpeeds.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_JointSpeeds.msg new file mode 100644 index 0000000..e85a31a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_JointSpeeds.msg @@ -0,0 +1,2 @@ + +float32[] joint_speed \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_Position.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_Position.msg new file mode 100644 index 0000000..678ce63 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_Position.msg @@ -0,0 +1,4 @@ + +float32 x +float32 y +float32 z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfig_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfigurationEvent.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfigurationEvent.msg new file mode 100644 index 0000000..d677f33 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfigurationEvent.msg @@ -0,0 +1,42 @@ + +uint32 UNSPECIFIED_CONTROL_CONFIGURATION_EVENT = 0 + +uint32 ANGLE_UNIT_CHANGED = 1 + +uint32 GRAVITY_VECTOR_CHANGED = 2 + +uint32 JOINT_ADMITTANCE_CONFIGURATION_CHANGED = 4 + +uint32 NULL_ADMITTANCE_CONFIGURATION_CHANGED = 5 + +uint32 CARTESIAN_ADMITTANCE_CONFIGURATION_CHANGED = 6 + +uint32 JOINT_TORQUE_HYBRID_CONFIGURATION_CHANGED = 7 + +uint32 WRENCH_COMMAND_NORMAL_CONFIGURATION_CHANGED = 8 + +uint32 WRENCH_COMMAND_RESTRICTED_CONFIGURATION_CHANGED = 9 + +uint32 CONTROL_CONFIGURATION_FACTORY_RESTORED = 10 + +uint32 TOOL_CONFIGURATION_CHANGED = 11 + +uint32 PAYLOAD_CONFIGURATION_CHANGED = 12 + +uint32 CARTESIAN_REFERENCE_CHANGED = 13 + +uint32 CHANGE_CONTROL_MODE_FAILED = 14 + +uint32 JOINT_SPEED_SOFT_LIMITS_CHANGED = 16 + +uint32 TWIST_LINEAR_SOFT_LIMIT_CHANGED = 17 + +uint32 TWIST_ANGULAR_SOFT_LIMIT_CHANGED = 18 + +uint32 JOINT_ACCELERATION_SOFT_LIMITS_CHANGED = 19 + +uint32 DESIRED_TWIST_LINEAR_SPEED_CHANGED = 20 + +uint32 DESIRED_TWIST_ANGULAR_SPEED_CHANGED = 21 + +uint32 DESIRED_JOINT_SPEED_CHANGED = 22 diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfigurationNotification.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfigurationNotification.msg new file mode 100644 index 0000000..3863572 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ControlConfigurationNotification.msg @@ -0,0 +1,5 @@ + +uint32 event +Timestamp timestamp +UserProfileHandle user_handle +Connection connection \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/DesiredSpeeds.msg b/ros_kortex/kortex_driver/msg/generated/control_config/DesiredSpeeds.msg new file mode 100644 index 0000000..be5aa13 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/DesiredSpeeds.msg @@ -0,0 +1,4 @@ + +float32 linear +float32 angular +float32[] joint_speed \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/GravityVector.msg b/ros_kortex/kortex_driver/msg/generated/control_config/GravityVector.msg new file mode 100644 index 0000000..678ce63 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/GravityVector.msg @@ -0,0 +1,4 @@ + +float32 x +float32 y +float32 z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/JointAccelerationSoftLimits.msg b/ros_kortex/kortex_driver/msg/generated/control_config/JointAccelerationSoftLimits.msg new file mode 100644 index 0000000..b1aad35 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/JointAccelerationSoftLimits.msg @@ -0,0 +1,3 @@ + +uint32 control_mode +float32[] joint_acceleration_soft_limits \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/JointSpeedSoftLimits.msg b/ros_kortex/kortex_driver/msg/generated/control_config/JointSpeedSoftLimits.msg new file mode 100644 index 0000000..ce90f8d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/JointSpeedSoftLimits.msg @@ -0,0 +1,3 @@ + +uint32 control_mode +float32[] joint_speed_soft_limits \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/KinematicLimits.msg b/ros_kortex/kortex_driver/msg/generated/control_config/KinematicLimits.msg new file mode 100644 index 0000000..9be9fa1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/KinematicLimits.msg @@ -0,0 +1,6 @@ + +uint32 control_mode +float32 twist_linear +float32 twist_angular +float32[] joint_speed_limits +float32[] joint_acceleration_limits \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/KinematicLimitsList.msg b/ros_kortex/kortex_driver/msg/generated/control_config/KinematicLimitsList.msg new file mode 100644 index 0000000..b407054 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/KinematicLimitsList.msg @@ -0,0 +1,2 @@ + +KinematicLimits[] kinematic_limits_list \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/LinearTwist.msg b/ros_kortex/kortex_driver/msg/generated/control_config/LinearTwist.msg new file mode 100644 index 0000000..9a7bee9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/LinearTwist.msg @@ -0,0 +1,2 @@ + +float32 linear \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/PayloadInformation.msg b/ros_kortex/kortex_driver/msg/generated/control_config/PayloadInformation.msg new file mode 100644 index 0000000..f60166e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/PayloadInformation.msg @@ -0,0 +1,3 @@ + +float32 payload_mass +ControlConfig_Position payload_mass_center \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/ToolConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/control_config/ToolConfiguration.msg new file mode 100644 index 0000000..3174f45 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/ToolConfiguration.msg @@ -0,0 +1,4 @@ + +CartesianTransform tool_transform +float32 tool_mass +ControlConfig_Position tool_mass_center \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/TwistAngularSoftLimit.msg b/ros_kortex/kortex_driver/msg/generated/control_config/TwistAngularSoftLimit.msg new file mode 100644 index 0000000..9882e9c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/TwistAngularSoftLimit.msg @@ -0,0 +1,3 @@ + +uint32 control_mode +float32 twist_angular_soft_limit \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/control_config/TwistLinearSoftLimit.msg b/ros_kortex/kortex_driver/msg/generated/control_config/TwistLinearSoftLimit.msg new file mode 100644 index 0000000..7182135 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/control_config/TwistLinearSoftLimit.msg @@ -0,0 +1,3 @@ + +uint32 control_mode +float32 twist_linear_soft_limit \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/BootloaderVersion.msg b/ros_kortex/kortex_driver/msg/generated/device_config/BootloaderVersion.msg new file mode 100644 index 0000000..1224490 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/BootloaderVersion.msg @@ -0,0 +1,2 @@ + +uint32 bootloader_version \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/Calibration.msg b/ros_kortex/kortex_driver/msg/generated/device_config/Calibration.msg new file mode 100644 index 0000000..9d8eda4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/Calibration.msg @@ -0,0 +1,3 @@ + +uint32 calibration_item +CalibrationParameter[] calibration_parameter \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationElement.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationElement.msg new file mode 100644 index 0000000..017bd56 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationElement.msg @@ -0,0 +1,2 @@ + +uint32 calibration_item \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationItem.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationItem.msg new file mode 100644 index 0000000..5afadf7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationItem.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_CALIBRATION_ITEM = 0 + +uint32 COGGING = 1 + +uint32 MAGNETIC = 2 + +uint32 MOTOR = 3 + +uint32 POSITION_RANGE = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationParameter.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationParameter.msg new file mode 100644 index 0000000..f19b5b5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationParameter.msg @@ -0,0 +1,3 @@ + +uint32 calibration_parameter_identifier +CalibrationParameter_value oneof_value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationParameter_value.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationParameter_value.msg new file mode 100644 index 0000000..12cff86 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationParameter_value.msg @@ -0,0 +1,4 @@ + +uint32[] signedIntValue +uint32[] unsignedIntValue +uint32[] floatValue \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationResult.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationResult.msg new file mode 100644 index 0000000..d5047be --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationResult.msg @@ -0,0 +1,3 @@ + +uint32 calibration_status +uint32 calibration_details \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationStatus.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationStatus.msg new file mode 100644 index 0000000..25b3392 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CalibrationStatus.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_CALIBRATION_STATUS = 0 + +uint32 NOT_CALIBRATED = 1 + +uint32 IN_PROGRESS = 2 + +uint32 CALIBRATED = 3 + +uint32 IN_FAULT = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/CapSenseRegister.msg b/ros_kortex/kortex_driver/msg/generated/device_config/CapSenseRegister.msg new file mode 100644 index 0000000..e42eb76 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/CapSenseRegister.msg @@ -0,0 +1,3 @@ + +uint32 address +uint32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_CapSenseConfig.msg b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_CapSenseConfig.msg new file mode 100644 index 0000000..cde8aea --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_CapSenseConfig.msg @@ -0,0 +1,4 @@ + +uint32 mode +float32 threshold_a +float32 threshold_b \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_CapSenseMode.msg b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_CapSenseMode.msg new file mode 100644 index 0000000..5a7abc4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_CapSenseMode.msg @@ -0,0 +1,12 @@ + +uint32 RESERVED = 0 + +uint32 INACTIVE = 1 + +uint32 ACTIVE_AUTO_THRESHOLD = 2 + +uint32 ACTIVE_NOISE_ATT = 4 + +uint32 ACTIVE_NORMAL = 5 + +uint32 CONFIGURATION = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_SafetyLimitType.msg b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_SafetyLimitType.msg new file mode 100644 index 0000000..f0beacf --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_SafetyLimitType.msg @@ -0,0 +1,8 @@ + +uint32 UNSPECIFIED_SAFETY_LIMIT_TYPE = 0 + +uint32 MINIMAL_LIMIT = 1 + +uint32 MAXIMAL_LIMIT = 2 + +uint32 EVENT_LIMIT = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceConfig_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/DeviceType.msg b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceType.msg new file mode 100644 index 0000000..8206d5f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/DeviceType.msg @@ -0,0 +1,2 @@ + +uint32 device_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/FirmwareVersion.msg b/ros_kortex/kortex_driver/msg/generated/device_config/FirmwareVersion.msg new file mode 100644 index 0000000..717c4f0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/FirmwareVersion.msg @@ -0,0 +1,2 @@ + +uint32 firmware_version \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/IPv4Settings.msg b/ros_kortex/kortex_driver/msg/generated/device_config/IPv4Settings.msg new file mode 100644 index 0000000..bf67c15 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/IPv4Settings.msg @@ -0,0 +1,4 @@ + +uint32 ipv4_address +uint32 ipv4_subnet_mask +uint32 ipv4_default_gateway \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/MACAddress.msg b/ros_kortex/kortex_driver/msg/generated/device_config/MACAddress.msg new file mode 100644 index 0000000..02257b1 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/MACAddress.msg @@ -0,0 +1,2 @@ + +uint8[] mac_address \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/ModelNumber.msg b/ros_kortex/kortex_driver/msg/generated/device_config/ModelNumber.msg new file mode 100644 index 0000000..c9f4bde --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/ModelNumber.msg @@ -0,0 +1,2 @@ + +string model_number \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/PartNumber.msg b/ros_kortex/kortex_driver/msg/generated/device_config/PartNumber.msg new file mode 100644 index 0000000..1a664a0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/PartNumber.msg @@ -0,0 +1,2 @@ + +string part_number \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/PartNumberRevision.msg b/ros_kortex/kortex_driver/msg/generated/device_config/PartNumberRevision.msg new file mode 100644 index 0000000..542f7cc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/PartNumberRevision.msg @@ -0,0 +1,2 @@ + +string part_number_revision \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/PowerOnSelfTestResult.msg b/ros_kortex/kortex_driver/msg/generated/device_config/PowerOnSelfTestResult.msg new file mode 100644 index 0000000..f7c1b8f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/PowerOnSelfTestResult.msg @@ -0,0 +1,2 @@ + +uint32 power_on_self_test_result \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/RebootRqst.msg b/ros_kortex/kortex_driver/msg/generated/device_config/RebootRqst.msg new file mode 100644 index 0000000..c590050 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/RebootRqst.msg @@ -0,0 +1,2 @@ + +uint32 delay \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/RunMode.msg b/ros_kortex/kortex_driver/msg/generated/device_config/RunMode.msg new file mode 100644 index 0000000..6cb4249 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/RunMode.msg @@ -0,0 +1,2 @@ + +uint32 run_mode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/RunModes.msg b/ros_kortex/kortex_driver/msg/generated/device_config/RunModes.msg new file mode 100644 index 0000000..15c2a7d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/RunModes.msg @@ -0,0 +1,10 @@ + +uint32 RUN_MODE = 0 + +uint32 CALIBRATION_MODE = 1 + +uint32 CONFIGURATION_MODE = 2 + +uint32 DEBUG_MODE = 3 + +uint32 TUNING_MODE = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyConfiguration.msg new file mode 100644 index 0000000..55cc2d3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyConfiguration.msg @@ -0,0 +1,5 @@ + +SafetyHandle handle +float32 error_threshold +float32 warning_threshold +SafetyEnable enable \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyConfigurationList.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyConfigurationList.msg new file mode 100644 index 0000000..463c33d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyConfigurationList.msg @@ -0,0 +1,2 @@ + +SafetyConfiguration[] configuration \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyEnable.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyEnable.msg new file mode 100644 index 0000000..eacdd94 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyEnable.msg @@ -0,0 +1,3 @@ + +SafetyHandle handle +bool enable \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyInformation.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyInformation.msg new file mode 100644 index 0000000..985096b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyInformation.msg @@ -0,0 +1,12 @@ + +SafetyHandle handle +bool can_change_safety_state +bool has_warning_threshold +bool has_error_threshold +uint32 limit_type +float32 default_warning_threshold +float32 default_error_threshold +float32 upper_hard_limit +float32 lower_hard_limit +uint32 status +uint32 unit \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyInformationList.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyInformationList.msg new file mode 100644 index 0000000..976e2b8 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyInformationList.msg @@ -0,0 +1,2 @@ + +SafetyInformation[] information \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyStatus.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyStatus.msg new file mode 100644 index 0000000..129c5a3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyStatus.msg @@ -0,0 +1,2 @@ + +uint32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SafetyThreshold.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyThreshold.msg new file mode 100644 index 0000000..ba839ee --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SafetyThreshold.msg @@ -0,0 +1,3 @@ + +SafetyHandle handle +float32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_config/SerialNumber.msg b/ros_kortex/kortex_driver/msg/generated/device_config/SerialNumber.msg new file mode 100644 index 0000000..ac55995 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_config/SerialNumber.msg @@ -0,0 +1,2 @@ + +string serial_number \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_manager/DeviceHandles.msg b/ros_kortex/kortex_driver/msg/generated/device_manager/DeviceHandles.msg new file mode 100644 index 0000000..7ce75ef --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_manager/DeviceHandles.msg @@ -0,0 +1,2 @@ + +DeviceHandle[] device_handle \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/device_manager/DeviceManager_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/device_manager/DeviceManager_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/device_manager/DeviceManager_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_config/GripperConfig_SafetyIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/gripper_config/GripperConfig_SafetyIdentifier.msg new file mode 100644 index 0000000..d16957a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_config/GripperConfig_SafetyIdentifier.msg @@ -0,0 +1,20 @@ + +uint32 UNSPECIFIED_ACTUATOR_SAFETY_IDENTIFIER = 0 + +uint32 MAXIMUM_MOTOR_CURRENT = 1 + +uint32 MAXIMUM_VOLTAGE = 2 + +uint32 MINIMUM_VOLTAGE = 4 + +uint32 MAXIMUM_MOTOR_TEMPERATURE = 8 + +uint32 MAXIMUM_CORE_TEMPERATURE = 16 + +uint32 NON_VOLATILE_MEMORY_CORRUPTED = 32 + +uint32 EMERGENCY_LINE_ASSERTED = 64 + +uint32 COMMUNICATION_TICK_LOST = 128 + +uint32 WATCHDOG_TRIGGERED = 256 diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_config/RobotiqGripperStatusFlags.msg b/ros_kortex/kortex_driver/msg/generated/gripper_config/RobotiqGripperStatusFlags.msg new file mode 100644 index 0000000..f4f1458 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_config/RobotiqGripperStatusFlags.msg @@ -0,0 +1,10 @@ + +uint32 UNSPECIFIED_ROBOTIQ_STATUS = 0 + +uint32 ROBOTIQ_STAT_INITIALIZED = 1 + +uint32 ROBOTIQ_STAT_OBJECT_DETECTED = 2 + +uint32 ROBOTIQ_STAT_POS_REACHED = 4 + +uint32 ROBOTIQ_STAT_STOPPED = 8 diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/CustomDataUnit.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/CustomDataUnit.msg new file mode 100644 index 0000000..7cfb944 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/CustomDataUnit.msg @@ -0,0 +1,17 @@ + +uint32 custom_data_0 +uint32 custom_data_1 +uint32 custom_data_2 +uint32 custom_data_3 +uint32 custom_data_4 +uint32 custom_data_5 +uint32 custom_data_6 +uint32 custom_data_7 +uint32 custom_data_8 +uint32 custom_data_9 +uint32 custom_data_10 +uint32 custom_data_11 +uint32 custom_data_12 +uint32 custom_data_13 +uint32 custom_data_14 +uint32 custom_data_15 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_Command.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_Command.msg new file mode 100644 index 0000000..ff2311a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_Command.msg @@ -0,0 +1,4 @@ + +GripperCyclic_MessageId command_id +uint32 flags +MotorCommand[] motor_cmd \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_CustomData.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_CustomData.msg new file mode 100644 index 0000000..0574768 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_CustomData.msg @@ -0,0 +1,4 @@ + +GripperCyclic_MessageId custom_data_id +CustomDataUnit gripper_custom_data +CustomDataUnit[] motor_custom_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_Feedback.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_Feedback.msg new file mode 100644 index 0000000..4089f06 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_Feedback.msg @@ -0,0 +1,8 @@ + +GripperCyclic_MessageId feedback_id +uint32 status_flags +uint32 fault_bank_a +uint32 fault_bank_b +uint32 warning_bank_a +uint32 warning_bank_b +MotorFeedback[] motor \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_MessageId.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_MessageId.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_MessageId.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/GripperCyclic_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/MotorCommand.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/MotorCommand.msg new file mode 100644 index 0000000..977af07 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/MotorCommand.msg @@ -0,0 +1,5 @@ + +uint32 motor_id +float32 position +float32 velocity +float32 force \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/MotorFeedback.msg b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/MotorFeedback.msg new file mode 100644 index 0000000..e83cf2e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/gripper_cyclic/MotorFeedback.msg @@ -0,0 +1,7 @@ + +uint32 motor_id +float32 position +float32 velocity +float32 current_motor +float32 voltage +float32 temperature_motor \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetConfiguration.msg new file mode 100644 index 0000000..9051405 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetConfiguration.msg @@ -0,0 +1,5 @@ + +uint32 device +bool enabled +uint32 speed +uint32 duplex \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDevice.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDevice.msg new file mode 100644 index 0000000..9c9173f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDevice.msg @@ -0,0 +1,4 @@ + +uint32 ETHERNET_DEVICE_UNSPECIFIED = 0 + +uint32 ETHERNET_DEVICE_EXPANSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDeviceIdentification.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDeviceIdentification.msg new file mode 100644 index 0000000..bf7c80e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDeviceIdentification.msg @@ -0,0 +1,2 @@ + +uint32 device \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDuplex.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDuplex.msg new file mode 100644 index 0000000..a3de1c5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetDuplex.msg @@ -0,0 +1,6 @@ + +uint32 ETHERNET_DUPLEX_UNSPECIFIED = 0 + +uint32 ETHERNET_DUPLEX_HALF = 1 + +uint32 ETHERNET_DUPLEX_FULL = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetSpeed.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetSpeed.msg new file mode 100644 index 0000000..fe5e4d7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/EthernetSpeed.msg @@ -0,0 +1,6 @@ + +uint32 ETHERNET_SPEED_UNSPECIFIED = 0 + +uint32 ETHERNET_SPEED_10M = 1 + +uint32 ETHERNET_SPEED_100M = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOConfiguration.msg new file mode 100644 index 0000000..578cc66 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOConfiguration.msg @@ -0,0 +1,5 @@ + +uint32 identifier +uint32 mode +uint32 pull +uint32 default_value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOIdentification.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOIdentification.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOIdentification.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOIdentifier.msg new file mode 100644 index 0000000..017720c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOIdentifier.msg @@ -0,0 +1,10 @@ + +uint32 GPIO_IDENTIFIER_UNSPECIFIED = 0 + +uint32 GPIO_IDENTIFIER_1 = 1 + +uint32 GPIO_IDENTIFIER_2 = 2 + +uint32 GPIO_IDENTIFIER_3 = 3 + +uint32 GPIO_IDENTIFIER_4 = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOMode.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOMode.msg new file mode 100644 index 0000000..42b05ff --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOMode.msg @@ -0,0 +1,8 @@ + +uint32 GPIO_MODE_UNSPECIFIED = 0 + +uint32 GPIO_MODE_INPUT_FLOATING = 1 + +uint32 GPIO_MODE_OUTPUT_PUSH_PULL = 2 + +uint32 GPIO_MODE_OUTPUT_OPEN_DRAIN = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOPull.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOPull.msg new file mode 100644 index 0000000..138ce14 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOPull.msg @@ -0,0 +1,8 @@ + +uint32 GPIO_PULL_UNSPECIFIED = 0 + +uint32 GPIO_PULL_NONE = 1 + +uint32 GPIO_PULL_UP = 2 + +uint32 GPIO_PULL_DOWN = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOState.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOState.msg new file mode 100644 index 0000000..ca65637 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOState.msg @@ -0,0 +1,3 @@ + +uint32 identifier +uint32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOValue.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOValue.msg new file mode 100644 index 0000000..ac352ad --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/GPIOValue.msg @@ -0,0 +1,6 @@ + +uint32 GPIO_VALUE_UNSPECIFIED = 0 + +uint32 GPIO_VALUE_LOW = 1 + +uint32 GPIO_VALUE_HIGH = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CConfiguration.msg new file mode 100644 index 0000000..c751857 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CConfiguration.msg @@ -0,0 +1,5 @@ + +uint32 device +bool enabled +uint32 mode +uint32 addressing \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CData.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CData.msg new file mode 100644 index 0000000..60dc377 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CData.msg @@ -0,0 +1,3 @@ + +uint8[] data +uint32 size \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDevice.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDevice.msg new file mode 100644 index 0000000..031e6cd --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDevice.msg @@ -0,0 +1,4 @@ + +uint32 I2C_DEVICE_UNSPECIFIED = 0 + +uint32 I2C_DEVICE_EXPANSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDeviceAddressing.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDeviceAddressing.msg new file mode 100644 index 0000000..7a509d0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDeviceAddressing.msg @@ -0,0 +1,6 @@ + +uint32 I2C_DEVICE_ADDRESSING_UNSPECIFIED = 0 + +uint32 I2C_DEVICE_ADDRESSING_7_BITS = 1 + +uint32 I2C_DEVICE_ADDRESSING_10_BITS = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDeviceIdentification.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDeviceIdentification.msg new file mode 100644 index 0000000..bf7c80e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CDeviceIdentification.msg @@ -0,0 +1,2 @@ + +uint32 device \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CMode.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CMode.msg new file mode 100644 index 0000000..a846ebe --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CMode.msg @@ -0,0 +1,8 @@ + +uint32 I2C_MODE_UNSPECIFIED = 0 + +uint32 I2C_MODE_STANDARD = 1 + +uint32 I2C_MODE_FAST = 2 + +uint32 I2C_MODE_FAST_PLUS = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CReadParameter.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CReadParameter.msg new file mode 100644 index 0000000..f8c3bce --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CReadParameter.msg @@ -0,0 +1,5 @@ + +uint32 device +uint32 device_address +uint32 size +uint32 timeout \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CReadRegisterParameter.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CReadRegisterParameter.msg new file mode 100644 index 0000000..81f8519 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CReadRegisterParameter.msg @@ -0,0 +1,7 @@ + +uint32 device +uint32 device_address +uint32 register_address +uint32 register_address_size +uint32 size +uint32 timeout \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CRegisterAddressSize.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CRegisterAddressSize.msg new file mode 100644 index 0000000..6a1d0f3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CRegisterAddressSize.msg @@ -0,0 +1,6 @@ + +uint32 I2C_REGISTER_ADDRESS_SIZE_UNSPECIFIED = 0 + +uint32 I2C_REGISTER_ADDRESS_SIZE_8_BITS = 1 + +uint32 I2C_REGISTER_ADDRESS_SIZE_16_BITS = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CWriteParameter.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CWriteParameter.msg new file mode 100644 index 0000000..65147e4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CWriteParameter.msg @@ -0,0 +1,5 @@ + +uint32 device +uint32 device_address +uint32 timeout +I2CData data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CWriteRegisterParameter.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CWriteRegisterParameter.msg new file mode 100644 index 0000000..26abaed --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/I2CWriteRegisterParameter.msg @@ -0,0 +1,7 @@ + +uint32 device +uint32 device_address +uint32 register_address +uint32 register_address_size +uint32 timeout +I2CData data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/InterconnectConfig_SafetyIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/InterconnectConfig_SafetyIdentifier.msg new file mode 100644 index 0000000..9dd7f85 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/InterconnectConfig_SafetyIdentifier.msg @@ -0,0 +1,20 @@ + +uint32 UNSPECIFIED_INTERCONNECT_SAFETY_IDENTIFIER = 0 + +uint32 MAXIMUM_MOTOR_CURRENT = 1 + +uint32 MAXIMUM_VOLTAGE = 2 + +uint32 MINIMUM_VOLTAGE = 4 + +uint32 MAXIMUM_MOTOR_TEMPERATURE = 8 + +uint32 MAXIMUM_CORE_TEMPERATURE = 16 + +uint32 NON_VOLATILE_MEMORY_CORRUPTED = 32 + +uint32 EMERGENCY_LINE_ASSERTED = 64 + +uint32 COMMUNICATION_TICK_LOST = 128 + +uint32 WATCHDOG_TRIGGERED = 256 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/InterconnectConfig_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/InterconnectConfig_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/InterconnectConfig_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_config/UARTPortId.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_config/UARTPortId.msg new file mode 100644 index 0000000..b9b3071 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_config/UARTPortId.msg @@ -0,0 +1,4 @@ + +uint32 UART_PORT_UNSPECIFIED = 0 + +uint32 UART_PORT_EXPANSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Command.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Command.msg new file mode 100644 index 0000000..3b6ebb5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Command.msg @@ -0,0 +1,4 @@ + +InterconnectCyclic_MessageId command_id +uint32 flags +InterconnectCyclic_Command_tool_command oneof_tool_command \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Command_tool_command.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Command_tool_command.msg new file mode 100644 index 0000000..e02acb6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Command_tool_command.msg @@ -0,0 +1,2 @@ + +GripperCyclic_Command[] gripper_command \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_CustomData.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_CustomData.msg new file mode 100644 index 0000000..f400bbb --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_CustomData.msg @@ -0,0 +1,19 @@ + +InterconnectCyclic_MessageId custom_data_id +uint32 custom_data_0 +uint32 custom_data_1 +uint32 custom_data_2 +uint32 custom_data_3 +uint32 custom_data_4 +uint32 custom_data_5 +uint32 custom_data_6 +uint32 custom_data_7 +uint32 custom_data_8 +uint32 custom_data_9 +uint32 custom_data_10 +uint32 custom_data_11 +uint32 custom_data_12 +uint32 custom_data_13 +uint32 custom_data_14 +uint32 custom_data_15 +InterconnectCyclic_CustomData_tool_customData oneof_tool_customData \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_CustomData_tool_customData.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_CustomData_tool_customData.msg new file mode 100644 index 0000000..4ed91af --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_CustomData_tool_customData.msg @@ -0,0 +1,2 @@ + +GripperCyclic_CustomData[] gripper_custom_data \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Feedback.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Feedback.msg new file mode 100644 index 0000000..f272bc4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Feedback.msg @@ -0,0 +1,17 @@ + +InterconnectCyclic_MessageId feedback_id +uint32 status_flags +uint32 jitter_comm +float32 imu_acceleration_x +float32 imu_acceleration_y +float32 imu_acceleration_z +float32 imu_angular_velocity_x +float32 imu_angular_velocity_y +float32 imu_angular_velocity_z +float32 voltage +float32 temperature_core +uint32 fault_bank_a +uint32 fault_bank_b +uint32 warning_bank_a +uint32 warning_bank_b +InterconnectCyclic_Feedback_tool_feedback oneof_tool_feedback \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Feedback_tool_feedback.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Feedback_tool_feedback.msg new file mode 100644 index 0000000..956ed28 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_Feedback_tool_feedback.msg @@ -0,0 +1,2 @@ + +GripperCyclic_Feedback[] gripper_feedback \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_MessageId.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_MessageId.msg new file mode 100644 index 0000000..9d1731b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_MessageId.msg @@ -0,0 +1,2 @@ + +uint32 identifier \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/interconnect_cyclic/InterconnectCyclic_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/ArmLaterality.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/ArmLaterality.msg new file mode 100644 index 0000000..b4d05a6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/ArmLaterality.msg @@ -0,0 +1,8 @@ + +uint32 ARM_LATERALITY_UNSPECIFIED = 0 + +uint32 ARM_LATERALITY_NOT_APPLICABLE = 1 + +uint32 ARM_LATERALITY_LEFT = 2 + +uint32 ARM_LATERALITY_RIGHT = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/BaseType.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/BaseType.msg new file mode 100644 index 0000000..6bbf9d0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/BaseType.msg @@ -0,0 +1,10 @@ + +uint32 BASE_TYPE_UNSPECIFIED = 0 + +uint32 BASE_TYPE_L53_QUICK_CONNECT = 1 + +uint32 BASE_TYPE_L53_FIXED = 2 + +uint32 BASE_TYPE_L31_FIXED = 3 + +uint32 BASE_TYPE_HDK_FIXED = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/CompleteProductConfiguration.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/CompleteProductConfiguration.msg new file mode 100644 index 0000000..9a1db22 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/CompleteProductConfiguration.msg @@ -0,0 +1,13 @@ + +string kin +uint32 model +CountryCode country_code +string assembly_plant +string model_year +uint32 degree_of_freedom +uint32 base_type +uint32 end_effector_type +uint32 vision_module_type +uint32 interface_module_type +uint32 arm_laterality +uint32 wrist_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/EndEffectorType.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/EndEffectorType.msg new file mode 100644 index 0000000..5cba4e9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/EndEffectorType.msg @@ -0,0 +1,10 @@ + +uint32 END_EFFECTOR_TYPE_UNSPECIFIED = 0 + +uint32 END_EFFECTOR_TYPE_NOT_INSTALLED = 1 + +uint32 END_EFFECTOR_TYPE_L31_GRIPPER_2F = 2 + +uint32 END_EFFECTOR_TYPE_ROBOTIQ_2F_85 = 3 + +uint32 END_EFFECTOR_TYPE_ROBOTIQ_2F_140 = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/InterfaceModuleType.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/InterfaceModuleType.msg new file mode 100644 index 0000000..b998368 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/InterfaceModuleType.msg @@ -0,0 +1,8 @@ + +uint32 INTERFACE_MODULE_TYPE_UNSPECIFIED = 0 + +uint32 INTERFACE_MODULE_TYPE_NOT_INSTALLED = 1 + +uint32 INTERFACE_MODULE_TYPE_L53 = 2 + +uint32 INTERFACE_MODULE_TYPE_L31 = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/ModelId.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/ModelId.msg new file mode 100644 index 0000000..568a4da --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/ModelId.msg @@ -0,0 +1,8 @@ + +uint32 MODEL_ID_UNSPECIFIED = 0 + +uint32 MODEL_ID_L53 = 1 + +uint32 MODEL_ID_L31 = 2 + +uint32 MODEL_ID_HDK = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/ProductConfigurationEndEffectorType.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/ProductConfigurationEndEffectorType.msg new file mode 100644 index 0000000..fc2a2b9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/ProductConfigurationEndEffectorType.msg @@ -0,0 +1,2 @@ + +uint32 end_effector_type \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/VisionModuleType.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/VisionModuleType.msg new file mode 100644 index 0000000..0bf5598 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/VisionModuleType.msg @@ -0,0 +1,10 @@ + +uint32 VISION_MODULE_TYPE_UNSPECIFIED = 0 + +uint32 VISION_MODULE_TYPE_NOT_INSTALLED = 1 + +uint32 VISION_MODULE_TYPE_L53_2D3D = 2 + +uint32 VISION_MODULE_TYPE_L53_2D = 3 + +uint32 VISION_MODULE_TYPE_EOD = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/product_configuration/WristType.msg b/ros_kortex/kortex_driver/msg/generated/product_configuration/WristType.msg new file mode 100644 index 0000000..27b86e0 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/product_configuration/WristType.msg @@ -0,0 +1,8 @@ + +uint32 WRIST_TYPE_UNSPECIFIED = 0 + +uint32 WRIST_TYPE_NOT_APPLICABLE = 1 + +uint32 WRIST_TYPE_SPHERICAL = 2 + +uint32 WRIST_TYPE_CURVED = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/BitRate.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/BitRate.msg new file mode 100644 index 0000000..4959606 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/BitRate.msg @@ -0,0 +1,10 @@ + +uint32 BITRATE_UNSPECIFIED = 0 + +uint32 BITRATE_10_MBPS = 1 + +uint32 BITRATE_15_MBPS = 2 + +uint32 BITRATE_20_MBPS = 3 + +uint32 BITRATE_25_MBPS = 4 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/DistortionCoefficients.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/DistortionCoefficients.msg new file mode 100644 index 0000000..2cc41e6 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/DistortionCoefficients.msg @@ -0,0 +1,6 @@ + +float32 k1 +float32 k2 +float32 k3 +float32 p1 +float32 p2 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/ExtrinsicParameters.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/ExtrinsicParameters.msg new file mode 100644 index 0000000..5d82663 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/ExtrinsicParameters.msg @@ -0,0 +1,3 @@ + +VisionConfig_RotationMatrix rotation +TranslationVector translation \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/FocusAction.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/FocusAction.msg new file mode 100644 index 0000000..f7d1b34 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/FocusAction.msg @@ -0,0 +1,14 @@ + +uint32 FOCUSACTION_UNSPECIFIED = 0 + +uint32 FOCUSACTION_START_CONTINUOUS_FOCUS = 1 + +uint32 FOCUSACTION_PAUSE_CONTINUOUS_FOCUS = 2 + +uint32 FOCUSACTION_FOCUS_NOW = 3 + +uint32 FOCUSACTION_DISABLE_FOCUS = 4 + +uint32 FOCUSACTION_SET_FOCUS_POINT = 5 + +uint32 FOCUSACTION_SET_MANUAL_FOCUS = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/FocusPoint.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/FocusPoint.msg new file mode 100644 index 0000000..1c99030 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/FocusPoint.msg @@ -0,0 +1,3 @@ + +uint32 x +uint32 y \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/FrameRate.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/FrameRate.msg new file mode 100644 index 0000000..1f3368d --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/FrameRate.msg @@ -0,0 +1,8 @@ + +uint32 FRAMERATE_UNSPECIFIED = 0 + +uint32 FRAMERATE_6_FPS = 1 + +uint32 FRAMERATE_15_FPS = 2 + +uint32 FRAMERATE_30_FPS = 3 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/IntrinsicParameters.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/IntrinsicParameters.msg new file mode 100644 index 0000000..d7ab6f9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/IntrinsicParameters.msg @@ -0,0 +1,8 @@ + +uint32 sensor +uint32 resolution +float32 principal_point_x +float32 principal_point_y +float32 focal_length_x +float32 focal_length_y +DistortionCoefficients distortion_coeffs \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/IntrinsicProfileIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/IntrinsicProfileIdentifier.msg new file mode 100644 index 0000000..7655bab --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/IntrinsicProfileIdentifier.msg @@ -0,0 +1,3 @@ + +uint32 sensor +uint32 resolution \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/ManualFocus.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/ManualFocus.msg new file mode 100644 index 0000000..129c5a3 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/ManualFocus.msg @@ -0,0 +1,2 @@ + +uint32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/Option.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/Option.msg new file mode 100644 index 0000000..aa509db --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/Option.msg @@ -0,0 +1,86 @@ + +uint32 OPTION_UNSPECIFIED = 0 + +uint32 OPTION_BACKLIGHT_COMPENSATION = 1 + +uint32 OPTION_BRIGHTNESS = 2 + +uint32 OPTION_CONTRAST = 3 + +uint32 OPTION_EXPOSURE = 4 + +uint32 OPTION_GAIN = 5 + +uint32 OPTION_GAMMA = 6 + +uint32 OPTION_HUE = 7 + +uint32 OPTION_SATURATION = 8 + +uint32 OPTION_SHARPNESS = 9 + +uint32 OPTION_WHITE_BALANCE = 10 + +uint32 OPTION_ENABLE_AUTO_EXPOSURE = 11 + +uint32 OPTION_ENABLE_AUTO_WHITE_BALANCE = 12 + +uint32 OPTION_VISUAL_PRESET = 13 + +uint32 OPTION_LASER_POWER = 14 + +uint32 OPTION_ACCURACY = 15 + +uint32 OPTION_MOTION_RANGE = 16 + +uint32 OPTION_FILTER_OPTION = 17 + +uint32 OPTION_CONFIDENCE_THRESHOLD = 18 + +uint32 OPTION_EMITTER_ENABLED = 19 + +uint32 OPTION_FRAMES_QUEUE_SIZE = 20 + +uint32 OPTION_TOTAL_FRAME_DROPS = 21 + +uint32 OPTION_AUTO_EXPOSURE_MODE = 22 + +uint32 OPTION_POWER_LINE_FREQUENCY = 23 + +uint32 OPTION_ASIC_TEMPERATURE = 24 + +uint32 OPTION_ERROR_POLLING_ENABLED = 25 + +uint32 OPTION_PROJECTOR_TEMPERATURE = 26 + +uint32 OPTION_OUTPUT_TRIGGER_ENABLED = 27 + +uint32 OPTION_MOTION_MODULE_TEMPERATURE = 28 + +uint32 OPTION_DEPTH_UNITS = 29 + +uint32 OPTION_ENABLE_MOTION_CORRECTION = 30 + +uint32 OPTION_AUTO_EXPOSURE_PRIORITY = 31 + +uint32 OPTION_COLOR_SCHEME = 32 + +uint32 OPTION_HISTOGRAM_EQUALIZATION_ENABLED = 33 + +uint32 OPTION_MIN_DISTANCE = 34 + +uint32 OPTION_MAX_DISTANCE = 35 + +uint32 OPTION_TEXTURE_SOURCE = 36 + +uint32 OPTION_FILTER_MAGNITUDE = 37 + +uint32 OPTION_FILTER_SMOOTH_ALPHA = 38 + +uint32 OPTION_FILTER_SMOOTH_DELTA = 39 + +uint32 OPTION_HOLES_FILL = 40 + +uint32 OPTION_STEREO_BASELINE = 41 + +uint32 OPTION_AUTO_EXPOSURE_CONVERGE_STEP = 42 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/OptionIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/OptionIdentifier.msg new file mode 100644 index 0000000..4d75db5 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/OptionIdentifier.msg @@ -0,0 +1,3 @@ + +uint32 sensor +uint32 option \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/OptionInformation.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/OptionInformation.msg new file mode 100644 index 0000000..c70843e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/OptionInformation.msg @@ -0,0 +1,9 @@ + +uint32 sensor +uint32 option +bool supported +bool read_only +float32 minimum +float32 maximum +float32 step +float32 default_value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/OptionValue.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/OptionValue.msg new file mode 100644 index 0000000..dd64fe7 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/OptionValue.msg @@ -0,0 +1,4 @@ + +uint32 sensor +uint32 option +float32 value \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/Resolution.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/Resolution.msg new file mode 100644 index 0000000..d0901c9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/Resolution.msg @@ -0,0 +1,14 @@ + +uint32 RESOLUTION_UNSPECIFIED = 0 + +uint32 RESOLUTION_320x240 = 1 + +uint32 RESOLUTION_424x240 = 2 + +uint32 RESOLUTION_480x270 = 3 + +uint32 RESOLUTION_640x480 = 4 + +uint32 RESOLUTION_1280x720 = 5 + +uint32 RESOLUTION_1920x1080 = 6 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/Sensor.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/Sensor.msg new file mode 100644 index 0000000..193ad1f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/Sensor.msg @@ -0,0 +1,6 @@ + +uint32 SENSOR_UNSPECIFIED = 0 + +uint32 SENSOR_COLOR = 1 + +uint32 SENSOR_DEPTH = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/SensorFocusAction.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorFocusAction.msg new file mode 100644 index 0000000..61ce96a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorFocusAction.msg @@ -0,0 +1,4 @@ + +uint32 sensor +uint32 focus_action +SensorFocusAction_action_parameters oneof_action_parameters \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/SensorFocusAction_action_parameters.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorFocusAction_action_parameters.msg new file mode 100644 index 0000000..d05778b --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorFocusAction_action_parameters.msg @@ -0,0 +1,3 @@ + +FocusPoint[] focus_point +ManualFocus[] manual_focus \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/SensorIdentifier.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorIdentifier.msg new file mode 100644 index 0000000..b2bb9d9 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorIdentifier.msg @@ -0,0 +1,2 @@ + +uint32 sensor \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/SensorSettings.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorSettings.msg new file mode 100644 index 0000000..e1d8c8a --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/SensorSettings.msg @@ -0,0 +1,5 @@ + +uint32 sensor +uint32 resolution +uint32 frame_rate +uint32 bit_rate \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/TranslationVector.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/TranslationVector.msg new file mode 100644 index 0000000..9d359dc --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/TranslationVector.msg @@ -0,0 +1,4 @@ + +float32 t_x +float32 t_y +float32 t_z \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_RotationMatrix.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_RotationMatrix.msg new file mode 100644 index 0000000..58c1b4e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_RotationMatrix.msg @@ -0,0 +1,4 @@ + +VisionConfig_RotationMatrixRow row1 +VisionConfig_RotationMatrixRow row2 +VisionConfig_RotationMatrixRow row3 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_RotationMatrixRow.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_RotationMatrixRow.msg new file mode 100644 index 0000000..a389a4e --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_RotationMatrixRow.msg @@ -0,0 +1,4 @@ + +float32 column1 +float32 column2 +float32 column3 \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_ServiceVersion.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_ServiceVersion.msg new file mode 100644 index 0000000..9665d1c --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionConfig_ServiceVersion.msg @@ -0,0 +1,4 @@ + +uint32 RESERVED_0 = 0 + +uint32 CURRENT_VERSION = 1 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/VisionEvent.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionEvent.msg new file mode 100644 index 0000000..65d7bd4 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionEvent.msg @@ -0,0 +1,6 @@ + +uint32 UNSPECIFIED_VISION_EVENT = 0 + +uint32 SENSOR_SETTINGS_CHANGED = 1 + +uint32 OPTION_VALUE_CHANGED = 2 diff --git a/ros_kortex/kortex_driver/msg/generated/vision_config/VisionNotification.msg b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionNotification.msg new file mode 100644 index 0000000..4b5085f --- /dev/null +++ b/ros_kortex/kortex_driver/msg/generated/vision_config/VisionNotification.msg @@ -0,0 +1,4 @@ + +uint32 event +uint32 sensor +uint32 option \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/non_generated/ApiOptions.msg b/ros_kortex/kortex_driver/msg/non_generated/ApiOptions.msg new file mode 100644 index 0000000..471fddd --- /dev/null +++ b/ros_kortex/kortex_driver/msg/non_generated/ApiOptions.msg @@ -0,0 +1 @@ +uint32 timeout_ms \ No newline at end of file diff --git a/ros_kortex/kortex_driver/msg/non_generated/KortexError.msg b/ros_kortex/kortex_driver/msg/non_generated/KortexError.msg new file mode 100644 index 0000000..4539261 --- /dev/null +++ b/ros_kortex/kortex_driver/msg/non_generated/KortexError.msg @@ -0,0 +1,3 @@ +string description +uint32 code +uint32 subCode \ No newline at end of file diff --git a/ros_kortex/kortex_driver/package.xml b/ros_kortex/kortex_driver/package.xml new file mode 100644 index 0000000..757f440 --- /dev/null +++ b/ros_kortex/kortex_driver/package.xml @@ -0,0 +1,37 @@ + + + kortex_driver + 2.2.2 + The package that acts as a robot's driver. Supports simulated and real Kortex robots. + + Hugo Lamontagne + Alexandre Vannobel + + + BSD + + catkin + roscpp + rospy + std_msgs + control_msgs + controller_manager_msgs + actionlib + moveit_ros_planning_interface + kdl_parser + roscpp + rospy + std_msgs + roscpp + rospy + std_msgs + message_generation + message_runtime + + + + + + + + diff --git a/ros_kortex/kortex_driver/protos/ActuatorConfig.proto b/ros_kortex/kortex_driver/protos/ActuatorConfig.proto new file mode 100644 index 0000000..4072cc2 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/ActuatorConfig.proto @@ -0,0 +1,438 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.ActuatorConfig; + +// Service to configure actuators +service ActuatorConfig {//@PROXY_ID=10 @ERROR=Kinova.Api.Error + + // Retrieves axis offsets for absolute and relative encoder + rpc GetAxisOffsets (Kinova.Api.Common.Empty) returns (AxisOffsets); //@RPC_ID=1 + + // Sets offsets for absolute and relative encoder + // Invoking this method shall invalidate arm calibration if one exists. This method is for kinova usage only. + rpc SetAxisOffsets (AxisPosition) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Reads torque calibration parameters (internal use only) + rpc ReadTorqueCalibration (Kinova.Api.Common.Empty) returns (TorqueCalibration); //@RPC_ID=3 + + // Writes torque calibration parameters (internal use only) + rpc WriteTorqueCalibration (TorqueCalibration) returns (Kinova.Api.Common.Empty); //@RPC_ID=4 + + // Sets zero torque calibration + rpc SetTorqueOffset (TorqueOffset) returns (Kinova.Api.Common.Empty); //@RPC_ID=5 + + // Retrieves actuator control mode + rpc GetControlMode (Kinova.Api.Common.Empty) returns (ControlModeInformation); //@RPC_ID=6 + + // Sets actuator control mode + rpc SetControlMode (ControlModeInformation) returns (Kinova.Api.Common.Empty); //@RPC_ID=7 + + // Retrieves activated control loop(s) + rpc GetActivatedControlLoop (Kinova.Api.Common.Empty) returns (ControlLoop); //@RPC_ID=8 + + // Sets activated control loop(s) + rpc SetActivatedControlLoop (ControlLoop) returns (Kinova.Api.Common.Empty); //@RPC_ID=9 + + // Retrieves motor drive FOC parameters (internal use only) + rpc GetVectorDriveParameters (Kinova.Api.Common.Empty) returns (VectorDriveParameters); //@RPC_ID=10 + + // Sets motor drive FOC parameters (internal use only) + rpc SetVectorDriveParameters (VectorDriveParameters) returns (Kinova.Api.Common.Empty); //@RPC_ID=11 + + // Retrieves encoder derivative parameters (internal use only) + rpc GetEncoderDerivativeParameters (Kinova.Api.Common.Empty) returns (EncoderDerivativeParameters); //@RPC_ID=12 + + // Sets encoder derivative parameters (internal use only) + rpc SetEncoderDerivativeParameters (EncoderDerivativeParameters) returns (Kinova.Api.Common.Empty); //@RPC_ID=13 + + // Retrieves control loop parameters + rpc GetControlLoopParameters (LoopSelection) returns (ControlLoopParameters); //@RPC_ID=14 + + // Sets control loop parameters + rpc SetControlLoopParameters (ControlLoopParameters) returns (Kinova.Api.Common.Empty); //@RPC_ID=15 + + // Starts frequency response test (internal use only) + rpc StartFrequencyResponse (FrequencyResponse) returns (Kinova.Api.Common.Empty); //@RPC_ID=16 + + // Stops frequency response test (internal use only) + rpc StopFrequencyResponse (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty); //@RPC_ID=17 + + // Starts step response test (internal use only) + rpc StartStepResponse (StepResponse) returns (Kinova.Api.Common.Empty); //@RPC_ID=18 + + // Stops step response test (internal use only) + rpc StopStepResponse (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty); //@RPC_ID=19 + + // Starts ramp response test (internal use only) + rpc StartRampResponse (RampResponse) returns (Kinova.Api.Common.Empty); //@RPC_ID=20 + + // Stops ramp response test (internal use only) + rpc StopRampResponse (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty); //@RPC_ID=21 + + // Selects custom data + rpc SelectCustomData (CustomDataSelection) returns (Kinova.Api.Common.Empty); //@RPC_ID=22 + + // Retrieves selected custom data + rpc GetSelectedCustomData (Kinova.Api.Common.Empty) returns (CustomDataSelection); //@RPC_ID=23 + + // Sets command mode (config versus cyclic) + rpc SetCommandMode (CommandModeInformation) returns (Kinova.Api.Common.Empty); //@RPC_ID=24 + + // Clears all error(s) and warning(s) (bank A and B) + rpc ClearFaults (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty); //@RPC_ID=25 + + // Enables or disables servoing + rpc SetServoing (Servoing) returns (Kinova.Api.Common.Empty); //@RPC_ID=26 + + // Moves the actuator to the desired position + rpc MoveToPosition (PositionCommand) returns (Kinova.Api.Common.Empty); //@RPC_ID=27 + + // Retrieves command mode (config versus cyclic) + rpc GetCommandMode (Kinova.Api.Common.Empty) returns (CommandModeInformation); //@RPC_ID=28 + + // Retrieves servoing state + rpc GetServoing (Kinova.Api.Common.Empty) returns (Servoing); //@RPC_ID=29 + + // Retrieves torque offset calibration + rpc GetTorqueOffset (Kinova.Api.Common.Empty) returns (TorqueOffset); //@RPC_ID=30 + + // Sets cogging feedforward mode + rpc SetCoggingFeedforwardMode (CoggingFeedforwardModeInformation) returns (Kinova.Api.Common.Empty); //@RPC_ID=31 + + // Retrieves cogging feedforward mode + rpc GetCoggingFeedforwardMode (Kinova.Api.Common.Empty) returns (CoggingFeedforwardModeInformation); //@RPC_ID=32 +} + +// Identifies ActuatorConfig service current version +enum ServiceVersion +{ + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Admissible limit types +enum SafetyLimitType +{ + MAXIMAL_LIMIT = 0; // Maximal limit + MINIMAL_LIMIT = 1; // Minimal limit +} + +// Admissible control modes +enum ControlMode +{ + NONE = 0; // None + POSITION = 1; // Position mode + VELOCITY = 2; // Velocity mode + TORQUE = 3; // Torque mode + CURRENT = 4; // Current mode + CUSTOM = 5; // Custom mode +} + +// Admissible command modes +enum CommandMode +{ + CYCLIC = 0; // Cyclic data only + ASYNC_CYCLIC_FLAGS = 1; // Not supported + ASYNC = 2; // Config messages only + CYCLIC_JITTERCOMPENSATED_POSITION = 3; // Smoothing using only position inputs + CYCLIC_JITTERCOMPENSATED_VELOCITY = 4; // Smoothing using position and velocity inputs + CYCLIC_JITTERCOMPENSATED_ACCELERATION = 5; // Smoothing using position, velocity and acceleration inputs (not supported) +} + +// Admissible control loop selections +enum ControlLoopSelection +{ + RESERVED = 0; // 0x0 - Reserved (internal use only) + JOINT_POSITION = 1; // 0x1 - Joint position control (if available) + MOTOR_POSITION = 2; // 0x2 - Motor position control + JOINT_VELOCITY = 4; // 0x4 - Joint velocity control (if available) + MOTOR_VELOCITY = 8; // 0x8 - Motor velocity control + JOINT_TORQUE = 16; // 0x10 - Joint torque control + MOTOR_CURRENT = 32; // 0x20 - Motor current control +} + +// Admissable cogging feedforward modes +enum CoggingFeedforwardMode +{ + FEEDFORWARD_OFF = 0; // No cogging compensation + FEEDFORWARD_ADAPTIVE = 1; // Cogging compensation with adaptive parameters + FEEDFORWARD_CALIBRATED = 2; // Cogging compensation with calibrated parameters +} + +// Axis position +message AxisPosition +{ + float position = 1; // Axis position (meters) +} + +// Axis offsets +message AxisOffsets +{ + float absolute_offset = 1; // Absolute offset value (meters) + float relative_offset = 2; // Relative offset value (meters) +} + +// Torque calibration settings +message TorqueCalibration +{ + float global_gain = 1; // Global gain value + float global_offset = 2; // Global offset value + repeated float gain = 3; // Gain (index 0 to 3) + repeated float offset = 4; // Offset (index 0 to 3) +} + +// Defines torque offset +message TorqueOffset +{ + float torque_offset = 1; // Torque offset value +} + +// Control mode information +message ControlModeInformation +{ + ControlMode control_mode = 1; // Control mode +} + +// Control loop +message ControlLoop +{ + fixed32 control_loop = 1; // Use ControlLoopSelection enum values to form bitmask +} + +// Defines the loop selection +message LoopSelection +{ + ControlLoopSelection loop_selection = 1; // ControlLoopSelection enum +} + +// Field-oriented control PI controller gain values +message VectorDriveParameters +{ + float kpq = 1; // Quadrature axis current proportional gain + float kiq = 2; // Quadrature axis current integral gain + float kpd = 3; // Direct axis current proportional gain + float kid = 4; // Direct axis current integral gain +} + +// Variable window derivative parameters +message EncoderDerivativeParameters +{ + uint32 max_window_width = 1; // Maximum window width + float min_angle = 2; // Minimum angle for derivative (degrees) +} + +// Control loop parameters (discrete transfer function) +message ControlLoopParameters +{ + ControlLoopSelection loop_selection = 1; // ControlLoopSelection enum + float error_saturation = 2; // Error saturation value + float output_saturation = 3; // Output saturation value + repeated float kAz = 4; // KAz (index 0 to 4): denominator gains A1 to A5 + repeated float kBz = 5; // KBz (index 0 to 5): numerator gains B0 to B5 + float error_dead_band = 6; // Error dead band value +} + +// Frequency response +message FrequencyResponse +{ + ControlLoopSelection loop_selection = 1; // ControlLoopSelection enum + float min_frequency = 2; // Minimum frequency value + float max_frequency = 3; // Maximum frequency value + float amplitude = 4; // Amplitude value + float duration = 5; // Duration (in seconds) +} + +// Step response +message StepResponse +{ + ControlLoopSelection loop_selection = 1; // ControlLoopSelection enum + float amplitude = 2; // Amplitude value + float step_delay = 3; // Step delay value + float duration = 4; // Duration (in seconds) +} + +// Ramp response +message RampResponse +{ + ControlLoopSelection loop_selection = 1; // ControlLoopSelection enum + float slope = 2; // Slope value + float ramp_delay = 3; // Ramp delay value + float duration = 4; // Duration (in seconds) +} + +// Selected custom data channels content +message CustomDataSelection +{ + repeated CustomDataIndex channel = 1; // 16 channels maximum +} + +// Command mode +message CommandModeInformation +{ + CommandMode command_mode = 1; // Command mode +} + +// Enables/disables servoing +message Servoing +{ + bool enabled = 1; // Servoing enabled +} + +// Angular position command for an actuator +message PositionCommand +{ + float position = 1; // Position value (degrees) + float velocity = 2; // Velocity value (degrees per second) + float acceleration = 3; // Acceleration value (degrees per second^squared) +} + +// Cogging feedforward mode +message CoggingFeedforwardModeInformation +{ + CoggingFeedforwardMode cogging_feedforward_mode = 1; // Cogging feedforward mode +} + +// Admissible bank A actuator safeties +enum SafetyIdentifierBankA { + UNSPECIFIED_ACTUATOR_SAFETY_IDENTIFIER_BANK_A = 0; // 0x0 - Unspecified actuator safety + FOLLOWING_ERROR = 1; // 0x1 - Following error + MAXIMUM_VELOCITY = 2; // 0x2 - Maximum velocity + JOINT_LIMIT_HIGH = 4; // 0x4 - Joint position limit high + JOINT_LIMIT_LOW = 8; // 0x8 - Joint position limit low + STRAIN_GAUGE_MISMATCH = 16; // 0x10 - Strain gauge mismatch + MAXIMUM_TORQUE = 32; // 0x20 - Maximum torque + UNRELIABLE_ABSOLUTE_POSITION = 64; // 0x40 - Unreliable absolute position + MAGNETIC_POSITION = 128; // 0x80 - Magnetic position + HALL_POSITION = 256; // 0x100 - Hall position + HALL_SEQUENCE = 512; // 0x200 - Hall sequence + INPUT_ENCODER_HALL_MISMATCH = 1024; // 0x400 - Input encoder Hall mismatch + INPUT_ENCODER_INDEX_MISMATCH = 2048; // 0x800 - Input encoder index mismatch + INPUT_ENCODER_MAGNETIC_MISMATCH = 4096; // 0x1000 - Input encoder magnetic mismatch + MAXIMUM_MOTOR_CURRENT = 8192; // 0x2000 - Maximum motor current + MOTOR_CURRENT_MISMATCH = 16384; // 0x4000 - Motor current mismatch + MAXIMUM_VOLTAGE = 32768; // 0x8000 - Maximum voltage + MINIMUM_VOLTAGE = 65536; // 0x10000 - Minimum voltage + MAXIMUM_MOTOR_TEMPERATURE = 131072; // 0x20000 - Maximum motor temperature + MAXIMUM_CORE_TEMPERATURE = 262144; // 0x40000 - Maximum core temperature + NON_VOLATILE_MEMORY_CORRUPTED = 524288; // 0x80000 - Non-volatile memory corrupted + MOTOR_DRIVER_FAULT = 1048576; // 0x100000 - Motor driver fault + EMERGENCY_LINE_ASSERTED = 2097152; // 0x200000 - Emergency line asserted + COMMUNICATION_TICK_LOST = 4194304; // 0x400000 - Communication tick lost + WATCHDOG_TRIGGERED = 8388608; // 0x800000 - Watchdog triggered + UNRELIABLE_CAPACITIVE_SENSOR = 16777216; // 0x1000000 - Capacitive sensor is unreliable + UNEXPECTED_GEAR_RATIO = 33554432; // 0x2000000 - Incorrect gear ratio for detected configuration + HALL_MAGNETIC_MISMATCH = 67108864; // 0x4000000 - Position mismatch between hall and magnetic sensors +} + +// Custom data options +enum CustomDataIndex { + NO_CUSTOM_DATA_SELECTED = 0; // No custom data selected + UINT32_TEST_RAMP = 1; // Incremental value used for test and validation + UINT32_MOTOR_ENCODER_RAW = 2; // Rotor optical encoder incremental value (raw) + UINT32_JOINT_ENCODER_RAW = 3; // Joint optical encoder incremental value (raw) + FLOAT_TEMPERATURE_PHASE_0 = 4; // Motor phase 0 temperature (degrees Celsius) + FLOAT_TEMPERATURE_PHASE_1 = 5; // Motor phase 1 temperature (degrees Celsius) + FLOAT_TEMPERATURE_PHASE_2 = 6; // Motor phase 2 temperature (degrees Celsius) + INT32_TORQUE_SENSOR_RAW_0 = 7; // Individual torque sensor strain gauge 0 ADC value (raw) + INT32_TORQUE_SENSOR_RAW_1 = 8; // Individual torque sensor strain gauge 1 ADC value (raw) + INT32_TORQUE_SENSOR_RAW_2 = 9; // Individual torque sensor strain gauge 2 ADC value (raw) + INT32_TORQUE_SENSOR_RAW_3 = 10; // Individual torque sensor strain gauge 3 ADC value (raw) + FLOAT_TORQUE_SENSOR_0 = 11; // Individual torque sensor strain gauge 0 converted value (Newton-meters) + FLOAT_TORQUE_SENSOR_1 = 12; // Individual torque sensor strain gauge 1 converted value (Newton-meters) + FLOAT_TORQUE_SENSOR_2 = 13; // Individual torque sensor strain gauge 2 converted value (Newton-meters) + FLOAT_TORQUE_SENSOR_3 = 14; // Individual torque sensor strain gauge 3 converted value (Newton-meters) + UINT32_MOTOR_ENCODER_RAW_LATCH_ON_INDEX_RISING = 15; // Rotor optical encoder incremental value at last index signal rising edge (raw) + UINT32_JOINT_ENCODER_RAW_LATCH_ON_INDEX_RISING = 16; // Joint optical encoder incremental value at last index signal rising edge (raw) + UINT32_ABSOLUTE_POSITION_SENSOR_RAW = 17; // Absolute position sensor integer value (raw) + FLOAT_ABSOLUTE_POSITION_SENSOR = 18; // Absolute position sensor converted value (degrees) + FLOAT_CONTROL_POSITION_JOINT_REQUESTED = 19; // Last axis position command received via Ethernet + UINT32_JIG_FLAGS = 20; // Jig status flags (internal use) + UINT32_TICK_MOTOR_CONTROL = 21; // Rotor optical encoder incremental value corrected for counter overflow (raw) + UINT32_TICK_JOINT_CONTROL = 22; // Joint optical encoder incremental value corrected for counter overflow (raw) + UINT32_INDEX_TICK_MOTOR_CONTROL = 23; // Rotor optical encoder incremental value corrected for counter overflow at last index signal rising edge (raw) + UINT32_INDEX_TICK_JOINT_CONTROL = 24; // Joint optical encoder incremental value corrected for counter overflow at last index signal rising edge (raw) + FLOAT_ACCELERATION_X = 25; // x-axis acceleration (meters per second squared) + FLOAT_ACCELERATION_Y = 26; // y-axis acceleration (meters per second squared) + FLOAT_ACCELERATION_Z = 27; // z-axis acceleration (meters per second squared) + FLOAT_ANGULAR_RATE_X = 28; // x-axis angular velocity (degrees per second) + FLOAT_ANGULAR_RATE_Y = 29; // y-axis angular velocity (degrees per second) + FLOAT_ANGULAR_RATE_Z = 30; // z-axis angular velocity (degrees per second) + FLOAT_POSITION_MOTOR_CMD = 31; // Axis position command sent to motor position control loop (degrees) + FLOAT_VELOCITY_MOTOR_CMD = 32; // Axis velocity command sent to motor velocity control loop (degrees per second) + FLOAT_POSITION_MOTOR = 33; // Actuator position measured by rotor optical encoder (degrees) + FLOAT_VELOCITY_MOTOR = 34; // Actuator angular velocity measured by rotor optical encoder (degrees per second) + UINT32_COMMUNICATIONS_JITTER = 35; // Jitter from the communication (microseconds) + FLOAT_TORQUE_AVERAGE = 36; // Actuator torque (Newton-meters) + FLOAT_CURRENT_MOTOR = 37; // Motor current (Amperes) + FLOAT_VOLTAGE_DIGITAL = 38; // Main board voltage (Volts) + FLOAT_TEMPERATURE_MOTOR_CELSIUS = 39; // Motor temperature (maximum of the three (3) phase temperatures) (degrees Celsius) + FLOAT_TEMPERATURE_CORE_CELSIUS = 40; // Microcontroller temperature (degrees Celsius) + UINT32_FAULT_A = 41; // Bank A faults (see ActuatorConfig.SafetyIdentifier) + UINT32_FAULT_B = 42; // Bank B faults (see ActuatorConfig.SafetyIdentifier) + UINT32_WARNING_A = 43; // Bank A warnings (see ActuatorConfig.SafetyIdentifier) + UINT32_WARNING_B = 44; // Bank B warnings (see ActuatorConfig.SafetyIdentifier) + FLOAT_POSITION_FROM_HALLS = 45; // Actuator position measured by motor hall sensors (degrees) + FLOAT_PHASE_CURRENT_0 = 46; // Motor phase 0 current (Amperes) + FLOAT_PHASE_CURRENT_1 = 47; // Motor phase 1 current (Amperes) + FLOAT_PHASE_CURRENT_2 = 48; // Motor phase 2 current (Amperes) + FLOAT_PHASE_PWM_0 = 49; // Pulse width modulation duty cycle applied to motor phase 0 (percentage) + FLOAT_PHASE_PWM_1 = 50; // Pulse width modulation duty cycle applied to motor phase 1 (percentage) + FLOAT_PHASE_PWM_2 = 51; // Pulse width modulation duty cycle applied to motor phase 2 (percentage) + FLOAT_MOTOR_ELECTRICAL_ANGLE = 52; // Motor electrical angle (degrees) + FLOAT_CURRENT_MOTOR_CMD = 53; // Motor current command sent to motor drive (Amperes) + FLOAT_TORQUE_JOINT_CMD = 54; // Axis torque command sent to joint torque control loop (Newton-meters) + FLOAT_POSITION_UNWRAPPED = 55; // Actuator position unwrapped (degrees) + UINT32_HALL_SENSOR_0 = 56; // Hall sensor 0 value (raw) + UINT32_HALL_SENSOR_1 = 57; // Hall sensor 1 value (raw) + UINT32_HALL_SENSOR_2 = 58; // Hall sensor 2 value (raw) + INT32_HALL_SENSOR_SCALED_0 = 59; // Hall sensor 0 scaled value (raw) + INT32_HALL_SENSOR_SCALED_1 = 60; // Hall sensor 1 scaled value (raw) + INT32_HALL_SENSOR_SCALED_2 = 61; // Hall sensor 2 scaled value (raw) + FLOAT_COGGING_COEFFICIENT_A_0 = 62; // Cogging torque cancellation coefficient A0 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_1 = 63; // Cogging torque cancellation coefficient A1 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_2 = 64; // Cogging torque cancellation coefficient A2 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_3 = 65; // Cogging torque cancellation coefficient A3 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_4 = 66; // Cogging torque cancellation coefficient A4 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_5 = 67; // Cogging torque cancellation coefficient A5 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_6 = 68; // Cogging torque cancellation coefficient A6 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_7 = 69; // Cogging torque cancellation coefficient A7 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_8 = 70; // Cogging torque cancellation coefficient A8 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_9 = 71; // Cogging torque cancellation coefficient A9 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_10 = 72; // Cogging torque cancellation coefficient A10 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_11 = 73; // Cogging torque cancellation coefficient A11 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_12 = 74; // Cogging torque cancellation coefficient A12 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_13 = 75; // Cogging torque cancellation coefficient A13 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_14 = 76; // Cogging torque cancellation coefficient A14 (Amperes) + FLOAT_COGGING_COEFFICIENT_A_15 = 77; // Cogging torque cancellation coefficient A15 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_0 = 78; // Cogging torque cancellation coefficient B0 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_1 = 79; // Cogging torque cancellation coefficient B1 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_2 = 80; // Cogging torque cancellation coefficient B2 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_3 = 81; // Cogging torque cancellation coefficient B3 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_4 = 82; // Cogging torque cancellation coefficient B4 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_5 = 83; // Cogging torque cancellation coefficient B5 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_6 = 84; // Cogging torque cancellation coefficient B6 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_7 = 85; // Cogging torque cancellation coefficient B7 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_8 = 86; // Cogging torque cancellation coefficient B8 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_9 = 87; // Cogging torque cancellation coefficient B9 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_10 = 88; // Cogging torque cancellation coefficient B10 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_11 = 89; // Cogging torque cancellation coefficient B11 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_12 = 90; // Cogging torque cancellation coefficient B12 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_13 = 91; // Cogging torque cancellation coefficient B13 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_14 = 92; // Cogging torque cancellation coefficient B14 (Amperes) + FLOAT_COGGING_COEFFICIENT_B_15 = 93; // Cogging torque cancellation coefficient B15 (Amperes) + FLOAT_CURRENT_COGGING_FEEDFORWARD = 94; // Commanded cogging cancellation feedforward current sent to motor drive (Amperes) +} diff --git a/ros_kortex/kortex_driver/protos/ActuatorCyclic.proto b/ros_kortex/kortex_driver/protos/ActuatorCyclic.proto new file mode 100644 index 0000000..1e89083 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/ActuatorCyclic.proto @@ -0,0 +1,137 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.ActuatorCyclic; + +// Service to exchange cyclic data with an actuator +service ActuatorCyclic {//@PROXY_ID=11 @ERROR=Kinova.Api.Error + + // Sends a command to a single actuator and receives feedback on status of that actuator + rpc Refresh (Command) returns (Feedback); //@RPC_ID=1 + + // Sends a command to a single actuator without feedback + rpc RefreshCommand (Command) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Obtains feedback from a single actuator + rpc RefreshFeedback (MessageId) returns (Feedback); //@RPC_ID=3 + + // Obtains custom data from a single actuator + rpc RefreshCustomData (MessageId) returns (CustomData); //@RPC_ID=4 +} + +// Identifies ActuatorCyclic service current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Identifies actuator commands +enum CommandFlags { + NO_COMMAND = 0; // 0x0 Default value + SERVO_ENABLE = 1; // 0x1 Servoing mode is enabled + BRAKE_DISABLE = 2; // 0x2 Brake normally applied, 1 disables brake + CLEAR_MAJOR_FAULT = 4; // 0x4 Clear the major fault flag (See StatusFlags) + CLEAR_MINOR_FAULT = 8; // 0x8 Clear the minor fault flag (See StatusFlags) + PROTECTIVE_STOP = 16; // 0x10 Protective stop has been activated + FORCE_BRAKE_RELEASE = 32; // 0x20 Force a brake release + IGNORE = 64; // 0x40 ignore the other CommandFlag bits + LOW_GAINS = 128; // 0x80 Use a set of specific gain value used by the joint admittance mode + LED_0 = 256; // 0x100 Activate LED 0 (interface module buttons 0) + LED_1 = 512; // 0x200 Activate LED 1 (interface module buttons 1) +} + +// Identifies actuator status +enum StatusFlags { + UNKNOWN_STATUS = 0; // 0x0 Unknown status + STABILIZED = 16; // 0x10 Actuator is in a stable state + MOTOR_INDEXED = 32; // 0x20 Position sensor is indexed + MOTOR_INDEXING = 64; // 0x40 Position sensor is indexing + JOINT_INDEXED = 128; // 0x80 Reserved + JOINT_INDEXING = 256; // 0x100 Reserved + HIGH_PRECISION = 512; // 0x200 Reserved + BRAKING = 1024; // 0x400 The actuator is braking + SERVOING = 2048; // 0x800 The actuator is in servoing mode + MAJOR_FAULT = 4096; // 0x1000 A major fault has occurred + MINOR_FAULT = 8192; // 0x2000 A minor fault has occurred + CALIBRATED_TORQUE = 16384; // 0x4000 The torque sensor is calibrated + CALIBRATED_MAG_SENSOR = 32768; // 0x8000 The magnetic sensor is calibrated + CALIBRATED_ZERO = 65536; // 0x10000 The zero position calibration has been performed + GPIO_0 = 131072; // 0x20000 Reserved + GPIO_1 = 262144; // 0x40000 Reserved + CS_QUASI_STATIC_CONTACT = 524288; // 0x80000 Reserved + CS_TRANSIENT_CONTACT = 1048576; // 0x100000 Reserved + VFD_HALL_SYNC = 2097152; // 0x200000 Reserved + VFD_INDEXED = 4194304; // 0x400000 Reserved + DRIVE_BOARD_READY = 8388608; // 0x800000 Reserved + CALIBRATED_CURRENT = 16777216; // 0x1000000 Current sensor is calibrated + CALIBRATED_MOTOR = 33554432; // 0x2000000 Motor is calibrated + SW0_ACTIVE = 67108864; // 0x4000000 Status of interface module buttons 0 + SW1_ACTIVE = 134217728; // 0x8000000 Status of interface module buttons 1 +} + +// Provides a message identifier +message MessageId { + fixed32 identifier = 1; // Message ID (first 2 bytes : device ID, last 2 bytes : sequence number). By default, set to zero +} + +// Defines an actuator command +message Command { + MessageId command_id = 1; // MessageId + fixed32 flags = 2; // Command flags (see enum CommandFlags) + float position = 3; // Desired position of the actuator (degrees) + float velocity = 4; // Desired velocity of the actuator (degrees per second) + float torque_joint = 5; // Desired torque of the actuator (Newton-meters) + float current_motor = 6; // Desired current of the motor (Amperes) +} + +// Status feedback provided by an actuator +message Feedback { + MessageId feedback_id = 1; // MessageId + fixed32 status_flags = 2; // Status flags (see enum StatusFlags for the rest) + fixed32 jitter_comm = 3; // Jitter from the communication in μs + float position = 4; // Position of the actuator (degrees) + float velocity = 5; // Angular velocity of the actuator (degrees per second) + float torque = 6; // Torque of the actuator (Newton meter) + float current_motor = 7; // Current of the motor (Amperes) + float voltage = 8; // Voltage of the main board in (Volt) + float temperature_motor = 9; // Motor temperature (average of the three (3) temperatures (degrees Celsius)) + float temperature_core = 10; // Microcontroller temperature in (degrees Celsius) + fixed32 fault_bank_a = 11; // Bank A Fault (see ActuatorConfig.SafetyIdentifier) + fixed32 fault_bank_b = 12; // Bank B Fault (see ActuatorConfig.SafetyIdentifier) + fixed32 warning_bank_a = 13; // Bank A Warning (see ActuatorConfig.SafetyIdentifier) + fixed32 warning_bank_b = 14; // Bank B Warning (see ActuatorConfig.SafetyIdentifier) +} + +// Custom development data, content varies according to debug needs +message CustomData { + MessageId custom_data_id = 1; // MessageId + fixed32 custom_data_0 = 2; // Custom data word 0 + fixed32 custom_data_1 = 3; // Custom data word 1 + fixed32 custom_data_2 = 4; // Custom data word 2 + fixed32 custom_data_3 = 5; // Custom data word 3 + fixed32 custom_data_4 = 6; // Custom data word 4 + fixed32 custom_data_5 = 7; // Custom data word 5 + fixed32 custom_data_6 = 8; // Custom data word 6 + fixed32 custom_data_7 = 9; // Custom data word 7 + fixed32 custom_data_8 = 10; // Custom data word 8 + fixed32 custom_data_9 = 11; // Custom data word 9 + fixed32 custom_data_10 = 12; // Custom data word 10 + fixed32 custom_data_11 = 13; // Custom data word 11 + fixed32 custom_data_12 = 14; // Custom data word 12 + fixed32 custom_data_13 = 15; // Custom data word 13 + fixed32 custom_data_14 = 16; // Custom data word 14 + fixed32 custom_data_15 = 17; // Custom data word 15 +} diff --git a/ros_kortex/kortex_driver/protos/Base.proto b/ros_kortex/kortex_driver/protos/Base.proto new file mode 100644 index 0000000..87a0517 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/Base.proto @@ -0,0 +1,2082 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; +import public "Errors.proto"; +import public "ProductConfiguration.proto"; + +package Kinova.Api.Base; + +/* + * Base service. Broadly useful service. + * Provides functions for configuring a range of base-related functionalities and for enabling high-level control for the robot. + */ +service Base {//@PROXY_ID=2 @ERROR=Kinova.Api.Error + + // Creates a user profile and returns a handle to the profile + rpc CreateUserProfile (FullUserProfile) returns (Kinova.Api.Common.UserProfileHandle);//@RPC_ID=1 + + // Updates an existing user profile + rpc UpdateUserProfile (UserProfile) returns (Kinova.Api.Common.Empty);//@RPC_ID=2 + + // Retrieves an existing user profile + rpc ReadUserProfile (Kinova.Api.Common.UserProfileHandle) returns (UserProfile);//@RPC_ID=3 + + // Deletes an existing user profile + rpc DeleteUserProfile (Kinova.Api.Common.UserProfileHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=4 + + // Retrieves all user profiles + rpc ReadAllUserProfiles (Kinova.Api.Common.Empty) returns (UserProfileList);//@RPC_ID=5 + + // Retrieves the list of all user profile handles + rpc ReadAllUsers (Kinova.Api.Common.Empty) returns (UserList);//@RPC_ID=6 + + // Changes the password of an existing user + rpc ChangePassword (PasswordChange) returns (Kinova.Api.Common.Empty);//@RPC_ID=7 + + // Creates a new sequence and returns a handle to the sequence + rpc CreateSequence (Sequence) returns (SequenceHandle);//@RPC_ID=8 + + // Updates an existing sequence + rpc UpdateSequence (Sequence) returns (Kinova.Api.Common.Empty);//@RPC_ID=9 + + // Retrieves an existing sequence + rpc ReadSequence (SequenceHandle) returns (Sequence);//@RPC_ID=10 + + // Deletes an existing sequence + rpc DeleteSequence (SequenceHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=11 + + // Retrieves the list of all existing sequences + rpc ReadAllSequences (Kinova.Api.Common.Empty) returns (SequenceList);//@RPC_ID=12 + + // DeleteSequenceTask is still RPC_ID=13, but is at position 221 in this file + + // DeleteAllSequenceTasks is still RPC_ID=14, but is at position 222 in this file + + // Plays an existing sequence + rpc PlaySequence (SequenceHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=15 + + // Plays an existing sequence with options + rpc PlayAdvancedSequence (AdvancedSequenceHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=16 + + // Stops execution of currently playing sequence + rpc StopSequence (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=17 + + // Pauses execution of currently playing sequence + rpc PauseSequence (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=18 + + // Resumes execution of currently paused sequence + rpc ResumeSequence (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=19 + + // Creates a new protection zone and returns a handle to the protection zone + rpc CreateProtectionZone (ProtectionZone) returns (ProtectionZoneHandle);//@RPC_ID=20 + + // Updates an existing protection zone + rpc UpdateProtectionZone (ProtectionZone) returns (Kinova.Api.Common.Empty);//@RPC_ID=21 + + // Retrieves an existing protection zone + rpc ReadProtectionZone (ProtectionZoneHandle) returns (ProtectionZone);//@RPC_ID=22 + + // Deletes an existing protection zone + rpc DeleteProtectionZone (ProtectionZoneHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=23 + + // Retrieves a list of all protection zones + rpc ReadAllProtectionZones (Kinova.Api.Common.Empty) returns (ProtectionZoneList);//@RPC_ID=24 + + // Creates a new mapping + rpc CreateMapping (Mapping) returns (MappingHandle);//@RPC_ID=26 + + // Retrieves an existing mapping + rpc ReadMapping (MappingHandle) returns (Mapping);//@RPC_ID=27 + + // Updates an existing mapping + rpc UpdateMapping (Mapping) returns (Kinova.Api.Common.Empty);//@RPC_ID=28 + + // Deletes an existing mapping + rpc DeleteMapping (MappingHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=29 + + // Retrieves a list of all mappings + rpc ReadAllMappings (Kinova.Api.Common.Empty) returns (MappingList);//@RPC_ID=30 + + // Creates a new map + rpc CreateMap (Map) returns (MapHandle);//@RPC_ID=36 + + // Retrieves an existing map + rpc ReadMap (MapHandle) returns (Map);//@RPC_ID=37 + + // Updates an existing map + rpc UpdateMap (Map) returns (Kinova.Api.Common.Empty);//@RPC_ID=38 + + // Deletes an existing map + rpc DeleteMap (MapHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=39 + + // Retrieves a list of all maps associated to the specified mapping + rpc ReadAllMaps (MappingHandle) returns (MapList);//@RPC_ID=40 + + // Activates the specified map within the specified map group and mapping + rpc ActivateMap (ActivateMapHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=41 + + // Creates a new action + rpc CreateAction (Action) returns (ActionHandle);//@RPC_ID=42 + + // Retrieves an existing action + rpc ReadAction (ActionHandle) returns (Action);//@RPC_ID=43 + + // Retrieves a list of all existing actions + rpc ReadAllActions (RequestedActionType) returns (ActionList);//@RPC_ID=44 + + // Deletes an existing action + rpc DeleteAction (ActionHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=45 + + // Updates an existing action + rpc UpdateAction (Action) returns (Kinova.Api.Common.Empty);//@RPC_ID=46 + + // Commands the robot to execute the specified existing action + rpc ExecuteActionFromReference (ActionHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=47 + + // Commands the robot to execute the specified action + rpc ExecuteAction (Action) returns (Kinova.Api.Common.Empty);//@RPC_ID=48 + + // Pauses the currently executed action. ResumeAction can be invoked afterwards + rpc PauseAction (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=49 + + // Stops the currently executed action. ResumeAction cannot be invoked afterwards + rpc StopAction (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=50 + + // Resumes execution of the currently paused action + rpc ResumeAction (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=51 + + // Retrieves the IPv4 network configuration for the specified network adapter + rpc GetIPv4Configuration (NetworkHandle) returns (IPv4Configuration);//@RPC_ID=59 + + // Modifies the IPv4 network configuration for the specified network adapter + rpc SetIPv4Configuration (FullIPv4Configuration) returns (Kinova.Api.Common.Empty);//@RPC_ID=60 + + // Enables (or disables) the specified communication interface + rpc SetCommunicationInterfaceEnable (CommunicationInterfaceConfiguration) returns (Kinova.Api.Common.Empty);//@RPC_ID=61 + + // Determines if the specified communication interface is enabled (or disabled) + rpc IsCommunicationInterfaceEnable (NetworkHandle) returns (CommunicationInterfaceConfiguration);//@RPC_ID=62 + + // Retrieves the list of available Wi-Fi networks + rpc GetAvailableWifi (Kinova.Api.Common.Empty) returns (WifiInformationList);//@RPC_ID=63 + + // Retrieves information about a specific Wi-Fi network + rpc GetWifiInformation (Ssid) returns (WifiInformation);//@RPC_ID=64 + + // Configures a specific Wi-Fi network + rpc AddWifiConfiguration (WifiConfiguration) returns (Kinova.Api.Common.Empty);//@RPC_ID=65 + + // Deletes a specific Wi-Fi network + rpc DeleteWifiConfiguration (Ssid) returns (Kinova.Api.Common.Empty);//@RPC_ID=66 + + // Retrieves the list of configured Wi-Fi networks + rpc GetAllConfiguredWifis (Kinova.Api.Common.Empty) returns (WifiConfigurationList);//@RPC_ID=67 + + // Connects robot to specified Wi-Fi network + rpc ConnectWifi (Ssid) returns (Kinova.Api.Common.Empty);//@RPC_ID=68 + + // Disconnects the robot from the currently connected Wi-Fi network + rpc DisconnectWifi (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=69 + + // Retrieves information about the connected Wi-Fi network + rpc GetConnectedWifiInformation (Kinova.Api.Common.Empty) returns (WifiInformation);//@RPC_ID=70 + + // Unsubscribes client from receiving notifications for the specified topic + rpc Unsubscribe (Kinova.Api.Common.NotificationHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=97 @UNSUB + + // Subscribes to configuration change topic for notifications + rpc ConfigurationChangeTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=98 @PUB_SUB=ConfigurationChangeNotification + + // Subscribes to mapping information topic for notifications + rpc MappingInfoTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=99 @PUB_SUB=MappingInfoNotification + + // Subscribes to control mode topic for notifications + rpc ControlModeTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=100 @PUB_SUB=ControlModeNotification + + // Subscribes to operating mode topic for notifications + rpc OperatingModeTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=101 @PUB_SUB=OperatingModeNotification + + // Subscribes to sequence information topic for notifications + rpc SequenceInfoTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=102 @PUB_SUB=SequenceInfoNotification + + // Subscribes to protection zone topic for notifications + rpc ProtectionZoneTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=103 @PUB_SUB=ProtectionZoneNotification + + // Subscribes to user topic for notifications + rpc UserTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=104 @PUB_SUB=UserNotification + + // Subscribes to controller topic for notifications + rpc ControllerTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=105 @PUB_SUB=ControllerNotification + + // Subscribes to action topic for notifications + rpc ActionTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=106 @PUB_SUB=ActionNotification + + // Subscribes to robot event topic for notifications + rpc RobotEventTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=107 @PUB_SUB=RobotEventNotification + + // Moves robot to the specified tool pose (position and orientation) while imposing specified constraints. + rpc PlayCartesianTrajectory (ConstrainedPose) returns (Kinova.Api.Common.Empty);//@RPC_ID=109 + + // Moves robot to the specified position while imposing specified constraints. + rpc PlayCartesianTrajectoryPosition (ConstrainedPosition) returns (Kinova.Api.Common.Empty);//@RPC_ID=110 + + // Moves to the specified orientation while imposing specified constraints. + rpc PlayCartesianTrajectoryOrientation (ConstrainedOrientation) returns (Kinova.Api.Common.Empty);//@RPC_ID=111 + + // Stops robot movement + rpc Stop (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=112 + + // Retrieves the current computed tool pose (position and orientation) for the robot + rpc GetMeasuredCartesianPose (Kinova.Api.Common.Empty) returns (Pose);//@RPC_ID=115 + + // Sends a wrench command (screw consisting of force and torque) to be applied to the tool. This method is EXPERIMENTAL. + rpc SendWrenchCommand (WrenchCommand) returns (Kinova.Api.Common.Empty);//@RPC_ID=118 + + /* + * Sends a wrench (screw consisting of force and torque) joystick command to be applied to the tool. + * The wrench values sent to this call are expected to be a ratio of maximum value (between -1.0/+1.0). This method is EXPERIMENTAL. + */ + rpc SendWrenchJoystickCommand (WrenchCommand) returns (Kinova.Api.Common.Empty);//@RPC_ID=119 + + /* + * Sends a twist (screw consisting of linear and angular velocity) joystick command to be applied to the tool. + * The twist values sent to this call are expected to be a ratio of the maximum value (between -1.0/+1.0). + */ + rpc SendTwistJoystickCommand (TwistCommand) returns (Kinova.Api.Common.Empty);//@RPC_ID=120 + + // Sends a twist (screw consisting of linear and angular velocity) command to be applied to the tool + rpc SendTwistCommand (TwistCommand) returns (Kinova.Api.Common.Empty);//@RPC_ID=121 + + // Moves joints to the specified joint angles while imposing specified constraints. + rpc PlayJointTrajectory (ConstrainedJointAngles) returns (Kinova.Api.Common.Empty);//@RPC_ID=124 + + // Moves specifed joint to the specifed joint angle while imposing specified constraints. + rpc PlaySelectedJointTrajectory (ConstrainedJointAngle) returns (Kinova.Api.Common.Empty);//@RPC_ID=125 + + // Retrieves the currently measured joint angles for each joint + rpc GetMeasuredJointAngles (Kinova.Api.Common.Empty) returns (JointAngles);//@RPC_ID=126 + + /* + * Sends a set of joint speed commands to all joints with one command. Joint speed commmands must be sent to all joints. + * If you do not want to move some of the joints, simply send a speed value of 0 degrees / second for that joint. + */ + rpc SendJointSpeedsCommand (JointSpeeds) returns (Kinova.Api.Common.Empty);//@RPC_ID=132 + + // Sends a speed command for a specific joint + rpc SendSelectedJointSpeedCommand (JointSpeed) returns (Kinova.Api.Common.Empty);//@RPC_ID=133 + + // Sends a command to move the gripper + rpc SendGripperCommand (GripperCommand) returns (Kinova.Api.Common.Empty);//@RPC_ID=136 + + // Retrieves the current gripper movement, that is the current gripper position, force or speed + rpc GetMeasuredGripperMovement (GripperRequest) returns (Gripper);//@RPC_ID=137 + + // Sets the robot in the chosen admittance mode + rpc SetAdmittance (Admittance) returns (Kinova.Api.Common.Empty);//@RPC_ID=139 + + // Sets a new operating mode. Only Maintenance, Update and Run modes are permitted. + rpc SetOperatingMode (OperatingModeInformation) returns (Kinova.Api.Common.Empty);//@RPC_ID=141 + + // Stops robot movement and activates emergency stop state. You will not be able to move the robot. Use ClearFaults() to clear the stop. + rpc ApplyEmergencyStop (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=145 + + // Clears robot stop. Robot is permitted to move again. + rpc ClearFaults (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=146 + + // Retrieves current control mode + rpc GetControlMode (Kinova.Api.Common.Empty) returns (ControlModeInformation);//@RPC_ID=150 + + // Retrieves current operating mode + rpc GetOperatingMode (Kinova.Api.Common.Empty) returns (OperatingModeInformation);//@RPC_ID=151 + + // Sets the servoing mode + rpc SetServoingMode (ServoingModeInformation) returns (Kinova.Api.Common.Empty);//@RPC_ID=152 + + // Retrieves current servoing mode + rpc GetServoingMode (Kinova.Api.Common.Empty) returns (ServoingModeInformation);//@RPC_ID=153 + + // Subscribes to servoing mode topic for notifications + rpc ServoingModeTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=154 @PUB_SUB=ServoingModeNotification + + // Deletes all configurations and reverts settings to their factory defaults (except network settings) + rpc RestoreFactorySettings (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=160 + + // Reboots the robot + rpc Reboot (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=162 + + // Subscribes to factory topic for notifications + rpc FactoryTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=164 @PUB_SUB=FactoryNotification + + // Retrieves the list of all connected controllers + rpc GetAllConnectedControllers (Kinova.Api.Common.Empty) returns (ControllerList);//@RPC_ID=166 + + // Retrieves the state of a specified controller + rpc GetControllerState (ControllerHandle) returns (ControllerState);//@RPC_ID=167 + + // Retrieves the number of actuators in the robot + rpc GetActuatorCount (Kinova.Api.Common.Empty) returns (ActuatorInformation);//@RPC_ID=171 + + // Initiates Wi-Fi scanning + rpc StartWifiScan (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=172 + + // Retrieves a configured Wi-Fi network + rpc GetConfiguredWifi (Ssid) returns (WifiConfiguration);//@RPC_ID=173 + + // Subscribes to network event notifications + rpc NetworkTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=174 @PUB_SUB=NetworkNotification + + // Retrieves current robot arm state + rpc GetArmState (Kinova.Api.Common.Empty) returns (ArmStateInformation);//@RPC_ID=175 + + // Subscribes to robot arm state notifications + rpc ArmStateTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=176 @PUB_SUB=ArmStateNotification + + // Retrieves the IPv4 network information for the specified network adapter + rpc GetIPv4Information (NetworkHandle) returns (IPv4Information);//@RPC_ID=177 + + // Sets the Wi-Fi country code + rpc SetWifiCountryCode (Kinova.Api.Common.CountryCode) returns (Kinova.Api.Common.Empty);//@RPC_ID=178 + + // Retrieves the Wi-Fi country code + rpc GetWifiCountryCode (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.CountryCode);//@RPC_ID=179 + + // Configures capacitive sensor on the gripper or wrist + rpc SetCapSenseConfig (CapSenseConfig) returns (Kinova.Api.Common.Empty);//@RPC_ID=180 + + // Retrieves configuration of capacitive sensor on the gripper or wrist + rpc GetCapSenseConfig (Kinova.Api.Common.Empty) returns (CapSenseConfig);//@RPC_ID=181 + + // Retrieves speed hard limits for all joints + rpc GetAllJointsSpeedHardLimitation (Kinova.Api.Common.Empty) returns (JointsLimitationsList);//@RPC_ID=183 @DEPRECATED="This function will be removed in a future release. Use GetKinematicHardLimits from the ControlConfig service instead." + + // Retrieves torque hard limits for all joints + rpc GetAllJointsTorqueHardLimitation (Kinova.Api.Common.Empty) returns (JointsLimitationsList);//@RPC_ID=184 @DEPRECATED + + // Retrieves twist hard limitations + rpc GetTwistHardLimitation (Kinova.Api.Common.Empty) returns (TwistLimitation);//@RPC_ID=185 @DEPRECATED="This function will be removed in a future release. Use GetKinematicHardLimits from the ControlConfig service instead." + + // Retrieves wrench hard limitations + rpc GetWrenchHardLimitation (Kinova.Api.Common.Empty) returns (WrenchLimitation);//@RPC_ID=186 @DEPRECATED + + /* + * Sends the desired joystick speeds to all joints with one command. + * The speed values sent to this call are expected to be a ratio of the maximum value (between -1.0/+1.0) + * Speeds must be sent to all joints. If you don't want to move some of the joints, send a value of 0. + */ + rpc SendJointSpeedsJoystickCommand (JointSpeeds) returns (Kinova.Api.Common.Empty);//@RPC_ID=187 + + /* + * Sends a joystick speed for a specific joint. + * The speed value sent to this call is expected to be a ratio of the maximum value (between -1.0/+1.0) + */ + rpc SendSelectedJointSpeedJoystickCommand (JointSpeed) returns (Kinova.Api.Common.Empty);//@RPC_ID=188 + + // Enables TCP bridge to hardware device + rpc EnableBridge (BridgeConfig) returns (BridgeResult); //@RPC_ID=193 + + // Disables specified TCP bridge + rpc DisableBridge (BridgeIdentifier) returns (BridgeResult); //@RPC_ID=194 + + // Retrieves list of created bridges + rpc GetBridgeList (Kinova.Api.Common.Empty) returns (BridgeList); //@RPC_ID=195 + + // Retrieves configuration for specified bridge + rpc GetBridgeConfig (BridgeIdentifier) returns (BridgeConfig); //@RPC_ID=196 + + // Plays a pre-computed angular trajectory + rpc PlayPreComputedJointTrajectory (PreComputedJointTrajectory) returns (Kinova.Api.Common.Empty);//@RPC_ID=197 + + // Retrieves product configuration information + rpc GetProductConfiguration (Kinova.Api.Common.Empty) returns (Kinova.Api.ProductConfiguration.CompleteProductConfiguration);//@RPC_ID=198 + + // Set new end-effector type in product configuration (Identification Number) + rpc UpdateEndEffectorTypeConfiguration (Kinova.Api.ProductConfiguration.ProductConfigurationEndEffectorType) returns (Kinova.Api.Common.Empty);//@RPC_ID=201 + + // Restores product configuration to factory product configuration + rpc RestoreFactoryProductConfiguration (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=206 + + /* + * Obtains trajectory error report listing errors for rejected trajectory. + * Provides some feedback on why the trajectory could not be completed. + */ + rpc GetTrajectoryErrorReport (Kinova.Api.Common.Empty) returns (TrajectoryErrorReport);//@RPC_ID=207 + + // Retrieves list of soft speed limits for all joints + rpc GetAllJointsSpeedSoftLimitation (Kinova.Api.Common.Empty) returns (JointsLimitationsList);//@RPC_ID=208 @DEPRECATED="This function will be removed in a future release. Use GetKinematicSoftLimits from the ControlConfig service instead." + + // Retrieves list of soft torque limits for all joints + rpc GetAllJointsTorqueSoftLimitation (Kinova.Api.Common.Empty) returns (JointsLimitationsList);//@RPC_ID=209 @DEPRECATED + + // Retrieves all twist soft limitations + rpc GetTwistSoftLimitation (Kinova.Api.Common.Empty) returns (TwistLimitation);//@RPC_ID=210 @DEPRECATED="This function will be removed in a future release. Use GetKinematicSoftLimits from the ControlConfig service instead." + + // Retrieves all wrench soft limitations + rpc GetWrenchSoftLimitation (Kinova.Api.Common.Empty) returns (WrenchLimitation);//@RPC_ID=211 @DEPRECATED + + // Sets controller configuration mode + rpc SetControllerConfigurationMode (ControllerConfigurationMode) returns (Kinova.Api.Common.Empty);//@RPC_ID=212 + + // Retrieves current controller configuration mode + rpc GetControllerConfigurationMode (Kinova.Api.Common.Empty) returns (ControllerConfigurationMode);//@RPC_ID=213 + + // Enables the teaching mode on a sequence + rpc StartTeaching (SequenceTaskHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=214 + + // Disables the teaching mode on a sequence + rpc StopTeaching (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty);//@RPC_ID=215 + + // Adds tasks to the specified sequence + rpc AddSequenceTasks (SequenceTasksConfiguration) returns (SequenceTasksRange);//@RPC_ID=216 + + // Updates a task within the specified sequence + rpc UpdateSequenceTask (SequenceTaskConfiguration) returns (Kinova.Api.Common.Empty);//@RPC_ID=217 + + // Swaps two task indexes in a sequence + rpc SwapSequenceTasks (SequenceTasksPair) returns (Kinova.Api.Common.Empty);//@RPC_ID=218 + + // Reads a specific task from the specified sequence + rpc ReadSequenceTask (SequenceTaskHandle) returns (SequenceTask);//@RPC_ID=219 + + // Reads all tasks from the specified sequence + rpc ReadAllSequenceTasks (SequenceHandle) returns (SequenceTasks);//@RPC_ID=220 + + // Deletes a specific task from the specified sequence + rpc DeleteSequenceTask (SequenceTaskHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=13 + + // Deletes all tasks from the specified sequence + rpc DeleteAllSequenceTasks (SequenceHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=14 + + // Take a snapshot of current robot Cartesian, joint or gripper position + rpc TakeSnapshot (Snapshot) returns (Kinova.Api.Common.Empty);//@RPC_ID=223 + + // Retrieves current firmware bundle versions + rpc GetFirmwareBundleVersions (Kinova.Api.Common.Empty) returns (FirmwareBundleVersions);//@RPC_ID=224 + + // Move task to new index in a sequence + rpc MoveSequenceTask (SequenceTasksPair) returns (Kinova.Api.Common.Empty);//@RPC_ID=227 + + // Duplicates an existing mapping + rpc DuplicateMapping (MappingHandle) returns (MappingHandle);//@RPC_ID=228 + + // Duplicates an existing map + rpc DuplicateMap (MapHandle) returns (MapHandle);//@RPC_ID=229 + + // Sets controller configuration + rpc SetControllerConfiguration (ControllerConfiguration) returns (Kinova.Api.Common.Empty);//@RPC_ID=230 + + // Retrieves current controller configuration + rpc GetControllerConfiguration (ControllerHandle) returns (ControllerConfiguration);//@RPC_ID=231 + + // Retrieves all controller configurations + rpc GetAllControllerConfigurations (Kinova.Api.Common.Empty) returns (ControllerConfigurationList);//@RPC_ID=232 +} + +// Identifies Base service current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Information about a user, together with a password. Full set of information needed to create a user profile. +message FullUserProfile { + UserProfile user_profile = 1; // Information about the user, including its username. + string password = 2; // User's password +} + +// Information about a user +message UserProfile { + Kinova.Api.Common.UserProfileHandle handle = 1; // User handle (no need to set it with CreateUserProfile()) + string username = 2; // Username, which is used to connect to robot (or login via Web App) + string firstname = 3; // User's first name + string lastname = 4; // User's last name + string application_data = 5; // Application data (reserved for use by Web App) +} + +// Array of user profiles +message UserProfileList { + repeated UserProfile user_profiles = 1; // User profile +} + +// Array of user profile handles +message UserList { + repeated Kinova.Api.Common.UserProfileHandle user_handles = 1; // User handle +} + +// Information required to change user password +message PasswordChange { + Kinova.Api.Common.UserProfileHandle handle = 1; // User handle + string old_password = 2; // Current password + string new_password = 3; // New password +} + +// Reference to a specific sequence +message SequenceHandle { + uint32 identifier = 1; // Sequence identifier + fixed32 permission = 2; // Sequence permission. See 'Kinova.Api.Common.Permission' enum. +} + +// Reference to a sequence along with execution options +message AdvancedSequenceHandle { + SequenceHandle handle = 1; // Sequence handle + /* + * Loop execution. Set to true to play the sequence in loop, false otherwise. When a sequence is executed in loop, it will automatically + * go back to first task within the sequence after completing execution of last task and continue execution forever + * unless the sequence is explicitely stopped + */ + bool in_loop = 2; +} + +// Reference to a specific task inside a sequence +message SequenceTaskHandle { + SequenceHandle sequence_handle = 1; // Sequence handle + uint32 task_index = 2; // Task index inside the sequence +} + +// Information on a single task within a sequence +message SequenceTask { + uint32 group_identifier = 1; // This field is deprecated and unused. Use task_index in the SequenceTaskHandle instead. + Action action = 2; // Specifies the action to execute + string application_data = 3; // Application data (reserved for use by Web App) +} + +// Information on multiple tasks within a sequence +message SequenceTasks { + repeated SequenceTask sequence_tasks = 1; // List of tasks +} + +// Reference to a specific task within a sequence, and information on list of sequence tasks to be inserted +message SequenceTasksConfiguration { + SequenceTaskHandle sequence_task_handle = 1; // Sequence Handle and task index as the insertion point + repeated SequenceTask sequence_tasks = 2; // Tasks to be inserted +} + +// Reference to a specific task within a sequence, and configuration information on task to be updated +message SequenceTaskConfiguration { + SequenceTaskHandle sequence_task_handle = 1; // Sequence Handle and index of task to update + SequenceTask sequence_task = 2; // Configuration information on task to be updated +} + +// Information on a range of task indexes +message SequenceTasksRange { + uint32 first_task_index = 1; // Index of first task + uint32 second_task_index = 2; // Index of second task +} + +// Information on a sequence and a pair of tasks to be operated on +message SequenceTasksPair { + SequenceHandle sequence_handle = 1; // Sequence handle + uint32 first_task_index = 2; // Index of first task + uint32 second_task_index = 3; // Index of second task +} + +// Information about a sequence +message Sequence { + SequenceHandle handle = 1; // Sequence handle + string name = 2; // Sequence name + string application_data = 3; // Application data (reserved for use by Web App) + repeated SequenceTask tasks = 4; // Array of tasks that this sequence contains +} + +// An array of sequences +message SequenceList { + repeated Sequence sequence_list = 1; // Sequence +} + +// Representation of the result of appending (adding at the end) an action to an existing sequence (not implemented yet) +message AppendActionInformation { + SequenceHandle sequence_handle = 1; // Sequence to which action must be appended + Action action = 2; // Action to append +} + +// Reference to a specific action +message ActionHandle { + uint32 identifier = 1; // Action identifier + ActionType action_type = 2; // Action type + fixed32 permission = 3; // Permission of specified Action entity. Must use 'Kinova.Api.Common.Permission' enum. +} + +// Message used for requesting all action instances of a specific action type +message RequestedActionType { + ActionType action_type = 1; // Action type +} + +// Defines an action. An action is some task performed on the robot. +message Action { + ActionHandle handle = 1; // Reference to the action (useful when updating an existing action) + string name = 2; // Action friendly name + string application_data = 3; // Application data (reserved for use by Web App) + oneof action_parameters { + TwistCommand send_twist_command = 4; // Control the tool in velocity + WrenchCommand send_wrench_command = 5; // Control the tool in force (EXPERIMENTAL) + JointSpeeds send_joint_speeds = 7; // Action to control each joint speed + ConstrainedPose reach_pose = 9; // Reach a pose given Cartesian constraints. + ConstrainedJointAngles reach_joint_angles = 10; // Reach a series of joint angles given angular constraints. + AdmittanceMode toggle_admittance_mode = 16; // Enable or disable the admittance mode + Snapshot snapshot = 17; // Take a snapshot of current robot position + SwitchControlMapping switch_control_mapping = 19; // Switch the active controller map + JointNavigationDirection navigate_joints = 20; // Select the next actuator to control in a map + NavigationDirection navigate_mappings = 21; // Select a different map + ChangeTwist change_twist = 25; // Change tool twist + ChangeJointSpeeds change_joint_speeds = 26; // Change the joint speeds individually + ChangeWrench change_wrench = 28; // Change the Cartesian force + EmergencyStop apply_emergency_stop = 31; // Apply robot emergency stop + Faults clear_faults = 32; // Clear faults. Robot will be able to move if there is no more fault (see BaseCyclic.BaseFeedback.[fault_bank_a | fault_bank_b]) + Delay delay = 34; // Apply a delay + ActionHandle execute_action = 35; // Execute an existing action + GripperCommand send_gripper_command = 36; // Send a gripper command + Stop stop_action = 38; // Stop movement + PreComputedJointTrajectory play_pre_computed_trajectory = 39; // Play a pre-computed joint trajectory + } +} + +// Admissible types of actions +enum ActionType { + UNSPECIFIED_ACTION = 0; // Unspecified action type + SEND_TWIST_COMMAND = 1; // Control the robot in Cartesian velocity + SEND_WRENCH_COMMAND = 2; // Control the robot in force + SEND_JOINT_SPEEDS = 4; // Control each joint speed + REACH_POSE = 6; // Reach a pose + REACH_JOINT_ANGLES = 7; // Reach a series of joint angles + TOGGLE_ADMITTANCE_MODE = 13; // Enable or disable the admittance mode + SNAPSHOT = 14; // Take a snapshot of current robot position + SWITCH_CONTROL_MAPPING = 16; // Switch the active controller map + NAVIGATE_JOINTS = 17; // Select the next actuator to control from control mapping + NAVIGATE_MAPPINGS = 18; // Select a different map + CHANGE_TWIST = 22; // Change the twist + CHANGE_JOINT_SPEEDS = 23; // Change the joint speeds individually + CHANGE_WRENCH = 25; // Change the Cartesian force + APPLY_EMERGENCY_STOP = 28; // Apply robot emergency stop + CLEAR_FAULTS = 29; // Clear faults. Robot will be able to move if there is no more fault (see BaseCyclic.BaseFeedback.[fault_bank_a | fault_bank_b]) + TIME_DELAY = 31; // Apply a delay + EXECUTE_ACTION = 32; // Execute an existing action + SEND_GRIPPER_COMMAND = 33; // Send a gripper command + STOP_ACTION = 35; // Stop robot movement + PLAY_PRE_COMPUTED_TRAJECTORY = 39; // Play a pre-computed trajectory +} + +// Admissible types of snapshots +enum SnapshotType { + UNSPECIFIED_SNAPSHOT = 0; // Unspecified snapshot type + CARTESIAN_POSITION_SNAPSHOT = 1; // Snapshot of the current Cartesian robot position + JOINT_POSITION_SNAPSHOT = 2; // Snapshot of the current joint robot position + GRIPPER_SNAPSHOT = 3; // Snapshot of the current gripper position + COMBINED_SNAPSHOT = 4; // Snapshot of the current robot and gripper positions +} + +// Action parameter to take a snapshot of current robot position +message Snapshot { + SnapshotType snapshot_type = 1; // Snapshot type +} + +// Action parameter to switch the active controller map +message SwitchControlMapping { + uint32 controller_identifier = 1; // Identifier of the controller for which changing the active map is requested + MapGroupHandle map_group_handle = 2; // Reference to the map group for which the active map needs to change + MapHandle map_handle = 3; // Reference to new active map +} + +// Action to change the maximum Cartesian velocity by a specific increment +message ChangeTwist { + float linear = 1; // Linear Cartesian velocity increment (in meters per second) + float angular = 2; // Angular Cartesian velocity increment (in degrees per second) +} + +// Action to change the maximum angular velocity per joint by a specific increment +message ChangeJointSpeeds { + JointSpeeds joint_speeds = 1; // Joint speeds +} + +// Action to change the maximum Cartesian force by a specific increment +message ChangeWrench { + float force = 1; // Linear force increment (in Newton) + float torque = 2; // Angular torque increment (in Newton*meters) +} + +// Action to force an emergency of the robot +message EmergencyStop { +} + +// Action to clear faults +message Faults { +} + +// Action to apply a delay +message Delay { + uint32 duration = 1; // Delay (in seconds) +} + +// Action to stop robot movement +message Stop { +} + +// Array of actions +message ActionList { + repeated Action action_list = 1; // Action +} + +// Timeout for a specified duration +message Timeout { + uint32 value = 1; // Timeout value (not implemented yet) +} + +// Wi-Fi SSID +message Ssid { + string identifier = 1; // Wi-Fi Service Set Identifier +} + +// Configuration information for enabling or disabling a specific communication interface (e.g. Wi-Fi, Wired Ethernet) +message CommunicationInterfaceConfiguration { + NetworkType type = 1; // Network type (e.g. Wi-Fi, Wired Ethernet) + bool enable = 2; // Enable configuration. Set to true to enable network, false otherwise +} + +// Admissible network types +enum NetworkType { + UNSPECIFIED_NETWORK_TYPE = 0; // Unspecified network type + WIFI = 1; // Wi-Fi network + WIRED_ETHERNET = 2; // Wired Ethernet network + WIRED_MICROUSB = 3; // Wired Ethernet over USB network (RNDIS) + WIRED_USB = 4; // Wired Ethernet over USB network +} + +// Reference to a network +message NetworkHandle { + NetworkType type = 1; // Network type +} + +// IPv4 configuration information +message IPv4Configuration { + uint32 ip_address = 1; // IPv4 address + uint32 subnet_mask = 2; // IPv4 subnet mask + uint32 default_gateway = 3; // Gateway IPv4 address + bool dhcp_enabled = 4; // Enable automatic (DHCP) IPv4 configuration. Set to true to enable DHCP instead of static configuration. +} + +// Information about an IPv4 endpoint +message IPv4Information { + uint32 ip_address = 1; // IPv4 address + uint32 subnet_mask = 2; // IPv4 subnet mask + uint32 default_gateway = 3; // Gateway IPv4 address +} + +// IPv4 configuration for a specific network +message FullIPv4Configuration { + NetworkHandle handle = 1; // Network handle + IPv4Configuration ipv4_configuration = 2; // IPv4 configuration +} + + +// Admissible Wi-Fi Security types +enum WifiSecurityType { + UNSPECIFIED_AUTHENTICATION = 0; // Unspecified Wi-Fi security type + WEP = 1; // WEP authentication required + WPA2_PERSONAL = 2; // WPA2 Personal authentication required + WPA_PERSONAL = 4; // WPA Personal authentication required + NO_AUTHENTICATION = 8; // No authentication required +} + +// Admissible Wi-Fi encryption types +enum WifiEncryptionType { + UNSPECIFIED_ENCRYPTION = 0; // Unspecified Wi-Fi encryption type + AES_ENCRYPTION = 1; // AES encryption + TKIP_ENCRYPTION = 2; // TKIP encryption + WEP_ENCRYPTION = 4; // WEP encryption +} + +// Admissible signal quality values +enum SignalQuality { + UNSPECIFIED_SIGNAL_QUALITY = 0; // Unspecified signal quality + POOR = 1; // Poor signal quality + FAIR = 2; // Fair signal quality + GOOD = 3; // Good signal quality + EXCELLENT = 4; // Excellent signal quality + NONE = 5; // No signal +} + +// Information about a specific Wi-Fi network +message WifiInformation { + Ssid ssid = 1; // SSID + fixed32 security_type = 2; // Wi-Fi security type + fixed32 encryption_type = 3; // Wi-Fi encryption type + SignalQuality signal_quality = 4; // Wi-Fi signal quality + int32 signal_strength = 5; // Wi-Fi signal power in dBm + uint32 frequency = 6; // Wi-Fi operating frequency (channel) in MHz + uint32 channel = 7; // Wi-Fi operating channel +} + +// Array of information about different Wi-Fi networks +message WifiInformationList { + repeated WifiInformation wifi_information_list = 1; // Wi-Fi information +} + +// Wi-Fi connection configuration +message WifiConfiguration { + Ssid ssid = 1; // SSID + string security_key = 2; // Security key to used when connecting to Wi-Fi network + bool connect_automatically = 3; // Connection mode. Set to true so robot automatically connects to this Wi-Fi network at bootup, false otherwise +} + +// Array of Wi-Fi connection configuration for different networks +message WifiConfigurationList { + repeated WifiConfiguration wifi_configuration_list = 1; // Wi-Fi configurations +} + +// Reference to a specific protection zone +message ProtectionZoneHandle { + uint32 identifier = 1; // Protection zone identifier + fixed32 permission = 2; // Permission of specified Proctection zone entity. Must use 'Kinova.Api.Common.Permission' enum. +} + +/* + * Single row of a 3x3 rotation matrix. To be a valid possible row of a rotation matrix, + * the norm of the row must be 1 (the sum of the squares of the row elements has to equal 1). + */ +message RotationMatrixRow { + float column1 = 1; // Value between -1.0 and 1.0 + float column2 = 2; // Value between -1.0 and 1.0 + float column3 = 3; // Value between -1.0 and 1.0 +} + +/* + * Representation of a 3x3 rotation matrix. To be a valid rotation matrix, the rows must be orthonormal + * (the rows must each have norm of 1 and the row vectors must be orthogonal to each other). + * The determinant of the matrix must also be +1. + */ +message RotationMatrix { + RotationMatrixRow row1 = 1; // First rotation matrix row + RotationMatrixRow row2 = 2; // Second rotation matrix row + RotationMatrixRow row3 = 3; // Third rotation matrix row +} + +// Coordinates of a Cartesian point +message Point { + float x = 1; // x (in meters) + float y = 2; // y (in meters) + float z = 3; // z (in meters) +} + +// Admissible protection zone shape types +enum ShapeType { + UNSPECIFIED_SHAPE = 0; // Unspecified shape type + CYLINDER = 1; // Cylinder shape type + SPHERE = 2; // Sphere shape type + RECTANGULAR_PRISM = 3; // Rectangular prism shape type +} + +// Protection zone shape description +message ZoneShape { + ShapeType shape_type = 1; // Shape type + Point origin = 2; // Origin of the protection zone shape from reference (in meters) + RotationMatrix orientation = 3; // Rotation matrix to provide shape orientation + repeated float dimensions = 4; // Shape size measurement (in meters). If rectangular prism: x, y and z dimensions. If cylinder: radius and height. If sphere: radius + float envelope_thickness = 5; // Thickness of envelop around shape (in meters). The envelop is of same shape type as the shape at its center. +} + +// Protection zone configuration +message ProtectionZone { + ProtectionZoneHandle handle = 1; // Protection zone handle + string name = 2; // Protection zone friendly name + string application_data = 3; // Application data (reserved for use by Web App) + bool is_enabled = 4; // True if protection zone is enabled, false otherwise + ZoneShape shape = 5; // Protection zone shape + repeated CartesianLimitation limitations = 6; // List of Cartesian limitation + repeated CartesianLimitation envelope_limitations = 7; // List of Cartesian limitation of the envelop +} + +// Array of protection zones +message ProtectionZoneList { + repeated ProtectionZone protection_zones = 1; // Protection zone +} + +// Admissible limitation types +enum LimitationType { + UNSPECIFIED_LIMITATION = 0; // Unspecified limitation + FORCE_LIMITATION = 1; // Force limitation (not implemented yet) + ACCELERATION_LIMITATION = 2; // Acceleration limitation (not implemented yet) + VELOCITY_LIMITATION = 3; // Velocity limitation + TORQUE_LIMITATION = 4; // Torque limitation +} + +// Translation and orientation limits for a specified limit type for Cartesian configuration +message CartesianLimitation { + LimitationType type = 1; // Limitation type + float translation = 2; // Translation limitation + float orientation = 3; // Orientation limitation +} + +// Linear and angular speed limitations for twist configuration +message TwistLimitation { + float linear = 1; // Linear limitation + float angular = 2; // Angular limitation +} + +// Force and torque limitations for wrench configuration +message WrenchLimitation { + float force = 1; // Force limitation + float torque = 2; // Torque limitation +} + +// Array of Cartesian limitations +message CartesianLimitationList { + repeated CartesianLimitation limitations = 1; // Limitation +} + +// Limitation for a specified robot joint +message JointLimitation { + uint32 joint_identifier = 1; // Joint device identifier + LimitationType type = 2; // Joint limitation type + float value = 3; // Joint limitation value +} + +// Array of joint limitations +message JointsLimitationsList { + repeated JointLimitation joints_limitations = 1; // Joints Limitations +} + +// Parameters of an event log query (not implemented yet) +message Query { + Kinova.Api.Common.Timestamp start_timestamp = 1; // Start timestamp (set to zero to specify it) + Kinova.Api.Common.Timestamp end_timestamp = 2; // End timestamp (set to zero to not specify it) + string username = 3; // Queried username (set to "" to not specify it) +} + +// Admissible configuration events +enum ConfigurationNotificationEvent { + UNSPECIFIED_CONFIGURATION_EVENT = 0; // Unspecified configuration event + CONFIGURATION_UPDATED = 1; // Configuration deleted + CONFIGURATION_DELETED = 2; // Configuration updated + CONFIGURATION_DELETED_ALL = 3; // All configurations deleted + CONFIGURATION_CREATED = 4; // Configuration created +} + +// Representation of a configuration change event +message ConfigurationChangeNotification { + ConfigurationNotificationEvent event = 1; // Configuration event + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the configuration event + oneof configuration_change { + SequenceHandle sequence_handle = 4; // Sequence for which the configuration changed + ActionHandle action_handle = 5; // Action for which the configuration changed + MappingHandle mapping_handle = 6; // Mapping for which the configuration changed + MapGroupHandle map_group_handle = 7; // Map group for which the configuration changed + MapHandle map_handle = 8; // Map for which the configuration changed + Kinova.Api.Common.UserProfileHandle user_profile_handle = 9; // User Profile for which the configuration changed + ProtectionZoneHandle protection_zone_handle = 10; // Protection zone for which the configuration changed + Kinova.Api.Common.SafetyHandle safety_handle = 11; // Safety for which the configuration changed + NetworkHandle network_handle = 12; // Network element for which the configuration changed + Ssid ssid = 14; // Wi-Fi instance for which the configuration changed + ControllerHandle controller_handle = 16; // Controller instance for which the configuration changed + } + Kinova.Api.Common.Connection connection = 15; // Connection that caused the configuration event +} + +// Notification about a single mapping information event +message MappingInfoNotification { + uint32 controller_identifier = 1; // Identifier of the controller + MapHandle active_map_handle = 2; // New active map + Kinova.Api.Common.Timestamp timestamp = 3; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 4; // User that caused the mapping information event + Kinova.Api.Common.Connection connection = 5; // Connection that caused the mapping information event + MappingHandle mapping_handle = 6; // Mapping for which the map was activated +} + +// Admissible robot control modes. +// This enum may be removed in a future release. It has been moved to ControlConfig service. +enum ControlMode { + UNSPECIFIED_CONTROL_MODE = 0; // Unspecified control mode + ANGULAR_JOYSTICK = 1; // Angular joystick mode + CARTESIAN_JOYSTICK = 2; // Cartesian joystick mode + ANGULAR_TRAJECTORY = 4; // Angular trajectory mode + CARTESIAN_TRAJECTORY = 5; // Cartesian trajectory mode + CARTESIAN_ADMITTANCE = 6; // Cartesian admittance mode + JOINT_ADMITTANCE = 7; // Joint admittance mode + NULL_SPACE_ADMITTANCE = 8; // Null space mode + FORCE_CONTROL = 10; // Force control mode + FORCE_CONTROL_MOTION_RESTRICTED = 11; // Force control motion restricted mode + IDLE = 13; // Idle +}; + +// Control mode information +// This message may be removed in a future release. It has been moved to ControlConfig service. +message ControlModeInformation { + ControlMode mode = 1; // Control mode +} + +// Notification about a single control mode event +message ControlModeNotification { + ControlMode control_mode = 1; // New control mode + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the control mode event + Kinova.Api.Common.Connection connection = 4; // Connection that caused the control mode event +} + +// Admissible robot operating modes (used to report robot firmware upgrade current state) +enum OperatingMode { + UNSPECIFIED_OPERATING_MODE = 0; // Unspecified operating mode + MAINTENANCE_MODE = 1; // Robot in maintenance mode + UPDATE_MODE = 2; // Robot waiting for upgrade package + UPDATE_COMPLETED_MODE = 3; // Robot update successfully completed + UPDATE_FAILED_MODE = 4; // Robot update failed + SHUTTING_DOWN_MODE = 5; // Robot about to shutdown + RUN_MODE = 6; // Robot properly running (or normal operation mode) + UPDATING_DEVICE_MODE = 7; // Robot updating device +} + +// Admissible servoing modes +enum ServoingMode { + UNSPECIFIED_SERVOING_MODE = 0; // Unspecified servoing mode + SINGLE_LEVEL_SERVOING = 2; // Single-level servoing + LOW_LEVEL_SERVOING = 3; // Low-level servoing + BYPASS_SERVOING = 4; // Bypass mode +} + +// Information about the servoing mode +message ServoingModeInformation { + ServoingMode servoing_mode = 1; // Servoing mode +} + +// Information about the operating mode +message OperatingModeInformation { + OperatingMode operating_mode = 1; // Operating mode + Kinova.Api.Common.DeviceHandle device_handle = 2; // Device matching operating mode (if applicable) +} + +// Notification about a single operating mode event +message OperatingModeNotification { + OperatingMode operating_mode = 1; // New operating mode + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the operating mode event + Kinova.Api.Common.Connection connection = 4; // Connection that caused the operating mode event + Kinova.Api.Common.DeviceHandle device_handle = 5; // Device matching operating mode (if applicable) +} + +// Notification about a single servoing mode event +message ServoingModeNotification { + ServoingMode servoing_mode = 1; // New servoing mode + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the servoing mode event + Kinova.Api.Common.Connection connection = 4; // Connection that caused the servoing mode event +} + +// Admissible sequence event types +enum EventIdSequenceInfoNotification { + UNSPECIFIED_SEQUENCE_EVENT = 0; // Unspecified sequence event + SEQUENCE_COMPLETED = 1; // Sequence completed successfully + SEQUENCE_ABORTED = 2; // Sequence aborted + SEQUENCE_PAUSED = 3; // Sequence paused + SEQUENCE_TASK_STARTED = 4; // Sequence task started + SEQUENCE_TASK_COMPLETED = 5; // Sequence task completed + SEQUENCE_STARTED = 6; // Sequence started +} + +// Notification about a single sequence information event +message SequenceInfoNotification { + EventIdSequenceInfoNotification event_identifier = 1; // Sequence event type + SequenceHandle sequence_handle = 2; // Handle of the sequence that this event refers to + uint32 task_index = 3; // Task index + uint32 group_identifier = 4; // This field is deprecated and unused. Use task_index instead. + Kinova.Api.Common.Timestamp timestamp = 5; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 6; // User that caused the sequence event + SubErrorCodes abort_details = 7; // Details if event_identifier is equal to ABORT + Kinova.Api.Common.Connection connection = 8; // Connection that caused the sequence event +} + +// Information about a sequence +message SequenceInformation { + EventIdSequenceInfoNotification event_identifier = 1; // Sequence event type + uint32 task_index = 2; // Task index + uint32 task_identifier = 3; // Task identifier +} + +// Admissible protection zone events +enum ProtectionZoneEvent { + UNSPECIFIED_PROTECTION_ZONE_EVENT = 0; // Unspecified protection zone event + REACHED = 1; // Protection zone limit is reached + ENTERED = 2; // Protection zone limit is entered + EXITED = 3; // Protection zone limit is exited +}; + +// Notification about a single protection zone event +message ProtectionZoneNotification { + ProtectionZoneEvent event = 1; // Event type + ProtectionZoneHandle handle = 2; // Handle of the protection zone that this event refers to + Kinova.Api.Common.Timestamp timestamp = 3; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 4; // User that caused the protection zone event to occur + Kinova.Api.Common.Connection connection = 5; // Connection that caused the protection zone event to occur +} + +// Information about a protection zone event +message ProtectionZoneInformation { + ProtectionZoneEvent event = 1; // Event type +} + +// Admissible user event types +enum UserEvent { + UNSPECIFIED_USER_EVENT = 0; // Unspecified user event + LOGGED_OUT = 1; // User logged out + LOGGED_IN = 2; // User logged in +}; + +// Notification about a single user event +message UserNotification { + UserEvent user_event = 1; // User event type + Kinova.Api.Common.UserProfileHandle modified_user = 2; // User profile that was modified + Kinova.Api.Common.Timestamp timestamp = 3; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 4; // User that caused the user profile event (i.e. user who changed the user profile) + Kinova.Api.Common.Connection connection = 5; // Connection that caused the user profile event (i.e. user who changed the user profile) +} + +// Admissible controller types +enum ControllerType { + UNSPECIFIED_CONTROLLER_TYPE = 0; // Unspecified controller device type + XBOX_CONTROLLER = 1; // Xbox gamepad + WRIST_CONTROLLER = 2; // Wrist buttons + BASIC_JOYSTICK_CONTROLLER = 3; // Simplified joystick connected to Kinova robot base + BASE_GPIO_CONTROLLER = 4; // GPIO Controller (not implemented yet) +} + +// Reference to a specific controller device +message ControllerHandle { + ControllerType type = 1; // Controller device type + uint32 controller_identifier = 2; // Controller device identifier +} + +// Reference ro a specific button (or axis) of a controller device +message ControllerElementHandle { + ControllerHandle controller_handle = 1; // Controller handle + oneof identifier { + uint32 button = 2; // Button identifier (only set if 'button' controller event, otherwise zero) + uint32 axis = 3; // Axis identifier (only set if 'axis' controller event, otherwise zero) + } +} + +// Notification about a single controller event +message ControllerNotification { + oneof state { + ControllerState controller_state = 1; // Used to indicate if a controller connection or disconnection event occured + ControllerElementState controller_element = 2; // Used to indicate if a specific button (or axis) was pressed (or moved) + } + Kinova.Api.Common.Timestamp timestamp = 3; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 4; // User that caused the controller event + Kinova.Api.Common.Connection connection = 5; // Connection that caused the controller event +} + +// Array of references to different controllers +message ControllerList { + repeated ControllerHandle handles = 1; // Controller handle +} + +// Indicates if a specific controller is connected (or disconnected) +message ControllerState { + ControllerHandle handle = 1; // Controller identifier + ControllerEventType event_type = 2; // Type of controller event that occured +} + +// Indicates if a specific button (or axis) was pressed (or moved) +message ControllerElementState { + ControllerElementHandle handle = 1; // Controller element handle + ControllerElementEventType event_type = 2; // Type of controller element event that occured + float axis_value = 3; // Axis value (set between -1.0 and 1.0); only set if 'axis' controller element, otherwise set to zero +} + +// Admissible controller event types +enum ControllerEventType { + UNSPECIFIED_CONTROLLER_EVENT = 0; // Unspecified controller event + CONTROLLER_DISCONNECTED = 1; // Controller is disconnected + CONTROLLER_CONNECTED = 2; // Controller is connected +} + +// Admissible controller element event types +enum ControllerElementEventType { + UNSPECIFIED_CONTROLLER_ELEMENT_EVENT = 0; // Unspecified controller element event + AXIS_MOVED = 1; // Controller axis moved + BUTTON_DOWN = 2; // Controller button pressed + BUTTON_UP = 3; // Controller button released + BUTTON_CLICK = 4; // Controller button clicked +} + +// Admissible action event types +enum ActionEvent { + UNSPECIFIED_ACTION_EVENT = 0; // Unspecified action event + ACTION_END = 1; // Action execution end reached + ACTION_ABORT = 2; // Action execution aborted + ACTION_PAUSE = 3; // Action execution paused + ACTION_START = 4; // Action execution started + ACTION_PREPROCESS_START = 5; // Action pre-process started + ACTION_PREPROCESS_ABORT = 6; // Action pre-process aborted + ACTION_PREPROCESS_END = 7; // Action pre-process ended + ACTION_POSTPROCESS_START = 8; // Action post-process started + ACTION_POSTPROCESS_ABORT = 9; // Action post-process aborted + ACTION_POSTPROCESS_END = 10; // Action post-process ended +} + +// Notification about a single action event +message ActionNotification { + ActionEvent action_event = 1; // Action event type + ActionHandle handle = 2; // Identifies the action for which this event occured + Kinova.Api.Common.Timestamp timestamp = 3; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 4; // User that caused the action event + SubErrorCodes abort_details = 5; // Details if action_event is equal to ACTION_ABORT + Kinova.Api.Common.Connection connection = 6; // Connection that caused the action event +} + +// Indicates the execution state of an action (not implemented yet) +message ActionExecutionState { + ActionEvent action_event = 1; // Action event type + ActionHandle handle = 2; // Identifies the action for which this event occured +} + +// Admissible robot events +enum RobotEvent { + UNSPECIFIED_ROBOT_EVENT = 0; // Unspecified robot event + ARM_CONNECTED = 1; // Robot arm is connected + ARM_DISCONNECTED = 2; // Robot arm is disconnected + TOOL_CONNECTED = 5; // Tool is connected to the interface module (not implemented yet) + TOOL_DISCONNECTED = 6; // Tool is disconnected from the interface module (not implemented yet) +} + +// Notification about a single robot event +message RobotEventNotification { + RobotEvent event = 1; // Robot event type + Kinova.Api.Common.DeviceHandle handle = 2; // Identifier of the hardware device connected or disconnected + Kinova.Api.Common.Timestamp timestamp = 3; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 4; // User that caused the robot event to occur + Kinova.Api.Common.Connection connection = 6; // Connection that caused the robot event to occur +} + +// Admissible backup events (not implemented yet) +enum BackupEvent { + UNSPECIFIED_BACKUP_EVENT = 0; // Unspecified backup event + BACKUP_RESTORED = 1; // Configuration backup restored + BACKUP_UPLOADED = 2; // Configuration backup uploaded on robot +} + +// Admissible factory events +enum FactoryEvent { + UNSPECIFIED_FACTORY_EVENT = 0; // Unspecified factory event + FACTORY_DEFAULT_RESTORED = 1; // Factory defaults restored on robot + NETWORK_FACTORY_DEFAULT_RESTORED = 2; // Network factory defaults restored on robot (not implemented yet) +} + +// Notification about a single factory event +message FactoryNotification { + FactoryEvent event = 1; // Event type + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the factory event to occur + Kinova.Api.Common.Connection connection = 4; // Connection that caused the factory event to occur +} + +// Admissible network events +enum NetworkEvent { + UNSPECIFIED_NETWORK_EVENT = 0; // Unspecified network event + WIFI_CONNECTED = 1; // Wi-Fi connected + WIFI_DISCONNECTED = 2; // Wi-Fi Disconnected + WIFI_SCAN_STARTED = 3; // Wi-Fi scan was initiated + WIFI_SCAN_RESULTS = 4; // Wi-Fi scan results are available + WIFI_SCAN_FAILED = 5; // Wi-Fi scan failed + WIFI_NOT_FOUND = 6; // Wi-Fi selected network not found + WIFI_ASSOC_REJECTED = 7; // Wi-Fi AP rejected association + WIFI_AUTH_WRONG_KEY = 8; // Wi-Fi wrong PSK supplied + WIFI_AUTH_CONN_FAILED = 9; // Wi-Fi connection failure during auth + WIFI_AUTH_FAILED = 10; // Wi-Fi authentication failure +} + +// Notification about a single network event +message NetworkNotification { + NetworkEvent event = 1; // Event type + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the network event to occur + Kinova.Api.Common.Connection connection = 4; // Connection that caused the network event to occur +} + +// Array of configuration change notifications +message ConfigurationChangeNotificationList { + repeated ConfigurationChangeNotification notifications = 1; // Notification +} + +// Array of mapping information notifications +message MappingInfoNotificationList { + repeated MappingInfoNotification notifications = 1; // Notification +} + +// Array of control mode notifications +message ControlModeNotificationList { + repeated ControlModeNotification notifications = 1; // Notification +} + +// Array of operating mode notifications +message OperatingModeNotificationList { + repeated OperatingModeNotification notifications = 1; // Notification +} + +// Array of servoing mode notifications +message ServoingModeNotificationList { + repeated ServoingModeNotification notifications = 1; // Notification +} + +// Array of sequence information notifications +message SequenceInfoNotificationList { + repeated SequenceInfoNotification notifications = 1; // Notification +} + +// Array of protection zone notifications +message ProtectionZoneNotificationList { + repeated ProtectionZoneNotification notifications = 1; // Notification +} + +// Array of user notifications +message UserNotificationList { + repeated UserNotification notifications = 1; // Notification +} + +// Array of safety notifications +message SafetyNotificationList { + repeated Kinova.Api.Common.SafetyNotification notifications = 1; // Notification +} + +// Array of controller notifications +message ControllerNotificationList { + repeated ControllerNotification notifications = 1; // Notifications +} + +// Array of action notifications +message ActionNotificationList { + repeated ActionNotification notifications = 1; // Notification +} + +// Array of robot event notifications +message RobotEventNotificationList { + repeated RobotEventNotification notifications = 1; // Notification +} + +// Array of network event notifications +message NetworkNotificationList { + repeated NetworkNotification notifications = 1; // Notification +} + +// Reference to a specific Mapping +message MappingHandle { + uint32 identifier = 1; // Mapping identifier + fixed32 permission = 2; // Permission of specified mapping entity. Must use 'Kinova.Api.Common.Permission' enum. +} + +// Admissible controller input types +enum ControllerInputType { + UNSPECIFIED_CONTROLLER_INPUT_TYPE = 0; // Unspecified controller input type + ANALOG = 1; // Analog controller input type + DIGITAL = 2; // Digital controller input type +} + +// Admissible controller input behaviors +enum ControllerBehavior { + UNSPECIFIED_CONTROLLER_BEHAVIOR = 0; // Unspecified controller behavior + CONTROLLER_BUTTON_DOWN = 1; // Pushing button down + CONTROLLER_BUTTON_UP = 2; // Releasing button + CONTROLLER_AXIS_POSITIVE = 3; // Positive axis movement + CONTROLLER_AXIS_NEGATIVE = 4; // Negative axis movement + CONTROLLER_BUTTON_CLICK = 5; // Button down and up within X msec +} + +// A safety event (not implemented yet) +message SafetyEvent { + Kinova.Api.Common.SafetyHandle safety_handle = 1; // Safety that caused the event to occur +} + +// A controller event +message ControllerEvent { + ControllerInputType input_type = 1; // Type of controller input that caused the event_identifier + ControllerBehavior behavior = 2; // Controller behavior that occured + uint32 input_identifier = 3; // Controller input that caused the event +} + +// A GPIO event (not implemented yet) +message GpioEvent { + ControllerInputType input_type = 1; // Type of controller input that caused the event_identifier + GpioBehavior behavior = 2; // GPIO behavior that occured + uint32 input_identifier = 3; // GPIO PIN ID that caused the event +} + +// A map event +message MapEvent { + oneof events { + SafetyEvent safety_event = 1; // Mapped safety event (not implemented yet) + GpioEvent gpio_event = 2; // Mapped GPIO event (not implemented yet) + ControllerEvent controller_event = 3; // Mapped controller event + } + string name = 4; // Map event friendly name +} + +// Associates an event to an action +message MapElement { + MapEvent event = 1; // Map event that occured + Action action = 2; // Action to invoke upon event occurence + string name = 3; // Map element friendly name +} + +// Reference to a specific new active map for the specified mapping and map group +message ActivateMapHandle { + MappingHandle mapping_handle = 1; // Mapping that the active map is asked for + MapGroupHandle map_group_handle = 2; // Map group that the active map is asked for (not implemented yet) + MapHandle map_handle = 3; // New active map +} + +// A map as an array of map elements +message Map { + MapHandle handle = 1; // Map handle (do not set on createMap() call) + string name = 2; // Map friendly name + repeated MapElement elements = 3; // Array of map elements +} + +// Reference to a specific map +message MapHandle { + uint32 identifier = 1; // Identifier + fixed32 permission = 2; // Permission of specified map entity. Must use 'Kinova.Api.Common.Permission' enum. +} + +// Array of maps +message MapList { + repeated Map map_list = 1; // map +} + +// Reference to a specific map group (not implemented yet) +message MapGroupHandle { + uint32 identifier = 1; // Identifier + fixed32 permission = 2; // Permission of specified map group entity. Must use 'Kinova.Api.Common.Permission' enum. +} + +/* + * All information about a map group including the list of maps that it contains and its + * relationship versus other map groups (not implemented yet) + */ +message MapGroup { + MapGroupHandle group_handle = 1; // Map group handle (do not set on createMapGroup() call) + string name = 2; // Map group friendly name + MappingHandle related_mapping_handle = 3; // Mapping that this map group belongs to + MapGroupHandle parent_group_handle = 4; // Parent map group (if any) + repeated MapGroupHandle children_map_group_handles = 5; // Children map groups (if any) + repeated MapHandle map_handles = 6; // Array of maps that are included in this map group + string application_data = 7; // Application data (reserved for use by Web App) +} + +// Array of map groups (not implemented yet) +message MapGroupList { + repeated MapGroup map_groups = 1; // Map group +} + +/* + * All information about a mapping including the controller to which it is associated, + * the array of map groups it contains, the currently active map group, the array of maps it contains + * and the currently active map + */ +message Mapping { + MappingHandle handle = 1; // Mapping handle (do not set on createMapping() call) + string name = 2; // Mapping friendly name + uint32 controller_identifier = 3; // Associated controller identifier + MapGroupHandle active_map_group_handle = 4; // Currently active map group (not implemented yet) + repeated MapGroupHandle map_group_handles = 5; // Array of associated map groups (not implemented yet) + MapHandle active_map_handle = 6; // Currently active map + repeated MapHandle map_handles = 7; // Array of associated maps + string application_data = 8; // Application data (reserved for use by Web App) +} + +// Array of mappings +message MappingList { + repeated Mapping mappings = 1; // Mapping +} + +/* + * Admissible Base safeties. + * Used with BaseCyclic.BaseFeedback.[fault_bank_a | fault_bank_b | warning_bank_a | warning_bank_b] + */ +enum SafetyIdentifier { + UNSPECIFIED_BASE_SAFETY_IDENTIFIER = 0; // 0x0 - Unspecified base safety + FIRMWARE_UPDATE_FAILURE = 1; // 0x1 - Firmware update failure + EXTERNAL_COMMUNICATION_ERROR = 2; // 0x2 - External communication error (not implemented yet) + MAXIMUM_AMBIENT_TEMPERATURE = 4; // 0x4 - Maximum ambient temperature reached + MAXIMUM_CORE_TEMPERATURE = 8; // 0x8 - Maximum core temperature reached + JOINT_FAULT = 16; // 0x10 - Joint fault + CYCLIC_DATA_JITTER = 32; // 0x20 - Cyclic data jitter (not implemented yet) + REACHED_MAXIMUM_EVENT_LOGS = 64; // 0x40 - Reached Maximum number of event log entries (not implemented yet) + NO_KINEMATICS_SUPPORT = 128; // 0x80 - No kinematics support (not implemented yet) + ABOVE_MAXIMUM_DOF = 256; // 0x100 - Above maximum DoF + NETWORK_ERROR = 512; // 0x200 - Network error (not implemented yet) + UNABLE_TO_REACH_POSE = 1024; // 0x400 - Unable to reach pose + JOINT_DETECTION_ERROR = 2048; // 0x800 - Joint detection error + NETWORK_INITIALIZATION_ERROR = 4096; // 0x1000 - Network initialization error + MAXIMUM_CURRENT = 8192; // 0x2000 - Maximum current reached + MAXIMUM_VOLTAGE = 16384; // 0x4000 - Maximum voltage reached + MINIMUM_VOLTAGE = 32768; // 0x8000 - Minimum voltage reached + MAXIMUM_END_EFFECTOR_TRANSLATION_VELOCITY = 65536; // 0x10000 - Maximum tool translation velocity reached (not implemented yet) + MAXIMUM_END_EFFECTOR_ORIENTATION_VELOCITY = 131072; // 0x20000 - Maximum tool orientation velocity reached (not implemented yet) + MAXIMUM_END_EFFECTOR_TRANSLATION_ACCELERATION = 262144; // 0x40000 - Maximum tool translation acceleration reached (not implemented yet) + MAXIMUM_END_EFFECTOR_ORIENTATION_ACCELERATION = 524288; // 0x80000 - Maximum tool orientation acceleration reached (not implemented yet) + MAXIMUM_END_EFFECTOR_TRANSLATION_FORCE = 1048576; // 0x100000 - Maximum tool translation force reached (not implemented yet) + MAXIMUM_END_EFFECTOR_ORIENTATION_FORCE = 2097152; // 0x200000 - Maximum tool orientation force reached (not implemented yet) + MAXIMUM_END_EFFECTOR_PAYLOAD = 4194304; // 0x400000 - Maximum tool payload reached (not implemented yet) + EMERGENCY_STOP_ACTIVATED = 8388608; // 0x800000 - Emergency stop activated + EMERGENCY_LINE_ACTIVATED = 16777216; // 0x1000000 - Emergency line activated + INRUSH_CURRENT_LIMITER_FAULT = 33554432; // 0x2000000 - In rush current limiter fault + NVRAM_CORRUPTED = 67108864; // 0x4000000 - NVRAM corrupted (not implemented yet) + INCOMPATIBLE_FIRMWARE_VERSION = 134217728; // 0x8000000 - Incompatible firmware version + POWERON_SELF_TEST_FAILURE = 268435456; // 0x10000000 - Power on seflt test failure + DISCRETE_INPUT_STUCK_ACTIVE = 536870912; // 0x20000000 - Discrete Input stuck active + ARM_INTO_ILLEGAL_POSITION = 1073741824;// 0x40000000 - Arm is in an illegal position (sigularity) +} + +// A 4x4 homogeneous transformation matrix representing the transformation between two reference frames. +message TransformationMatrix { + TransformationRow r0 = 1; // First transformation row + TransformationRow r1 = 2; // Second transformation row + TransformationRow r2 = 3; // Third transformation row + TransformationRow r3 = 4; // Fourth transformation row +} + +// A single row of a 4x4 homogeneous transformation matrix +message TransformationRow { + float c0 = 1; // First column value + float c1 = 2; // Second column value + float c2 = 3; // Third column value + float c3 = 4; // Fourth column value +} + +/* + * A Cartesian tool pose (position and orientation). + * Orientation is defined as a sequence of three Euler angles using z-y-x Tait-Bryan extrinsic convention. + * That is, rotation around fixed X-axis, then rotation around fixed Y-axis, then rotation around fixed Z-axis. + */ +message Pose { + float x = 1; // X position (in meters) + float y = 2; // Y position (in meters) + float z = 3; // Z position (in meters) + float theta_x = 4; // Theta X orientation (in degrees) + float theta_y = 5; // Theta Y orienation (in degrees) + float theta_z = 6; // Theta Z orientation (in degrees) +} +// A Cartesian tool position +message Position { + float x = 1; // X position (in meters) + float y = 2; // Y position (in meters) + float z = 3; // Z position (in meters) +} + +/* + * A Cartesian tool orientation. Defines orientation as sequence of three Euler angles using z-y-x Tait-Bryan extrinsic convention. + * That is, rotation around fixed X-axis, then rotation around fixed Y-axis, then rotation around fixed Z-axis. + */ +message Orientation { + float theta_x = 1; // Theta X orientation (in degrees) + float theta_y = 2; // Theta Y orientation (in degrees) + float theta_z = 3; // Theta Z orientation (in degrees) +} + +// Admissible constraint types that can be applied when controlling a joint in trajectory mode +enum JointTrajectoryConstraintType { + UNSPECIFIED_JOINT_CONSTRAINT = 0; // Unspecified joint constraint + JOINT_CONSTRAINT_DURATION = 1; // Duration constraint (in second) + JOINT_CONSTRAINT_SPEED = 2; // Speed constraint (in meters per second) +} + +// A Cartesian tool speed (translation speed and angular speed) +message CartesianSpeed { + float translation = 1; // Translation speed (in meters per second) + float orientation = 2; // Orientation speed (in degrees per second) +} + +// Cartesian trajectory constraint that can be applied when controlling in Cartesian trajectory mode +message CartesianTrajectoryConstraint { + oneof type { + CartesianSpeed speed = 1; // Speed constraint + float duration = 2; // Duration constraint (in seconds) (not implemented yet) + } +} + +// Joint trajectory constraint that can be applied when controlling a joint in trajectory mode +message JointTrajectoryConstraint { + JointTrajectoryConstraintType type = 1; // Joint trajectory constraint type + float value = 2; // Constraint value (in seconds or in meters per second depending on constraint type) +} + +// Admissible wrench (force) modes +enum WrenchMode { + UNSPECIFIED_WRENCH_MODE = 0; // Unspecified wrench mode + WRENCH_RESTRICTED = 1; // Wrench restricted mode (tool motion is authorized only in the direction of the wrench command) + WRENCH_NORMAL = 2; // Wrench normal mode (tool motion is authorized in any direction) +} + +// A wrench (force and torque) +message Wrench { + float force_x = 1; // Linear X force (Newtons or ratio between -1.0 and 1.0 if used with Joystick command) + float force_y = 2; // Linear Y force (Newtons or ratio between -1.0 and 1.0 if used with Joystick command) + float force_z = 3; // Linear Z force (Newtons or ratio between -1.0 and 1.0 if used with Joystick command) + float torque_x = 4; // Angular X torque (Newton-meters or ratio between -1.0 and 1.0 if used with Joystick command) + float torque_y = 5; // Angular Y torque (Newton-meters or ratio between -1.0 and 1.0 if used with Joystick command) + float torque_z = 6; // Angular Z torque (Newton-meters or ratio between -1.0 and 1.0 if used with Joystick command) +} + +// A twist (linear and angular velocity). +message Twist { + float linear_x = 1; // Linear X velocity (m/s or ratio between -1.0 and 1.0 if used with joystick command) + float linear_y = 2; // Linear Y velocity (m/s or ratio between -1.0 and 1.0 if used with joystick command) + float linear_z = 3; // Linear Z velocity (m/s or ratio between -1.0 and 1.0 if used with joystick command) + float angular_x = 4; // Angular X velocity (deg/s or ratio between -1.0 and 1.0 if used with joystick command) + float angular_y = 5; // Angular Y velocity (deg/s or ratio between -1.0 and 1.0 if used with joystick command) + float angular_z = 6; // Angular Z velocity (deg/s or ratio between -1.0 and 1.0 if used with joystick command) +} + +// An admittance mode +message Admittance { + AdmittanceMode admittance_mode = 1; // mode +} + +// Admissible admittance modes +enum AdmittanceMode { + UNSPECIFIED_ADMITTANCE_MODE = 0; // Unspecified admittance mode + CARTESIAN = 1; // Cartesian admittance mode + JOINT = 2; // Joint admittance mode + NULL_SPACE = 3; // Null space admittance mode + DISABLED = 4; // No admittance +} + +// Cartesian tool pose with specified constraint +message ConstrainedPose { + Pose target_pose = 1; // Cartesian pose + CartesianTrajectoryConstraint constraint = 2; // Constraint to apply to the target pose +} + +// Cartesian tool position with specified constraint +message ConstrainedPosition { + Position target_position = 1; // Cartesian position + CartesianTrajectoryConstraint constraint = 2; // Constraint to apply to the target position +} + +// Cartesian tool orientation with specified constraint +message ConstrainedOrientation { + Orientation target_orientation = 1; // Cartesian orientation + CartesianTrajectoryConstraint constraint = 2; // Constraint to apply to the target orientation +} + +// A wrench command to be applied to the tool +message WrenchCommand { + Kinova.Api.Common.CartesianReferenceFrame reference_frame = 1; // The reference frame used for the wrench command + WrenchMode mode = 2; // Mode in which the command is executed + Wrench wrench = 3; // Wrench value + uint32 duration = 4; // Duration constraint. If not 0, allows to set a limit (in milliseconds) to the WrenchCommand +} + +// A twist command to be applied to the tool +message TwistCommand { + Kinova.Api.Common.CartesianReferenceFrame reference_frame = 1; // The reference frame used for the twist command + Twist twist = 2; // Twist value + uint32 duration = 3; // Duration constrant. If not 0, allows to set a limit (in milliseconds) to the TwistCommand (not implemented yet) +} + +// An array of joint angles values with specified constraint +message ConstrainedJointAngles { + JointAngles joint_angles = 1; // Joint angles values + JointTrajectoryConstraint constraint = 2; // Constraint to apply to all the joint angles (optional) +} + +// A single joint angle value with specifed constraint +message ConstrainedJointAngle { + uint32 joint_identifier = 1; // Joint identifier (use device_identifier) + float value = 2; // Joint value (in degrees) + JointTrajectoryConstraint constraint = 3; // Constraint to apply to the joint angle (optional) +} + +// An array of joint angles +message JointAngles { + repeated JointAngle joint_angles = 1; // Array of joint angles +} + +// Angle value of a specific joint +message JointAngle { + uint32 joint_identifier = 1; // Joint identifier + float value = 2; // Position (in degrees) +} + +// An array of joints speeds +message JointSpeeds { + repeated JointSpeed joint_speeds = 1; // Array of joint speeds + uint32 duration = 2; // Duration constraint. If not 0, allows to set a limit (in seconds) common to every joint specified in 'joint_speeds' (not implemented yet) +} + +// Speed of a specific joint +message JointSpeed { + uint32 joint_identifier = 1; // Joint identifier + float value = 2; // Joint speed (in degrees per second) + uint32 duration = 3; // Duration constraint. If not 0, allows to set a limit (in seconds) to the JointsSpeed (not implemented yet) +} + +// An array of joint torques +message JointTorques { + repeated JointTorque joint_torques = 1; // Array of joint torque. + uint32 duration = 2; // Duration constraint. If not 0, allows to set a limit (in seconds) common to every joint specified in 'joint_torques' (not implemented yet) +} + +// joint torque for a specified joint +message JointTorque { + uint32 joint_identifier = 1; // Joint identifier + float value = 2; // Joint speed (in Newton*meters) + uint32 duration = 3; // Duration constraint. If not 0, allows to set a limit (in seconds) to the JointTorque (not implemented yet) +} + +// Admissible gripper control mode +enum GripperMode { + UNSPECIFIED_GRIPPER_MODE = 0; // Unspecified gripper mode + GRIPPER_FORCE = 1; // Force control (in Newton) (not implemented yet) + GRIPPER_SPEED = 2; // Speed control (in meters per second) + GRIPPER_POSITION = 3; // Position control (in meters) +} + +// A command to control the gripper movement +message GripperCommand { + GripperMode mode = 1; // Mode in which to control the gripper + /* + * In position, admissible values for each finger is between 0 and 1.0, where 0 is fully open and 1.0 is fully closed. + * In speed, admissible values for each finger is between -1.0 and 1.0, where 1.0 corresponds + * to maximum opening speed and -1.0 corresponds to maximum closing speed. + */ + Gripper gripper = 2; // Gripper movement values + uint32 duration = 3; // Duration constraint. If not 0, allows to set a limit (in seconds) to the GripperCommand +} + +// Request to apply a specific gripper mode +message GripperRequest { + GripperMode mode = 1; // Mode for which the gripper movement status is requested +} + +// Gripper movement composed of a series of fingers movement +message Gripper { + repeated Finger finger = 1; // Finger movements +} + +// Movement of a specified gripper finger +message Finger { + uint32 finger_identifier = 1; // Finger identifier + + /* + * In position, admissible values for each finger is between 0 and 1.0, where 0 is fully open and 1.0 is fully closed. + * In speed or torque, admissible values for each finger is between -1.0 and 1.0, where 1.0 corresponds + * to maximum opening speed or torque and -1.0 corresponds to maximum closing speed or torque. + */ + float value = 2; +} + + +// Admissible map navigation directions +enum NavigationDirection { + UNSPECIFIED_NAVIGATION_DIRECTION = 0; // Unspecified navigation direction + NEXT = 1; // Go to next map + UP = 2; // Go to parent map group (not implemented yet) + DOWN = 3; // Go to children map group (not implemented yet) + PREVIOUS = 4; // Go to previous map +} + +// Admissible joint navigation directions +enum JointNavigationDirection { + UNSPECIFIED_JOINT_NAVIGATION_DIRECTION = 0; // Unspecified joint navigation direction + JOINT_NEXT = 1; // Go to next joint + JOINT_PREVIOUS = 2; // Go to previous joint +} + +// Admissible sound types (not implemented yet) +enum SoundType { + UNSPECIFIED_SOUND_TYPE = 0; // Unspecified sound types + BIP_SERIES = 1; // Bip series sound type + SINGLE_BIP = 2; // Single bin sound type +} + +// Admissible LED states (not implemented yet) +enum LedState { + UNSPECIFIED_LED_STATE = 0; // Unspecified LED state + LED_OFF = 1; // LED is off + LED_PULSE = 2; // LED is in pulse state + LED_ON = 3; // LED is one +} + +// Admissible GPIO behavior (not implemented yet) +enum GpioBehavior { + UNSPECIFIED_GPIO_BEHAVIOR = 0; // Unspecified GPIO behavior + GPIO_FALLING = 1; // Falling edge + GPIO_RISING = 2; // Rising edge + GPIO_PULSE_LOW = 3; // Sequence of HIGH - LOW - HIGH + GPIO_PULSE_HIGH = 4; // Sequence of LOW - HIGH - LOW +} + +// Available GPIO PIN (not implemented yet) +enum Gen3GpioPinId { + UNSPECIFIED_PIN = 0; // Unspecified PIN ID + GPIO_PIN_B = 1; // GPIO PIN B + GPIO_PIN_C = 2; // GPIO PIN C + GPIO_PIN_D = 3; // GPIO PIN D + GPIO_PIN_E = 4; // GPIO PIN E + GPIO_PIN_G = 5; // GPIO PIN G + GPIO_PIN_H = 6; // GPIO PIN H + GPIO_PIN_I = 7; // GPIO PIN I + GPIO_PIN_K = 8; // GPIO PIN K + GPIO_PIN_N = 9; // GPIO PIN N + GPIO_PIN_O = 10; // GPIO PIN O + GPIO_PIN_S = 11; // GPIO PIN S + GPIO_PIN_T = 12; // GPIO PIN T +} + +// Identifies the system time (not implemented yet) +message SystemTime { + uint32 sec = 1; // Seconds after the minute(0-59) + uint32 min = 2; // Minutes after the hour (0-59) + uint32 hour = 3; // Hours since midnight (0-23) + uint32 mday = 4; // Day of the month (1-31) + uint32 mon = 5; // Months since January (0-11) + uint32 year = 6; // Years since 1900 +} + +// Admissible XBOX360 digital inputs +enum Xbox360DigitalInputIdentifier { + UNSPECIFIED_XBOX360_DIGITAL = 0; // Unspecified digital input + XBOX360_PAD_UP = 1; // Pad up input + XBOX360_PAD_DOWN = 2; // Pad down input + XBOX360_PAD_LEFT = 3; // Pad left input + XBOX360_PAD_RIGHT = 4; // Pad right input + XBOX360_FILE_BUTTON_START = 5; // File button start input + XBOX360_DOCUMENT_BUTTON_BACK = 6; // Document button back input + XBOX360_LEFT_THUMB_BUTTON = 7; // Left thumb button input + XBOX360_RIGHT_THUMB_BUTTON = 8; // Right thumb button input + XBOX360_LEFT_SHOULDER = 9; // Left shoulder input + XBOX360_RIGHT_SHOULDER = 10; // Right shoulder input + XBOX360_BUTTON_A = 13; // Button A input + XBOX360_BUTTON_B = 14; // Button B input + XBOX360_BUTTON_X = 15; // Button X input + XBOX360_BUTTON_Y = 16; // Button Y input +} + +// Admissible XBOX360 analog inputs +enum Xbox360AnalogInputIdentifier { + UNSPECIFIED_XBOX360_ANALOG = 0; // Unspecified analog input + XBOX360_THUMB_LEFT_X = 1; // Thumb left X input + XBOX360_THUMB_LEFT_Y = 2; // Thumb left Y input + XBOX360_THUMB_RIGHT_X = 3; // Thumb right X input + XBOX360_THUMB_RIGHT_Y = 4; // Thumb right Y input + XBOX360_TRIGGER_LEFT = 5; // Trigger left input + XBOX360_TRIGGER_RIGHT = 6; // Trigger right input +} + +// Admissible Wrist digital inputs +enum WristDigitalInputIdentifier { + UNSPECIFIED_WRIST_DIGITAL = 0; // Unspecified digital input + WRIST_BUTTON_1 = 1; // Button 1 input + WRIST_BUTTON_2 = 2; // Button 2 input + WRIST_BUTTON_BOTH = 3; // Button 1 + Button 2 combo +} + +// Controller configuration mode information +message ControllerConfigurationMode { + bool enable = 1; // Enable controller configuration mode. Set to true to configure controllers, false for normal operation +} + +// Controller configuration information +message ControllerConfiguration { + ControllerHandle handle = 1; // Controller identifier + string name = 2; // Controller friendly name + MappingHandle active_mapping_handle = 3; // Mapping that is active on this controller + string analog_input_identifier_enum = 4; // Name that identifies the enum used to interpret the ‘analog_input_identifier’ field (for example in ControllerEvent). Thus 'analog_input_identifier_enum' shall take the name of an existing enum (ex. Xbox360AnalogInputIdentifier) + string digital_input_identifier_enum = 5; // Name that identifies the enum used to interpret the ‘digital_input_identifier’ field (for example in ControllerEvent). Thus 'digital_input_identifier_enum' shall take the name of an existing enum (ex. Xbox360DigitalInputIdentifier, WristDigitalInputIdentifier) +} + +// Controller configuration information for multiple controllers +message ControllerConfigurationList { + repeated ControllerConfiguration controller_configurations = 1; // List of controller configurations +} + +// A count of the number of actuators in the robot +message ActuatorInformation { + uint32 count = 1; // Number of actuators +} + +// Information about the arm state +message ArmStateInformation { + Kinova.Api.Common.ArmState active_state = 1; // Arm active state + Kinova.Api.Common.Connection connection = 2; // Connection information of the last processed command which triggered an arm state change +} + +// Notification about a single arm state event +message ArmStateNotification { + Kinova.Api.Common.ArmState active_state = 1; // New arm state + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.Connection connection = 3; // Connection that caused the arm state event +} + +// Admissible capacitive sensor modes +enum CapSenseMode +{ + RESERVED = 0; // Reserved, do not use + INACTIVE = 1; // Cap sensor is inactive + ACTIVE_AUTO_THRESHOLD = 2; // Cap sensor is active in automatic threshold mode + ACTIVE_NOISE_ATT = 4; // Cap sensor is active with noise mitigation enabled + ACTIVE_NORMAL = 5; // Cap sensor is active in normal mode + CONFIGURATION = 6; // Configuration mode +} + +// Capacitive sensor configuration information +message CapSenseConfig +{ + uint32 identifier = 1; // MessageId + CapSenseMode mode = 2; // Operational mode of the sensor + float threshold_a = 3; // Threshold of the sensor A (successive detection count to trigger a change of state) + float threshold_b = 4; // Threshold of the sensor B (successive detection count to trigger a change of state) + float sensitivity_a = 5; // Sensitivity of the sensor A (picofarad) + float sensitivity_b = 6; // Sensitivity of the sensor B (picofarad) +} + +// An array of configuration information for different bridges. +message BridgeList { + repeated BridgeConfig bridgeConfig = 1; // List of bridge configuration. +} + +// The result of an operation on a specific bridge +message BridgeResult +{ + BridgeIdentifier bridge_id = 1; // ID of the bridge on which operation was performed + BridgeStatus status = 2; // Result code of operation. +} + +// Bridge identifier +message BridgeIdentifier { + uint32 bridge_id = 1; // Unique bridge identifier. +} + +// Bridge configuration information. It is used to either create a bridge or to retrieve information about an existing bridge +message BridgeConfig { + uint32 device_identifier = 1; // Identifier of the device to which the bridge is connecting. + BridgeType bridgetype = 2; // Bridge type. + BridgePortConfig port_config = 3; // Port configuration. If used to enable port bridging, it is optional. If no port config is given defaults for bridge type is used. + BridgeIdentifier bridge_id = 4; // Bridge identifier. Not used when creating bridge. It is used when retrieving configuration. +} + +// Port configuration information for a TCP port bridge +message BridgePortConfig +{ + uint32 target_port = 1; // Port on target device. + uint32 out_port = 2; // Port exposed on base's external interface +} + +// Bridge operation status +enum BridgeStatus { + BRIDGE_STATUS_OK = 0; // No error encountered. + BRIDGE_STATUS_OUTP_UNAVAILABLE = 1; // Requested output port unavailable. + BRIDGE_STATUS_UNKNOWN_DEVID = 2; // Given device identifier is unknown (no device associated with it). + BRIDGE_STATUS_UNKNOWN_BRIDGE_TYPE = 3; // Unknown bridge type used. + BRIDGE_STATUS_NOT_FOUND = 4; // Requested bridge not found. + BRIDGE_STATUS_NOT_INITIALIZED = 5; // Bridge manager not initialized. + BRIDGE_STATUS_UNKNOWN = 6; // Unknown error. +} + +// Type of port forward bridge to create +enum BridgeType { + BRIDGE_TYPE_UNSPECIFIED = 0; // Unspecified Type (custom bridge) + BRIDGE_TYPE_UART = 1; // Bridge to uart bridge TCP port. + BRIDGE_TYPE_TELNET = 2; // Bridge to telnet port +} + +// Pre-computed joint trajectory subject to specified continuity constraints. The starting point of the trajectory must have an elapsed time of 0 ms and the angular values must reflect the current state of the robot. The robot control libraries will validate the trajectory fulfills the specified continuity constraints before playing the trajectory. +message PreComputedJointTrajectory { + TrajectoryContinuityMode mode = 1; // Trajectory continuity mode + repeated PreComputedJointTrajectoryElement trajectory_elements = 2; // List of pre-computed elements composing the trajectory. +} + +// Set of angle, speed, acceleration, and elapsed time values for each joint for a given 1 ms interval. A PreComputedJointTrajectory is made up of a series of these elements. +message PreComputedJointTrajectoryElement { + repeated float joint_angles = 1; // Angles values for all joints (in degrees) + repeated float joint_speeds = 2; // Speed values for all joints (in degrees per second) + repeated float joint_accelerations = 3; // Acceleration values for all joints (in degrees per second^2) + float time_from_start = 4; // Absolute elaspsed time since initial point (in seconds) +} + +// Admissible trajectory continuity mode +enum TrajectoryContinuityMode +{ + TRAJECTORY_CONTINUITY_MODE_UNSPECIFIED = 0; // Unspecified continuity + TRAJECTORY_CONTINUITY_MODE_POSITION = 1; // Position continuity only + TRAJECTORY_CONTINUITY_MODE_SPEED = 2; // Position and speed continuity + TRAJECTORY_CONTINUITY_MODE_ACCELERATION = 3; // Position, speed and acceleration continuity +} + +// Trajectory validation error types +enum TrajectoryErrorType +{ + TRAJECTORY_ERROR_TYPE_UNSPECIFIED = 0; // Unspecified error type + TRAJECTORY_ERROR_TYPE_OUTSIDE_WORKSPACE = 1; // The trajectory point is outside robot workspace + TRAJECTORY_ERROR_TYPE_ACTUATOR_COUNT_MISMATCH = 2; // There is an actuator count mismatch with the robot + TRAJECTORY_ERROR_TYPE_INVALID_DURATION = 3; // The trajectory has an invalid duration + TRAJECTORY_ERROR_TYPE_ZERO_DISTANCE = 4; // The trajectory does not move the robot because the delta is either zero or too small + TRAJECTORY_ERROR_TYPE_INVALID_SPEED = 5; // The speed for a trajectory point for an actuator is invalid + TRAJECTORY_ERROR_TYPE_LARGE_SPEED = 6; // The speed for a trajectory point for an actuator exceeds its limit + TRAJECTORY_ERROR_TYPE_INVALID_ACCELERATION = 7; // The acceleration for a trajectory point for an actuator is invalid + TRAJECTORY_ERROR_TYPE_INVALID_TIME_STEP = 8; // The time step for a trajectory point is invalid + TRAJECTORY_ERROR_TYPE_LARGE_SIZE = 9; // The trajectory is too large + TRAJECTORY_ERROR_TYPE_WRONG_MODE = 10; // The robot is not currently in Trajectory Control mode + TRAJECTORY_ERROR_TYPE_JOINT_POSITION_LIMIT = 11; // The position limit for a trajectory point for an actuator is exceeded + TRAJECTORY_ERROR_TYPE_FILE_ERROR = 12; // An internal file error was encountered + TRAJECTORY_ERROR_TYPE_NO_FILE_IN_MEMORY = 13; // An internal file memory error was encountered + TRAJECTORY_ERROR_TYPE_INDEX_OUT_OF_TRAJ = 14; // The index for a trajectory point is invalid + TRAJECTORY_ERROR_TYPE_ALREADY_RUNNING = 15; // A trajectory is already running + TRAJECTORY_ERROR_TYPE_WRONG_STARTING_POINT = 16; // The difference between the trajectory's starting point and the current position is too large + TRAJECTORY_ERROR_TYPE_CARTESIAN_CANNOT_START = 17; // The cartesian trajectory is not able to start + TRAJECTORY_ERROR_TYPE_WRONG_STARTING_SPEED = 18; // The difference between the trajectory's starting speed and the current speed is too large + TRAJECTORY_ERROR_TYPE_INVALID_POSITION = 19; // The position for a trajectory point for an actuator is invalid +} + +// Trajectory validation error identifiers +enum TrajectoryErrorIdentifier +{ + TRAJECTORY_ERROR_IDENTIFIER_UNSPECIFIED = 0; // Unspecified error identifier + TRAJECTORY_ERROR_IDENTIFIER_UNAPPLICABLE = 1; // No identifier required for this error + TRAJECTORY_ERROR_IDENTIFIER_TIME = 2; // Time validation failed + TRAJECTORY_ERROR_IDENTIFIER_POSITION = 3; // Position validation failed + TRAJECTORY_ERROR_IDENTIFIER_VELOCITY = 4; // Velocity validation failed + TRAJECTORY_ERROR_IDENTIFIER_ACCELERATION = 5; // Acceleration validation failed +} + +// Details for a single trajectory validation error +message TrajectoryErrorElement +{ + TrajectoryErrorType error_type = 1; // Error type + TrajectoryErrorIdentifier error_identifier = 2; // Error identifier + float error_value = 3; // Erroneous value + float min_value = 4; // Minimum permitted value + float max_value = 5; // Maximum permitted value + uint32 index = 6; // Actuator index + string message = 7; // Clarification message for the error +} + +// Report collecting information on different validation errors for a particular trajectory +message TrajectoryErrorReport +{ + repeated TrajectoryErrorElement trajectory_error_elements = 1; +} + +// Firmware bundle versions including main firmware bundle version and components versions +message FirmwareBundleVersions +{ + string main_bundle_version = 1; // Version of the main bundle + repeated FirmwareComponentVersion components_versions = 2; // List containing all components of the bundle +} + +// Individual component with its version +message FirmwareComponentVersion +{ + string name = 1; // Name of the component + string version = 2; // Version of the component + uint32 device_id = 3; // Device id of the component +} diff --git a/ros_kortex/kortex_driver/protos/BaseCyclic.proto b/ros_kortex/kortex_driver/protos/BaseCyclic.proto new file mode 100644 index 0000000..c4f9636 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/BaseCyclic.proto @@ -0,0 +1,172 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; +import public "InterconnectCyclicMessage.proto"; + +package Kinova.Api.BaseCyclic; + +// Service to exchange cyclic data with base +service BaseCyclic { //@PROXY_ID=3 @ERROR=Kinova.Api.Error + + // Sends a command to actuators and interface and returns feedback from base, actuators, and interface on actual status + rpc Refresh (Command) returns (Feedback); //@RPC_ID=1 + + // Sends a command to actuators and interface without receiving feedback + rpc RefreshCommand (Command) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Obtains feedback from base, actuators, and interface on their status + rpc RefreshFeedback (Kinova.Api.Common.Empty) returns (Feedback); //@RPC_ID=3 + + // Retrieves custom data + rpc RefreshCustomData (CustomData) returns (CustomData); //@RPC_ID=4 +} + +// Identifies BaseCyclic current version +enum ServiceVersion +{ + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Defines an actuator command +message ActuatorCommand // @NOTE=copied from ActuatorCyclic.proto +{ + fixed32 command_id = 1; // Command ID (first 2 bytes: device ID, last 2 bytes: sequence number) + fixed32 flags = 2; // Flags + float position = 3; // Desired position of the actuator (in degrees) + float velocity = 4; // Desired velocity of the actuator (in degrees per second) + float torque_joint = 5; // Desired torque of the actuator (in Newton * meters) + float current_motor = 6; // Desired current of the motor (in Amperes) +} + +// Defines the feedback provided by an actuator +message ActuatorFeedback // @NOTE=copied from ActuatorCyclic.proto +{ + fixed32 command_id = 1; // Command ID (first 2 bytes: device ID, last 2 bytes: sequence number) + fixed32 status_flags = 2; // Status flags + fixed32 jitter_comm = 3; // Jitter from the communication (in microseconds) + float position = 4; // Position of the actuator (in degrees) + float velocity = 5; // Velocity of the actuator (in degrees per second) + float torque = 6; // Torque of the actuator (in Newton * meters) + float current_motor = 7; // Current of the motor (in Amperes) + float voltage = 8; // Voltage of the main board (in Volts) + float temperature_motor = 9; // Motor temperature (maximum of the three (3) phase temperatures in °C) + float temperature_core = 10; // Microcontroller temperature (in degrees Celsius) + fixed32 fault_bank_a = 11; // Fault bank A + fixed32 fault_bank_b = 12; // Fault bank B + fixed32 warning_bank_a = 13; // Warning bank A + fixed32 warning_bank_b = 14; // Warning bank B +} + +// Custom development data from an actuator, content varies according to debug needs +message ActuatorCustomData // @NOTE=copied from ActuatorCyclic.proto +{ + fixed32 command_id = 1; // Command ID (first 2 bytes: device ID, last 2 bytes: sequence number) + fixed32 custom_data_0 = 2; // Custom data word 0 + fixed32 custom_data_1 = 3; // Custom data word 1 + fixed32 custom_data_2 = 4; // Custom data word 2 + fixed32 custom_data_3 = 5; // Custom data word 3 + fixed32 custom_data_4 = 6; // Custom data word 4 + fixed32 custom_data_5 = 7; // Custom data word 5 + fixed32 custom_data_6 = 8; // Custom data word 6 + fixed32 custom_data_7 = 9; // Custom data word 7 + fixed32 custom_data_8 = 10; // Custom data word 8 + fixed32 custom_data_9 = 11; // Custom data word 9 + fixed32 custom_data_10 = 12; // Custom data word 10 + fixed32 custom_data_11 = 13; // Custom data word 11 + fixed32 custom_data_12 = 14; // Custom data word 12 + fixed32 custom_data_13 = 15; // Custom data word 13 + fixed32 custom_data_14 = 16; // Custom data word 14 + fixed32 custom_data_15 = 17; // Custom data word 15 +} + +// Defines the feedback provided by the base +message BaseFeedback +{ + uint32 active_state_connection_identifier = 1; // Connection identifier of the last processed command which triggered an arm state change + Kinova.Api.Common.ArmState active_state = 2; // Active state of the arm + float arm_voltage = 3; // Arm voltage (in Volts) + float arm_current = 4; // Arm current (in Amperes) + float temperature_cpu = 5; // CPU temperature (in degree Celsius) + float temperature_ambient = 6; // Ambient temperature (in degree Celsius) + float imu_acceleration_x = 7; // IMU Measured acceleration (X-Axis) of the base (in meters per second squared) + float imu_acceleration_y = 8; // IMU Measured acceleration (Y-Axis) of the base (in meters per second squared) + float imu_acceleration_z = 9; // IMU Measured acceleration (Z-Axis) of the base (in meters per second squared) + float imu_angular_velocity_x = 10; // IMU Measured angular velocity (X-Axis) of the base (in degrees per second) + float imu_angular_velocity_y = 11; // IMU Measured angular velocity (Y-Axis) of the base (in degrees per second) + float imu_angular_velocity_z = 12; // IMU Measured angular velocity (Z-Axis) of the base (in degrees per second) + float tool_pose_x = 13; // Measured Cartesian position (X-Axis) of the tool (in meters) + float tool_pose_y = 14; // Measured Cartesian position (Y-Axis) of the tool (in meters) + float tool_pose_z = 15; // Measured Cartesian position (Z-Axis) of the tool (in meters) + float tool_pose_theta_x = 16; // Measured Cartesian orientation (X-Axis) of the tool (in degrees) + float tool_pose_theta_y = 17; // Measured Cartesian orientation (Y-Axis) of the tool (in degrees) + float tool_pose_theta_z = 18; // Measured Cartesian orientation (Z-Axis) of the tool (in degrees) + float tool_twist_linear_x = 19; // Measured Cartesian linear velocity (X-Axis) of the tool (in meters per second) + float tool_twist_linear_y = 20; // Measured Cartesian linear velocity (Y-Axis) of the tool (in meters per second) + float tool_twist_linear_z = 21; // Measured Cartesian linear velocity (Z-Axis) of the tool (in meters per second) + float tool_twist_angular_x = 22; // Measured Cartesian angular velocity (X-Axis) of the tool (in degrees per second) + float tool_twist_angular_y = 23; // Measured Cartesian angular velocity (Y-Axis) of the tool (in degrees per second) + float tool_twist_angular_z = 24; // Measured Cartesian angular velocity (Z-Axis) of the tool (in degrees per second) + float tool_external_wrench_force_x = 25; // Computed force in X-Axis from external wrench (in Newton) + float tool_external_wrench_force_y = 26; // Computed force in Y-Axis from external wrench (in Newton) + float tool_external_wrench_force_z = 27; // Computed force in Z-Axis from external wrench (in Newton) + float tool_external_wrench_torque_x = 28; // Computed torque about X-axis from external wrench (in Newton-meters) + float tool_external_wrench_torque_y = 29; // Computed torque about Y-axis from external wrench (in Newton-meters) + float tool_external_wrench_torque_z = 30; // Computed torque about Z-axis from external wrench (in Newton-meters) + fixed32 fault_bank_a = 31; // The arm fault flags bank A (0 if no fault) see Base.SafetyIdentifier + fixed32 fault_bank_b = 32; // The arm fault flags bank B (0 if no fault) see Base.SafetyIdentifier + fixed32 warning_bank_a = 33; // The arm warning flags bank A (0 if no warning) see Base.SafetyIdentifier + fixed32 warning_bank_b = 34; // The arm warning flags bank B (0 if no warning) see Base.SafetyIdentifier + float commanded_tool_pose_x = 35; // Commanded Cartesian position (X-Axis) of the tool (in meters) + float commanded_tool_pose_y = 36; // Commanded Cartesian position (Y-Axis) of the tool (in meters) + float commanded_tool_pose_z = 37; // Commanded Cartesian position (Z-Axis) of the tool (in meters) + float commanded_tool_pose_theta_x = 38; // Commanded Cartesian orientation (X-Axis) of the tool (in degrees) + float commanded_tool_pose_theta_y = 39; // Commanded Cartesian orientation (Y-Axis) of the tool (in degrees) + float commanded_tool_pose_theta_z = 40; // Commanded Cartesian orientation (Z-Axis) of the tool (in degrees) +} + +// Custom development data, content varies according to debug needs +message CustomData +{ + fixed32 frame_id = 1; // Frame ID + fixed32 custom_data_0 = 2; // Custom data word 0 + fixed32 custom_data_1 = 3; // Custom data word 1 + fixed32 custom_data_2 = 4; // Custom data word 2 + fixed32 custom_data_3 = 5; // Custom data word 3 + fixed32 custom_data_4 = 6; // Custom data word 4 + fixed32 custom_data_5 = 7; // Custom data word 5 + fixed32 custom_data_6 = 8; // Custom data word 6 + fixed32 custom_data_7 = 9; // Custom data word 7 + repeated ActuatorCustomData actuators_custom_data = 10; // Actuator custom data (repeated) + Kinova.Api.InterconnectCyclic.CustomData interconnect_custom_data = 11; // Interconnect custom data +} + + +// Defines a command provided to robot devices (actuators and interface) +message Command +{ + fixed32 frame_id = 1; // Frame ID + repeated ActuatorCommand actuators = 2; // Actuator command (repeated) + Kinova.Api.InterconnectCyclic.Command interconnect = 3; // Interface command +} + +// Defines the feedback provided by robot devices (base, actuators and interface) +message Feedback +{ + fixed32 frame_id = 1; // Frame ID + BaseFeedback base = 2; // Base feedback + repeated ActuatorFeedback actuators = 3; // Actuator feedback + Kinova.Api.InterconnectCyclic.Feedback interconnect = 4; // Interface feedback +} diff --git a/ros_kortex/kortex_driver/protos/Common.proto b/ros_kortex/kortex_driver/protos/Common.proto new file mode 100644 index 0000000..97f5ab7 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/Common.proto @@ -0,0 +1,332 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +package Kinova.Api.Common; + +// Admissible device types +enum DeviceTypes { + UNSPECIFIED_DEVICE_TYPE = 0; // Unspecified device type + BASE = 1; // Base module + VISION = 2; // Vision module + BIG_ACTUATOR = 3; // Big actuator module + SMALL_ACTUATOR = 4; // Small actuator module + INTERCONNECT = 5; // Interface module + GRIPPER = 6; // Gripper module + MEDIUM_ACTUATOR = 7; // Medium actuator module + XBIG_ACTUATOR = 8; // XBig actuator module +} + +// Reference to a specific device +message DeviceHandle { + DeviceTypes device_type = 1; // Device type + uint32 device_identifier = 2; // Unique device identifier (used with other services) + uint32 order = 3; // Unique value indicating the order of that device versus the others to facilitate representation +} + +// Admissible safety statuses +enum SafetyStatusValue { + SAFETY_STATUS_UNSPECIFIED = 0; // Unspecified safety status + SAFETY_STATUS_WARNING = 1; // Warning safety reached + SAFETY_STATUS_ERROR = 2; // Error safety reached + SAFETY_STATUS_NORMAL = 3; // Safety is off +} + +// Admissible permissions. Used as bitfields +enum Permission { + NO_PERMISSION = 0; // No permission + READ_PERMISSION = 1; // Read permission. Refers to an entity that can be read + UPDATE_PERMISSION = 2; // Update permission. Refers to an entity that can be modified + DELETE_PERMISSION = 4; // Delete permission. Refers to an entity that can be deleted +} + +// Admissible notification types +enum NotificationType { + NOTIFICATION_TYPE_UNSPECIFIED = 0; // Unspecified notification + NOTIFICATION_TYPE_THRESHOLD = 1; // Threshold notification. Refers to a notification sent beyond a specific threshold (not implemented yet) + NOTIFICATION_TYPE_FIX_RATE = 2; // Fix rate notification. Refers to a notification sent at a predetermined fix rate (not implemented yet) + NOTIFICATION_TYPE_EVENT = 3; // Event type notification. Refers to a notification sent in response to an event +} + +// Admissible units used throughout API methods +enum Unit { + UNSPECIFIED_UNIT = 0; // Unspecified unit + CELSIUS = 1; // Degree Celsius + AMPERE = 2; // Ampere + VOLT = 3; // Volt + METER_PER_SECOND = 4; // Meter per second + DEGREE_PER_SECOND = 5; // Degree per second + METER_PER_SECOND_2 = 6; // Meter per second squared + DEGREE_PER_SECOND_2 = 7; // Degree per second squared + NEWTON = 8; // Newton + NEWTON_METER =9; // Newton * meter + KILOGRAM = 10; // Kilogram + DEGREE = 11; // Degree + TICK = 12; // Tick + DEGREE_PER_MILLISECOND = 13;// Degre per millisecond +} + +// Message used when no information needs to be exchanged between client application and robot, and vice versa +message Empty { +} + +// Specifies options associated to a notification +message NotificationOptions { + NotificationType type = 1; // Type of notification + uint32 rate_m_sec = 2; // Rate value (in meters per second) (if applicable) + float threshold_value = 3; // Threshold value (if applicable) +} + +// Reference to a specific safety +message SafetyHandle { + uint32 identifier = 1; // Safety identifier +} + +// Reference to a specific notification topic +message NotificationHandle { + uint32 identifier = 1; // Notification identifier +} + +// Notification about a single safety event +message SafetyNotification { + SafetyHandle safety_handle = 1; // Safety handle + SafetyStatusValue value = 2; // New safety status + Timestamp timestamp = 3; // Event timestamp + UserProfileHandle user_handle = 4; // User that caused the safety event + Connection connection = 5; // Connection that caused the safety event +} + +// Timestamp based on Epoch (00:00:00 Thursday, January 1, 1970) +message Timestamp { + uint32 sec = 1; // Number of seconds that have elapsed since Epoch + uint32 usec = 2; // Number of microseconds that have elapsed since the last second (0-999999) +} + +// Reference to a user profile +message UserProfileHandle { + uint32 identifier = 1; // User profile identifier + fixed32 permission = 2; // Must use 'Permission' as bitwise +} + +// Connection between a user and the robot +message Connection { + UserProfileHandle user_handle = 1; // User profile handle, or set to zero if no user logged in + string connection_information = 2; // Connection info (e.g. IP address with port number) + uint32 connection_identifier = 3; // Connection identifier +} + +// Admissible robot arm states +enum ArmState +{ + ARMSTATE_UNSPECIFIED = 0; // Unspecified arm state + ARMSTATE_BASE_INITIALIZATION = 1; // Cannot be reported as the Base initialization must be completed before allowing user connection + ARMSTATE_IDLE = 2; // Base initialization succeeded + ARMSTATE_INITIALIZATION = 3; // Arm is being initialized + ARMSTATE_IN_FAULT = 4; // Arm is in fault + ARMSTATE_MAINTENANCE = 5; // Arm is in maintenance + ARMSTATE_SERVOING_LOW_LEVEL = 6; // Arm is in low-level servoing mode + ARMSTATE_SERVOING_READY = 7; // Arm is ready to be controlled + ARMSTATE_SERVOING_PLAYING_SEQUENCE = 8; // Arm is currently being controlled via a sequence + ARMSTATE_SERVOING_MANUALLY_CONTROLLED = 9; // Arm is currently being controlled manually + ARMSTATE_RESERVED = 255; // For debugging, this state must never be reported outside the base. this means that a state is not mapped correctly +} + +// UART configuration details +message UARTConfiguration { + uint32 port_id = 1; // UART port identification + bool enabled = 2; // True if UART device is enabled, false otherwise + UARTSpeed speed = 3; // Speed selection + UARTWordLength word_length = 4; // Word length + UARTStopBits stop_bits = 5; // Stop bits + UARTParity parity = 6; // Parity mode +} + +// UART port id identification +message UARTDeviceIdentification { + uint32 port_id = 1; // UART device port id +} + +// Admissible UART baudrates +enum UARTSpeed { + UART_SPEED_UNSPECIFIED = 0; // Unspecified UART speed + UART_SPEED_4800 = 1; // 4800 bps + UART_SPEED_9600 = 2; // 9600 bps + UART_SPEED_19200 = 3; // 19200 bps + UART_SPEED_38400 = 4; // 38400 bps + UART_SPEED_57600 = 5; // 57600 bps + UART_SPEED_115200 = 6; // 115200 bps + UART_SPEED_230400 = 7; // 230400 bps + UART_SPEED_460800 = 8; // 460800 bps + UART_SPEED_921600 = 9; // 921600 bps + UART_SPEED_1382400 = 10; // 1382400 bps + UART_SPEED_1612800 = 11; // 1612800 bps + UART_SPEED_1843200 = 12; // 1843200 bps + UART_SPEED_2073600 = 13; // 2073600 bps + UART_SPEED_2188800 = 14; // 2188800 bps + UART_SPEED_2246400 = 15; // 2246400 bps +} + +// Admissible UART word lengths +enum UARTWordLength { + UART_WORD_LENGTH_UNSPECIFIED = 0; // Unspecified UART word length + UART_WORD_LENGTH_7 = 1; // 7 bits + UART_WORD_LENGTH_8 = 2; // 8 bits + UART_WORD_LENGTH_9 = 3; // 9 bits +} + +// Admissible UART stop bits +enum UARTStopBits { + UART_STOP_BITS_UNSPECIFIED = 0; // Unspecified UART stop bits + UART_STOP_BITS_0_5 = 1; // 0.5 stop bit + UART_STOP_BITS_1 = 2; // 1 stop bit + UART_STOP_BITS_1_5 = 3; // 1.5 stop bits + UART_STOP_BITS_2 = 4; // 2 stop bits +} + +// Admissible UART parity mode +enum UARTParity { + UART_PARITY_UNSPECIFIED = 0; // Unspecified UART parity + UART_PARITY_NONE = 1; // No parity + UART_PARITY_ODD = 2; // Odd parity + UART_PARITY_EVEN = 3; // Even parity +} + +// Admissible Cartesian reference frame modes +enum CartesianReferenceFrame { + CARTESIAN_REFERENCE_FRAME_UNSPECIFIED = 0; // Unspecified Cartesian reference frame + CARTESIAN_REFERENCE_FRAME_MIXED = 1; // Mixed reference frame where translation reference = base and orientation reference = tool + CARTESIAN_REFERENCE_FRAME_TOOL = 2; // Tool reference frame where translation reference = tool and orientation reference = tool + CARTESIAN_REFERENCE_FRAME_BASE = 3; // Base reference frame where the translation reference = base and orientation reference = base +} + +// Country code +message CountryCode { + CountryCodeIdentifier identifier = 1; // ISO3166 country code identifier +} + +// Supported ISO3166 country identifiers +enum CountryCodeIdentifier { + UNSPECIFIED_COUNTRY_CODE = 0; + UNITED_ARAB_EMIRATES_AE = 1; + ANTIGUA_AND_BARBUDA_AG = 2; + ANGUILLA_AI = 3; + ALBANIA_AL = 4; + AMERICAN_SAMOA_AS = 5; + AUSTRIA_AT = 6; + AUSTRALIA_AU = 7; + ARUBA_AW = 8; + AZERBAIJAN_AZ = 9; + BOSNIA_AND_HERZEGOVINA_BA = 10; + BANGLADESH_BD = 11; + BELGIUM_BE = 12; + BULGARIA_BG = 13; + BAHRAIN_BH = 14; + BERMUDA_BM = 15; + BRUNEI_DARUSSALAM_BN = 16; + BRAZIL_BR = 17; + BAHAMAS_BS = 18; + BELARUS_BY = 19; + SWITZERLAND_CH = 20; + CANADA_CA = 21; + CHINA_CN = 22; + COLOMBIA_CO = 23; + COSTA_RICA_CR = 24; + CYPRUS_CY = 25; + CZECH_REPUBLIC_CZ = 26; + GERMANY_DE = 27; + DENMARK_DK = 28; + ECUADOR_EC = 29; + ESTONIA_EE = 30; + EGYPT_EG = 31; + SPAIN_ES = 32; + ETHIOPIA_ET = 33; + FINLAND_FI = 34; + FRANCE_FR = 35; + UNITED_KINGDOM_GB = 36; + GRENADA_GD = 37; + FRENCH_GUIANA_GF = 38; + GUADELOUPE_GP = 39; + GREECE_GR = 40; + GUATEMALA_GT = 41; + GUAM_GU = 42; + HONG_KONG_HK = 43; + CROATIA_HR = 44; + HUNGARY_HU = 45; + INDIA_IN = 46; + INDONESIA_ID = 47; + IRELAND_IE = 48; + ISRAEL_IL = 49; + ICELAND_IS = 50; + ITALY_IT = 51; + JORDAN_JO = 52; + JAPAN_JP = 53; + CAMBODIA_KH = 54; + REPUBLIC_OF_KOREA_KR = 55; + KUWAIT_KW = 56; + CAYMAN_ISLANDS_KY = 57; + LAO_PDR_LA = 58; + LEBANON_LB = 59; + LIECHTENSTEIN_LI = 60; + SRI_LANKA_LK = 61; + LESOTHO_LS = 62; + LITHUANIA_LT = 63; + LUXEMBOURG_LU = 64; + LATVIA_LV = 65; + MOROCCO_MA = 66; + MONACO_MC = 67; + MOLDOVA_MD = 68; + MONTENEGRO_ME = 69; + REPUBLIC_OF_MACEDONIA_MK = 70; + MONGOLIA_MN = 71; + MARTINIQUE_MQ = 72; + MAURITANIA_MR = 73; + MALTA_MT = 74; + MAURITIUS_MU = 75; + MALDIVES_MV = 76; + MALAWI_MW = 77; + MEXICO_MX = 78; + MALAYSIA_MY = 79; + NICARAGUA_NI = 80; + NETHERLANDS_NL = 81; + NORWAY_NO = 82; + NEW_ZEALAND_NZ = 83; + OMAN_OM = 84; + PANAMA_PA = 85; + PERU_PE = 86; + PHILIPPINES_PH = 87; + POLAND_PL = 88; + PUERTO_RICO_PR = 89; + PORTUGAL_PT = 90; + PARAGUAY_PY = 91; + REUNION_RE = 92; + ROMANIA_RO = 93; + SERBIA_RS = 94; + RUSSIAN_FEDERATION_RU = 95; + SWEDEN_SE = 96; + SINGAPORE_SI = 97; + SLOVAKIA_SK = 98; + EL_SALVADOR_SV = 99; + THAILAND_TH = 100; + TUNISIA_TN = 101; + TURKEY_TR = 102; + TRINIDAD_AND_TOBAGO_TT = 103; + TAIWAN_PROVINCE_OF_CHINA_TW = 104; + UKRAINE_UA = 105; + UNITED_STATES_US = 106; + HOLY_SEE_VATICAN_CITY_STATE_VA = 107; + BOLIVARIAN_REPUBLIC_OF_VENEZUELA_VE = 108; + BRITISH_VIRGIN_ISLANDS_VG = 109; + VIETNAM_VN = 110; + MAYOTTE_YT = 111; + SOUTH_AFRICA_ZA = 112; +} diff --git a/ros_kortex/kortex_driver/protos/ControlConfig.proto b/ros_kortex/kortex_driver/protos/ControlConfig.proto new file mode 100644 index 0000000..55a50c4 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/ControlConfig.proto @@ -0,0 +1,273 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.ControlConfig; + +// Service to configure robot control library +service ControlConfig {//@PROXY_ID=16 @ERROR=Kinova.Api.Error + + // Sets global gravity vector in terms of base reference frame. This needs to be configured to enable control of the robot in wall or ceiling mounting of the robot. + rpc SetGravityVector (GravityVector) returns (Kinova.Api.Common.Empty);//@RPC_ID=1 + + // Retrieves global gravity vector + rpc GetGravityVector (Kinova.Api.Common.Empty) returns (GravityVector);//@RPC_ID=2 + + // Sets payload information. This needs to be configured so that the control library can take into account the presence of the payload mass in computing the dynamics of the robot. + rpc SetPayloadInformation (PayloadInformation) returns (Kinova.Api.Common.Empty);//@RPC_ID=3 + + // Retrieves payload information + rpc GetPayloadInformation (Kinova.Api.Common.Empty) returns (PayloadInformation);//@RPC_ID=4 + + // Sets tool configuration. This needs to be configured for two reasons. 1) so that the control library can take into account the presence of the tool mass in computing the dynamics of the robot. 2) so that the robot is aware of the tool frame center relative position and orientation to correctly compute and report the tool position. + rpc SetToolConfiguration (ToolConfiguration) returns (Kinova.Api.Common.Empty);//@RPC_ID=5 + + // Retrieves tool configuration + rpc GetToolConfiguration (Kinova.Api.Common.Empty) returns (ToolConfiguration);//@RPC_ID=6 + + // Subscribes to control configuration notifications + rpc ControlConfigurationTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=7 @PUB_SUB=ControlConfigurationNotification + + // Unsubscribes client from receiving specified type of notifications + rpc Unsubscribe (Kinova.Api.Common.NotificationHandle) returns (Kinova.Api.Common.Empty);//@RPC_ID=8 @UNSUB + + // Defines the reference frame to use with twist and wrench commands + rpc SetCartesianReferenceFrame (CartesianReferenceFrameInfo) returns (Kinova.Api.Common.Empty);//@RPC_ID=9 + + // Retrieves the current reference frame used by the twist and wrench commands + rpc GetCartesianReferenceFrame (Kinova.Api.Common.Empty) returns (CartesianReferenceFrameInfo);//@RPC_ID=10 + + // Retrieves current control mode (not implemented yet) + rpc GetControlMode (Kinova.Api.Common.Empty) returns (ControlModeInformation);//@RPC_ID=13 + + // Set the software joint speed limits. + rpc SetJointSpeedSoftLimits (JointSpeedSoftLimits) returns (Kinova.Api.Common.Empty);//@RPC_ID=14 + + // Set the software twist linear limit. + rpc SetTwistLinearSoftLimit (TwistLinearSoftLimit) returns (Kinova.Api.Common.Empty);//@RPC_ID=15 + + // Set the software twist angular limit. + rpc SetTwistAngularSoftLimit (TwistAngularSoftLimit) returns (Kinova.Api.Common.Empty);//@RPC_ID=16 + + // Set the software joint acceleration limits. + rpc SetJointAccelerationSoftLimits (JointAccelerationSoftLimits) returns (Kinova.Api.Common.Empty);//@RPC_ID=17 + + // Retrieves angular and twist hard limits. + rpc GetKinematicHardLimits (Kinova.Api.Common.Empty) returns (KinematicLimits);//@RPC_ID=18 + + // Retrieves the software kinematic limits for a specific control mode. + rpc GetKinematicSoftLimits (ControlModeInformation) returns (KinematicLimits);//@RPC_ID=19 + + // Retrieves the software kinematic limits for all control modes. + rpc GetAllKinematicSoftLimits (Kinova.Api.Common.Empty) returns (KinematicLimitsList);//@RPC_ID=20 + + // Set the desired linear twist when using the joystick. + rpc SetDesiredLinearTwist (LinearTwist) returns (Kinova.Api.Common.Empty);//@RPC_ID=21 + + // Set the desired angular twist when using the joystick. + rpc SetDesiredAngularTwist (AngularTwist) returns (Kinova.Api.Common.Empty);//@RPC_ID=22 + + // Set the desired joint speeds when using the joystick in angular mode. + rpc SetDesiredJointSpeeds (JointSpeeds) returns (Kinova.Api.Common.Empty);//@RPC_ID=23 + + // Retrieves the desired joystick speeds + rpc GetDesiredSpeeds (Kinova.Api.Common.Empty) returns (DesiredSpeeds);//@RPC_ID=24 + + // Resets gravity vector to default values + rpc ResetGravityVector (Kinova.Api.Common.Empty) returns (GravityVector);//@RPC_ID=25 + + // Resets payload information to default values + rpc ResetPayloadInformation (Kinova.Api.Common.Empty) returns (PayloadInformation);//@RPC_ID=26 + + // Resets tool configuration to default values + rpc ResetToolConfiguration (Kinova.Api.Common.Empty) returns (ToolConfiguration);//@RPC_ID=27 + + // Resets joint speed soft limits to default values + rpc ResetJointSpeedSoftLimits (ControlModeInformation) returns (JointSpeedSoftLimits);//@RPC_ID=28 + + // Resets twist linear soft limit to default value + rpc ResetTwistLinearSoftLimit (ControlModeInformation) returns (TwistLinearSoftLimit);//@RPC_ID=29 + + // Resets twist angular soft limit to default value + rpc ResetTwistAngularSoftLimit (ControlModeInformation) returns (TwistAngularSoftLimit);//@RPC_ID=30 + + // Resets joint acceleration soft limits to default values + rpc ResetJointAccelerationSoftLimits (ControlModeInformation) returns (JointAccelerationSoftLimits);//@RPC_ID=31 +} + +// Identifies ControlConfig current version +enum ServiceVersion +{ + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Defines the gravity vector in terms of the robot base frame. If not explicitly configured, it defaults to (0, 0, -9.81), assuming a mounting on a horizontal surface. If the robot is mounted on a wall or ceiling, the gravity vector relative to the base frame will change. The control library needs to be aware of this to accurately compensate for gravity. +message GravityVector +{ + float x = 1; // x (meters / second^squared) + float y = 2; // y (meters / second^squared) + float z = 3; // z (meters / second^squared) +} + +// A Cartesian position +message Position { + float x = 1; // x position (in meters) + float y = 2; // y position (in meters) + float z = 3; // z position (in meters) +} + +// Defines payload information +message PayloadInformation +{ + float payload_mass = 1; // Tool mass in kg + Position payload_mass_center = 2; // Tool mass center position relative to the tool reference frame +} + +// Defines a Cartesian transform +message CartesianTransform +{ + float x = 1; // x (in meters) + float y = 2; // y (in meters) + float z = 3; // z (in meters) + float theta_x = 4; // Theta x (in degrees) + float theta_y = 5; // Theta y (in degrees) + float theta_z = 6; // Theta z (in degrees) +} + +// Defines a tool configuration +message ToolConfiguration { + CartesianTransform tool_transform = 1; // Cartesian transform tool + float tool_mass = 2; // Tool mass (in kg) + Position tool_mass_center = 3; // Tool mass center position relative to the interface module reference frame +} + +// Admissible control configuration events +enum ControlConfigurationEvent { + UNSPECIFIED_CONTROL_CONFIGURATION_EVENT = 0; // Unspecified control configuration event + ANGLE_UNIT_CHANGED = 1; // Angle unit changed event + GRAVITY_VECTOR_CHANGED = 2; // Gravity vector changed event + JOINT_ADMITTANCE_CONFIGURATION_CHANGED = 4; // Joint admittance configuration changed event + NULL_ADMITTANCE_CONFIGURATION_CHANGED = 5; // Null admittance configuration changed event + CARTESIAN_ADMITTANCE_CONFIGURATION_CHANGED = 6; // Cartesian admittance configuration changed event + JOINT_TORQUE_HYBRID_CONFIGURATION_CHANGED = 7; // Joint torque hybrid configuraiton changed event + WRENCH_COMMAND_NORMAL_CONFIGURATION_CHANGED = 8; // Wrench commmand normal configuration changed event + WRENCH_COMMAND_RESTRICTED_CONFIGURATION_CHANGED = 9; // Wrench command restricted configuration changed event + CONTROL_CONFIGURATION_FACTORY_RESTORED = 10; // Control configuration factory restored event + TOOL_CONFIGURATION_CHANGED = 11; // Tool configuration event + PAYLOAD_CONFIGURATION_CHANGED = 12; // Payload configuration event + CARTESIAN_REFERENCE_CHANGED = 13; // Cartesian reference event + CHANGE_CONTROL_MODE_FAILED = 14; // Control mode change fail event + JOINT_SPEED_SOFT_LIMITS_CHANGED = 16; // Joint speed software limits changed event + TWIST_LINEAR_SOFT_LIMIT_CHANGED = 17; // Linear speed software limit changed event + TWIST_ANGULAR_SOFT_LIMIT_CHANGED = 18; // Angular speed software limit changed event + JOINT_ACCELERATION_SOFT_LIMITS_CHANGED = 19; // Joint acceleration software limits changed event + DESIRED_TWIST_LINEAR_SPEED_CHANGED = 20; // Desired joystick twist linear speed changed event + DESIRED_TWIST_ANGULAR_SPEED_CHANGED = 21; // Desired joystick twist angular speed changed event + DESIRED_JOINT_SPEED_CHANGED = 22; // Desired joystick joint speed changed event +} + +// Notification about a single control configuration event +message ControlConfigurationNotification { + ControlConfigurationEvent event = 1; + Kinova.Api.Common.Timestamp timestamp = 2; // Event timestamp + Kinova.Api.Common.UserProfileHandle user_handle = 3; // User that caused the factory event to occur + Kinova.Api.Common.Connection connection = 4; // Connection that caused the configuration event +} + +// Cartesian reference frame +message CartesianReferenceFrameInfo { + Kinova.Api.Common.CartesianReferenceFrame reference_frame = 1; // Reference frame +} + +// Software twist linear speed limit +message TwistLinearSoftLimit { + ControlMode control_mode = 1; // Control mode + float twist_linear_soft_limit = 2; // Software linear twist limit +} + +// Software twist angular speed limit +message TwistAngularSoftLimit { + ControlMode control_mode = 1; // Control mode + float twist_angular_soft_limit = 2; // Software angular twist limit +} + +// Software joint speed limits +message JointSpeedSoftLimits { + ControlMode control_mode = 1; // Control mode + repeated float joint_speed_soft_limits = 2; // Software joint speed limits +} + +// Software Joint acceleration limits +message JointAccelerationSoftLimits { + ControlMode control_mode = 1; // Control mode + repeated float joint_acceleration_soft_limits = 2; // Software acceleration limits +} + +// Kinematic limits +message KinematicLimits { + ControlMode control_mode = 1; // Control mode + float twist_linear = 2; // Linear twist limits + float twist_angular = 3; // Angular twist limits + repeated float joint_speed_limits = 4; // Joint speed limits + repeated float joint_acceleration_limits = 5; // Joint Acceleration limits +} + +// Kinematic limits +message KinematicLimitsList { + repeated KinematicLimits kinematic_limits_list = 1; // List of kinematic limits +} + +// Desired Joystick speeds. +message DesiredSpeeds { + float linear = 1; // Desired linear speed (meters / second) + float angular = 2; // Desired angular speed (degrees / second) + repeated float joint_speed = 3; // Desired joint speeds (degrees / second) +} + +// Desired Joystick linear speed. +message LinearTwist { + float linear = 1; // Desired linear speed (meters / second) +} + +// Desired Joystick angular speed. +message AngularTwist { + float angular = 1; // Desired angular speed (degrees / second) +} + +// Desired Joystick joint speeds. +message JointSpeeds { + repeated float joint_speed = 1; // Desired joint speeds (degrees / second) +} + +// Admissible robot control modes +enum ControlMode { + UNSPECIFIED_CONTROL_MODE = 0; // Unspecified control mode + ANGULAR_JOYSTICK = 1; // Angular joystick mode + CARTESIAN_JOYSTICK = 2; // Cartesian joystick mode + ANGULAR_TRAJECTORY = 4; // Angular trajectory mode + CARTESIAN_TRAJECTORY = 5; // Cartesian trajectory mode + CARTESIAN_ADMITTANCE = 6; // Cartesian admittance mode + JOINT_ADMITTANCE = 7; // Joint admittance mode + NULL_SPACE_ADMITTANCE = 8; // Null space mode + FORCE_CONTROL = 10; // Force control mode + FORCE_CONTROL_MOTION_RESTRICTED = 11; // Force control motion restricted mode + IDLE = 13; // Idle +}; + +// Control mode information +message ControlModeInformation { + ControlMode control_mode = 1; // Control mode +} diff --git a/ros_kortex/kortex_driver/protos/DeviceConfig.proto b/ros_kortex/kortex_driver/protos/DeviceConfig.proto new file mode 100644 index 0000000..bef45cb --- /dev/null +++ b/ros_kortex/kortex_driver/protos/DeviceConfig.proto @@ -0,0 +1,337 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.DeviceConfig; + +// Service to get and set device configuration information +service DeviceConfig {//@PROXY_ID=9 @ERROR=Kinova.Api.Error + + // Returns the run mode for the device + rpc GetRunMode (Kinova.Api.Common.Empty) returns (RunMode); //@RPC_ID=1 + + // Sets the run mode for the device + rpc SetRunMode (RunMode) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Retrieves the type for the device + rpc GetDeviceType (Kinova.Api.Common.Empty) returns (DeviceType); //@RPC_ID=3 + + // Retrieves the device firmware version + rpc GetFirmwareVersion (Kinova.Api.Common.Empty) returns (FirmwareVersion); //@RPC_ID=4 + + // Retrieves the device bootloader version + rpc GetBootloaderVersion (Kinova.Api.Common.Empty) returns (BootloaderVersion); //@RPC_ID=5 + + // Retrieves the device model number + rpc GetModelNumber (Kinova.Api.Common.Empty) returns (ModelNumber); //@RPC_ID=6 + + // Retrieves the device part number + rpc GetPartNumber (Kinova.Api.Common.Empty) returns (PartNumber); //@RPC_ID=7 + + // Retrieves the device serial number + rpc GetSerialNumber (Kinova.Api.Common.Empty) returns (SerialNumber); //@RPC_ID=8 + + // Retrieves the device MAC address + rpc GetMACAddress (Kinova.Api.Common.Empty) returns (MACAddress); //@RPC_ID=9 + + // Retrieves the device IPv4 settings (not implemented on Base) + rpc GetIPv4Settings (Kinova.Api.Common.Empty) returns (IPv4Settings); //@RPC_ID=10 + + // Sets the device IPv4 settings (not implemented on Base) + rpc SetIPv4Settings (IPv4Settings) returns (Kinova.Api.Common.Empty); //@RPC_ID=11 + + // Retrieves the device part number revision + rpc GetPartNumberRevision (Kinova.Api.Common.Empty) returns (PartNumberRevision); //@RPC_ID=12 + + // Sends a request to the device to reboot + rpc RebootRequest (RebootRqst) returns (Kinova.Api.Common.Empty); //@RPC_ID=14 + + // Enables (disable) the specified safety + rpc SetSafetyEnable (SafetyEnable) returns (Kinova.Api.Common.Empty); //@RPC_ID=15 + + // Sets the error threshold for the specified safety + rpc SetSafetyErrorThreshold (SafetyThreshold) returns (Kinova.Api.Common.Empty); //@RPC_ID=16 + + // Sets the warning threshold for the specified safety + rpc SetSafetyWarningThreshold (SafetyThreshold) returns (Kinova.Api.Common.Empty); //@RPC_ID=17 + + // Configures the specified safety (i.e. sets error and warning thresholds) + rpc SetSafetyConfiguration (SafetyConfiguration) returns (Kinova.Api.Common.Empty); //@RPC_ID=18 + + // Retrieves configuration about the specified safety + rpc GetSafetyConfiguration (Kinova.Api.Common.SafetyHandle) returns (SafetyConfiguration); //@RPC_ID=19 + + // Retrieves information about the specified safety + rpc GetSafetyInformation (Kinova.Api.Common.SafetyHandle) returns (SafetyInformation); //@RPC_ID=20 + + // Indicates if specified safety is enabled (or disabled) + rpc GetSafetyEnable (Kinova.Api.Common.SafetyHandle) returns (SafetyEnable); //@RPC_ID=21 + + // Indicates if the specified safety is raised + rpc GetSafetyStatus (Kinova.Api.Common.SafetyHandle) returns (SafetyStatus); //@RPC_ID=22 + + // Clear all safety status for this device if they are no longer raised + rpc ClearAllSafetyStatus (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty); //@RPC_ID=23 + + // Clear a specific safety status if it is no longer raised + rpc ClearSafetyStatus (Kinova.Api.Common.SafetyHandle) returns (Kinova.Api.Common.Empty); //@RPC_ID=24 + + // Retrieves configuration on all safeties + rpc GetAllSafetyConfiguration (Kinova.Api.Common.Empty) returns (SafetyConfigurationList); //@RPC_ID=25 + + // Retrieves information on all safeties + rpc GetAllSafetyInformation (Kinova.Api.Common.Empty) returns (SafetyInformationList); //@RPC_ID=26 + + // Restores all safety configurations to factory defaults + rpc ResetSafetyDefaults (Kinova.Api.Common.Empty) returns (Kinova.Api.Common.Empty); //@RPC_ID=27 + + // Subscribes to safety notifications + rpc SafetyTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle); //@RPC_ID=28 @PUB_SUB=Kinova.Api.Common.SafetyNotification + + // Starts device calibration (intended for Kinova Production of Pico) + rpc ExecuteCalibration (Calibration) returns (Kinova.Api.Common.Empty); //@RPC_ID=34 + + // Retrieves the status/result of device calibration (intended for Kinova Production of Pico) + rpc GetCalibrationResult (CalibrationElement) returns (CalibrationResult); //@RPC_ID=35 + + // Stop calibration in progress + rpc StopCalibration (Calibration) returns (CalibrationResult); //@RPC_ID=36 + + // Sets the capacitive sensor calibration + rpc SetCapSenseConfig (CapSenseConfig) returns (Kinova.Api.Common.Empty); //@RPC_ID=37 + + // Retrieves the capacitive sensor calibration + rpc GetCapSenseConfig (Kinova.Api.Common.Empty) returns (CapSenseConfig); //@RPC_ID=38 + + // Reads low-level register from the capacitive sensor (for Kinova internal use ony, not to be used in the field) + rpc ReadCapSenseRegister (CapSenseRegister) returns (CapSenseRegister); //@RPC_ID=39 + + // Writes to low-level register of the capacitive sensor (for Kinova internal use ony, not to be used in the field) + rpc WriteCapSenseRegister (CapSenseRegister) returns (Kinova.Api.Common.Empty); //@RPC_ID=40 +} + +// Identifies DeviceConfig current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Options for the run mode for the device +enum RunModes { + RUN_MODE = 0; + CALIBRATION_MODE = 1; // calibration mode + CONFIGURATION_MODE = 2; // configuration mode + DEBUG_MODE = 3; // debug mode + TUNING_MODE = 4; // tuning mode +} + +// Device type +message DeviceType { + Kinova.Api.Common.DeviceTypes device_type = 1; // Device type +} + + +// Run mode +message RunMode { + RunModes run_mode = 1; // Run mode +} + +// Firmware version for the device +message FirmwareVersion { + uint32 firmware_version = 1; // Firmware version +} + +// Bootloader version for the device +message BootloaderVersion { + uint32 bootloader_version = 1; // Bootloader version +} + +// Model number for the device +message ModelNumber { + string model_number = 1; // Model number of size 25 including null character +} + +// Part number for the device +message PartNumber { + string part_number = 1; // Part number of size 25 including null character +} + +// Serial number for the device +message SerialNumber { + string serial_number = 1; // Serial number of size 25 including null character +} + +// MAC address for the device +message MACAddress { + bytes mac_address = 1; // MAC address +} + +// IPv4 settings for the device, including address, subnet mask, and default gateway +message IPv4Settings { + uint32 ipv4_address = 1; // IPv4Address + uint32 ipv4_subnet_mask = 2; // IPv4SubnetMask + uint32 ipv4_default_gateway = 3; // IPv4DefaultGateway +} + +// Part number revision for the device +message PartNumberRevision { + string part_number_revision = 1; // Part number revision +} + +// Result of power on self test +message PowerOnSelfTestResult { + uint32 power_on_self_test_result = 1; // Power on self test result +} + +// Reboot request with bootloader delay +message RebootRqst { + uint32 delay = 1; // Bootloader delay +} + +// Admissible calibration items +enum CalibrationItem +{ + UNSPECIFIED_CALIBRATION_ITEM = 0; // Unspecified calibration item + COGGING = 1; // Cogging calibration + MAGNETIC = 2; // Magnetic sensors calibration + MOTOR = 3; // Motor calibration + POSITION_RANGE = 4; // Position range calibration +} + +// Admissible calibration status +enum CalibrationStatus +{ + UNSPECIFIED_CALIBRATION_STATUS = 0; // Unspecified calibration status + NOT_CALIBRATED = 1; // Calibration is not done + IN_PROGRESS = 2; // Calibration is in progress + CALIBRATED = 3; // Calibration was successfully completed + IN_FAULT = 4; // Calibration failed +} + +// Types of safeties limits +enum SafetyLimitType { + UNSPECIFIED_SAFETY_LIMIT_TYPE = 0; + MINIMAL_LIMIT = 1; // Safety that will kick in below a certain Minimum threshold (e.g. Minimum temperature safety) + MAXIMAL_LIMIT = 2; // Safety that will kick in above a certain Maximum threshold (e.g. Maximum voltage safety) + EVENT_LIMIT = 3; // Safety that will kick in in reaction to a specific event (e.g. motor drive fault) + +} + +// Admissible capacitive sensor mode +enum CapSenseMode +{ + RESERVED = 0; // Reserved, do not use. + INACTIVE = 1; // Cap sensor is inactive. + ACTIVE_AUTO_THRESHOLD = 2; // Cap sensor is active in automatic threshold mode. + ACTIVE_NOISE_ATT = 4; // Cap sensor is active with noise mitigation enabled. + ACTIVE_NORMAL = 5; // Cap sensor is active in normal mode. + CONFIGURATION = 6; // Configuration mode. +} + +// Information about a specific safety +message SafetyInformation { + Kinova.Api.Common.SafetyHandle handle = 1; // Safety handle that this information is about + bool can_change_safety_state = 2; // True if related safety configuration can be modified + bool has_warning_threshold = 3; // True if safety status can go in Warning + bool has_error_threshold = 4; // True if safety status can go in Error + SafetyLimitType limit_type = 5; // Safety limit type + float default_warning_threshold = 6; // Default warning threshold (if 'limit_type' is either MINIMAL_LIMIT or MAXIMAL_LIMIT and 'has_warning_threshold' is true) + float default_error_threshold = 7; // Default error threshold (if 'limit_type' is either MINIMAL_LIMIT or MAXIMAL_LIMIT and 'has_error_threshold' is true) + float upper_hard_limit = 8; // Maximal threshold value (if 'limit_type' is either MINIMAL_LIMIT or MAXIMAL_LIMIT) + float lower_hard_limit = 9; // Minimal threshold value (if 'limit_type' is either MINIMAL_LIMIT or MAXIMAL_LIMIT) + Kinova.Api.Common.SafetyStatusValue status = 11;// Current Safety status + Kinova.Api.Common.Unit unit = 12; // Unit that the safety status is in +} + +// Array of safety information +message SafetyInformationList { + repeated SafetyInformation information = 1; +} + +// Enable or disable a specific safety +message SafetyEnable { + Kinova.Api.Common.SafetyHandle handle = 1; // Handle to safety to enable or disable + bool enable = 2; // Safety enable state +} + +// Configure threshold of a specific safety +message SafetyThreshold { + Kinova.Api.Common.SafetyHandle handle = 1; // Identifies safety to configure + float value = 2; // Safety threshold value +} + +// Configuration for a safety +message SafetyConfiguration { + Kinova.Api.Common.SafetyHandle handle = 1; // Handle to safety to configure + float error_threshold = 2; // Safety error threshold value + float warning_threshold = 3; // Safety warning threshold value + SafetyEnable enable = 4; // Safety enable state +} + +// Array of safety configurations +message SafetyConfigurationList { + repeated SafetyConfiguration configuration = 1; // Safety configuration +} + +// Safety status +message SafetyStatus { + Kinova.Api.Common.SafetyStatusValue value = 1; // Safety status (e.g. in error, warning or normal state) +} + +// Single calibration parameter information +message CalibrationParameter +{ + uint32 calibration_parameter_identifier = 1; // Calibration parameter identifier + oneof value { + int32 signedIntValue = 2; // Signed int calibration value. + uint32 unsignedIntValue = 3; // Unsigned int calibration value. + float floatValue = 4; // Float calibration value. + } +} + +// Calibration information to push to device +message Calibration +{ + CalibrationItem calibration_item = 1; // Item to calibrate + repeated CalibrationParameter calibration_parameter = 2; // Parameters associated to calibration item +} + +// Calibration element +message CalibrationElement +{ + CalibrationItem calibration_item = 1; // Item to get status +} + +// Result of a calibration +message CalibrationResult +{ + CalibrationStatus calibration_status = 1; // Calibration status + uint32 calibration_details = 2; // Additional information (used when status is in fault) +} + +// Capacitive sensor configuration message +message CapSenseConfig +{ + CapSenseMode mode = 1; // Operational mode of the sensor + float threshold_a = 2; // Sensitivity of the sensor A (0-100%). + float threshold_b = 3; // Sensitivity of the sensor B (0-100%). +} + +// Message used to address a register +message CapSenseRegister +{ + uint32 address = 1; // Register address + uint32 value = 2; // Register value +} diff --git a/ros_kortex/kortex_driver/protos/DeviceManager.proto b/ros_kortex/kortex_driver/protos/DeviceManager.proto new file mode 100644 index 0000000..5d3d145 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/DeviceManager.proto @@ -0,0 +1,35 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.DeviceManager; + +// This service provides information about which devices are present in the robot +service DeviceManager {//@PROXY_ID=23 @ERROR=Kinova.Api.Error + + // Retrieves the list of every device that the system contains, along with its type and order within the system + rpc ReadAllDevices (Kinova.Api.Common.Empty) returns (DeviceHandles);//@RPC_ID=1 +} + +// Identifies DeviceManager service current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Array of Device handles +message DeviceHandles { + repeated Kinova.Api.Common.DeviceHandle device_handle = 1; // Device handle +} diff --git a/ros_kortex/kortex_driver/protos/Errors.proto b/ros_kortex/kortex_driver/protos/Errors.proto new file mode 100644 index 0000000..dad290a --- /dev/null +++ b/ros_kortex/kortex_driver/protos/Errors.proto @@ -0,0 +1,152 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +package Kinova.Api; + +// Possible error codes +enum ErrorCodes { + ERROR_NONE = 0; // No error + ERROR_PROTOCOL_SERVER = 1; // Protocol server error + ERROR_PROTOCOL_CLIENT = 2; // Protocol client error + ERROR_DEVICE = 3; // Device error + ERROR_INTERNAL = 4; // Internal error +} + +// Possible sub-error codes +enum SubErrorCodes { + SUB_ERROR_NONE = 0; // No sub error + METHOD_FAILED = 1; // Method returned a failure status (generic error) + UNIMPLEMENTED = 2; // Unimplemented method + INVALID_PARAM = 3; // Invalid parameter + + UNSUPPORTED_SERVICE = 4; // Service not recognized + UNSUPPORTED_METHOD = 5; // Method not recognized + TOO_LARGE_ENCODED_FRAME_BUFFER = 6; // Encoded frame bigger than what transport permits + FRAME_ENCODING_ERR = 7; // Unable to encode frame + FRAME_DECODING_ERR = 8; // Unable to decode frame + INCOMPATIBLE_HEADER_VERSION = 9; // Frame header version differs from what is expected and is considered incompatible + UNSUPPORTED_FRAME_TYPE = 10; // Unrecognized frame type + UNREGISTERED_NOTIFICATION_RECEIVED = 11;// Server receiving unregistered notification + INVALID_SESSION = 12; // Session not recognized + PAYLOAD_DECODING_ERR = 13; // Unable to decode payload + UNREGISTERED_FRAME_RECEIVED = 14; // Client received a response for which it did not send an RPC call + + INVALID_PASSWORD = 15; // Password does not match specified user + USER_NOT_FOUND = 16; // Unrecognized user + + ENTITY_NOT_FOUND = 17; // Cannot find entity + + ROBOT_MOVEMENT_IN_PROGRESS = 18; // Robot refuses new control command because robot movement in progress + ROBOT_NOT_MOVING = 19; // Robot refuses stop command because robot is not moving + + NO_MORE_STORAGE_SPACE = 20; // Unable to execute because no more storage + + ROBOT_NOT_READY = 21; // Robot initialization is not complete + ROBOT_IN_FAULT = 22; // Robot in fault + ROBOT_IN_MAINTENANCE = 23; // Robot in maintenance + ROBOT_IN_UPDATE_MODE = 24; // Robot in update + ROBOT_IN_EMERGENCY_STOP = 25; // Robot in emergency stop state + + SINGLE_LEVEL_SERVOING = 26; // Robot is in single-level servoing mode + LOW_LEVEL_SERVOING = 27; // Robot is in low-level servoing mode + + MAPPING_GROUP_NON_ROOT = 28; // Trying to add a non-root MapGroup to Mapping + MAPPING_INVALID_GROUP = 29; // Trying to add an invalid or non-existent MapGroup to Mapping + MAPPING_INVALID_MAP = 30; // Trying to add an invalid or non-existent Map to Mapping + MAP_GROUP_INVALID_MAP = 31; // Trying to add an invalid or non-existent Map to MapGroup + MAP_GROUP_INVALID_PARENT = 32; // Trying to add a MapGroup under an invalid parent + MAP_GROUP_INVALID_CHILD = 33; // Trying to add an invalid or non-existent to MapGroup + MAP_GROUP_INVALID_MOVE = 34; // Trying to change a MapGroup's parent: move not supported + MAP_IN_USE = 35; // Deleting a Map used in a Mapping or MapGroup + + WIFI_CONNECT_ERROR = 36; // Unable to connect to specified Wifi network + UNSUPPORTED_NETWORK_TYPE = 37; // Unsupported network type + TOO_LARGE_ENCODED_PAYLOAD_BUFFER = 38; // Encoded payload bigger than what transport permits + + UPDATE_PERMISSION_DENIED = 39; // Attempting update command on non-updatable entity + DELETE_PERMISSION_DENIED = 40; // Attempting delete command on non-deletable entity + DATABASE_ERROR = 41; // Internal DB error + + UNSUPPORTED_OPTION = 42; // Option not supported + UNSUPPORTED_RESOLUTION = 43; // Resolution not supported + UNSUPPORTED_FRAME_RATE = 44; // Frame rate not supported + UNSUPPORTED_BIT_RATE = 45; // Bit rate not supported + UNSUPPORTED_ACTION = 46; // Action not supported (generic, when an action is not supported for a particular item) + UNSUPPORTED_FOCUS_ACTION = 47; // Focus action not supported + VALUE_IS_ABOVE_MAXIMUM = 48; // Specified value is above the supported maximum + VALUE_IS_BELOW_MINIMUM = 49; // Specified value is below the supported minimum + + DEVICE_DISCONNECTED = 50; // Device is not connected + DEVICE_NOT_READY = 51; // Device is not ready + + INVALID_DEVICE = 52; // Device id is invalid during bridging + + SAFETY_THRESHOLD_REACHED = 53; // Safety threshold is reached therefore safety is on + + INVALID_USER_SESSION_ACCESS = 54; // Service or function access not allowed: out of session or level access + + CONTROL_MANUAL_STOP = 55; // Manually stopped sequence or action + CONTROL_OUTSIDE_WORKSPACE = 56; // Commanded Cartesian position is outside of robot workspace + CONTROL_ACTUATOR_COUNT_MISMATCH = 57; // Number of constraint sent does not correspond to number of actuator (ex: joint speed) + CONTROL_INVALID_DURATION = 58; // Duration constraint is too short. The robot would need out of limit speeds/accelerations to reach this duration. + CONTROL_INVALID_SPEED = 59; // Speed constraint is negative + CONTROL_LARGE_SPEED = 60; // Speed constraint is too high (exceed speed limit of leads to high acceleration) + CONTROL_INVALID_ACCELERATION = 61; // Speed constraint is too high or duration constraint too short and leads to high acceleration + CONTROL_INVALID_TIME_STEP = 62; // Refresh rate is smaller than the duration of the trajectory + CONTROL_LARGE_SIZE = 63; // Duration of the trajectory is more than 100s. The length of the trajectory is limited to 100000 points to avoid saturating the base memory. + CONTROL_WRONG_MODE = 64; // Control mode is not a trajectory mode + CONTROL_JOINT_POSITION_LIMIT = 65; // Commanded configuration contains at least one actuator which is out of its physical limits + CONTROL_NO_FILE_IN_MEMORY = 66; // Trajectory is not computed and try to be started + CONTROL_INDEX_OUT_OF_TRAJECTORY = 67; // Attempting to read a point of the trajectory with an index higher than the number of point in trajectory point list. + CONTROL_ALREADY_RUNNING = 68; // Trajectory is already running + CONTROL_WRONG_STARTING_POINT = 69; // Robot is not on the first point of the trajectory when we try to start the trajectory. This can happen if there is a motion between the moment when trajectory is computed and when it is started. + CONTROL_CARTESIAN_CANNOT_START = 70; // Cannot start + CONTROL_UNDEFINED_CONSTRAINT = 71; // Kontrol library is not initialized + CONTROL_UNINITIALIZED = 72; // Contraint sent is not defined + CONTROL_NO_ACTION = 73; // Action does not exist + CONTROL_UNDEFINED = 74; // Undefined error + + WRONG_SERVOING_MODE = 75; // Robot is in not in the right servoing mode + + CONTROL_WRONG_STARTING_SPEED = 76; // Robot is not at the right speed when starting a new trajectory. + + USERNAME_LENGTH_EXCEEDED = 100; // User profile username length exceeds maximum allowed length + FIRSTNAME_LENGTH_EXCEEDED = 101; // User profile first name length exceeds maximum allowed length + LASTNAME_LENGTH_EXCEEDED = 102; // User profile last name length exceeds maximum allowed length + PASSWORD_LENGTH_EXCEEDED = 103; // User profile password length exceeds maximum allowed length + USERNAME_ALREADY_EXISTS = 104; // User profile username already in use by another profile + USERNAME_EMPTY = 105; // User profile empty username not allowed + PASSWORD_NOT_CHANGED = 106; // Change password both passwords are the same + MAXIMUM_USER_PROFILES_USED = 107; // Maximum number of user profiles in use + ROUTER_UNVAILABLE = 108; // The client router is currently unavailable. This can happen if an API method is called after the router has been deactivated via the method SetActivationStatus. + + ADDRESS_NOT_IN_VALID_RANGE = 120; // IP Address not valid against netmask + ADDRESS_NOT_CONFIGURABLE = 121; // IP Address not configurable on specified interface + + SESSION_NOT_IN_CONTROL = 130; // Trying to perform command from a non-controlling session in single-level mode + + METHOD_TIMEOUT = 131; // Timeout occured during method execution + + UNSUPPORTED_ROBOT_CONFIGURATION = 132; // Product Configuration setter method failed because changing this parameter is unsupported on your robot model + NVRAM_READ_FAIL = 133; // Failed to read in NVRAM. + NVRAM_WRITE_FAIL = 134; // Failed to write in NVRAM. + + NETWORK_NO_ADDRESS_ASSIGNED = 135; // The specified interface has no assigned IP + + READ_PERMISSION_DENIED = 136; // Attempting read command on unreadable entity + + CONTROLLER_INVALID_MAPPING = 137; // Attempting to assign an unsuited mapping to controller + + ACTION_IN_USE = 138; // Attempting to delete an Action used by another entity +} diff --git a/ros_kortex/kortex_driver/protos/GripperConfig.proto b/ros_kortex/kortex_driver/protos/GripperConfig.proto new file mode 100644 index 0000000..e0410e7 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/GripperConfig.proto @@ -0,0 +1,30 @@ +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.GripperConfig; + +// Gripper safety identifier +enum SafetyIdentifier { + UNSPECIFIED_ACTUATOR_SAFETY_IDENTIFIER = 0; //0x0 + MAXIMUM_MOTOR_CURRENT = 1; //0x1 + MAXIMUM_VOLTAGE = 2; //0x2 + MINIMUM_VOLTAGE = 4; //0x4 + MAXIMUM_MOTOR_TEMPERATURE = 8; //0x8 + MAXIMUM_CORE_TEMPERATURE = 16; //0x10 + NON_VOLATILE_MEMORY_CORRUPTED = 32; //0x20 + EMERGENCY_LINE_ASSERTED = 64; //0x40 + COMMUNICATION_TICK_LOST = 128; //0x80 + WATCHDOG_TRIGGERED = 256; //0x100 +} + +// Status flags for Robotiq Adaptive Gripper +enum RobotiqGripperStatusFlags { + UNSPECIFIED_ROBOTIQ_STATUS = 0; //0x0 + ROBOTIQ_STAT_INITIALIZED = 1; //0x01 + ROBOTIQ_STAT_OBJECT_DETECTED = 2; //0x02 + ROBOTIQ_STAT_POS_REACHED = 4; //0x04 + ROBOTIQ_STAT_STOPPED = 8; //0x08 +} + + diff --git a/ros_kortex/kortex_driver/protos/GripperCyclic.proto b/ros_kortex/kortex_driver/protos/GripperCyclic.proto new file mode 100644 index 0000000..e987f2a --- /dev/null +++ b/ros_kortex/kortex_driver/protos/GripperCyclic.proto @@ -0,0 +1,39 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + + syntax = "proto3"; + +import public "Common.proto"; +import public "GripperCyclicMessage.proto"; + +package Kinova.Api.GripperCyclic; + +// Service to exchange cyclic data with gripper +service GripperCyclic {//@PROXY_ID=17 @ERROR=Kinova.Api.Error + + // Sends a command to the gripper and receives feedback about the actual status of the gripper + rpc Refresh (Kinova.Api.GripperCyclic.Command) returns (Kinova.Api.GripperCyclic.Feedback); //@RPC_ID=1 + + // Sends a command to the gripper without receiving feedback + rpc RefreshCommand (Kinova.Api.GripperCyclic.Command) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Obtains feedback from the gripper on its status + rpc RefreshFeedback (Kinova.Api.GripperCyclic.MessageId) returns (Kinova.Api.GripperCyclic.Feedback); //@RPC_ID=3 + + // Obtains custom data from the gripper + rpc RefreshCustomData (Kinova.Api.GripperCyclic.MessageId) returns (Kinova.Api.GripperCyclic.CustomData); //@RPC_ID=4 +} + +enum ServiceVersion { + RESERVED_0 = 0; + CURRENT_VERSION = 1; // Current Version +} diff --git a/ros_kortex/kortex_driver/protos/GripperCyclicMessage.proto b/ros_kortex/kortex_driver/protos/GripperCyclicMessage.proto new file mode 100644 index 0000000..c27ac09 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/GripperCyclicMessage.proto @@ -0,0 +1,86 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + + syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.GripperCyclic; + +// Message identifier for command or feedback +message MessageId { + fixed32 identifier = 1; // Message ID (first 2 bytes : device ID, last 2 bytes : sequence number) +} + +// Command to a single gripper motor +message MotorCommand { + fixed32 motor_id = 1; // Motor ID (1, nb_motor) + float position = 3; // Desired position of the gripper fingers in percentage (0-100%) + float velocity = 4; // Desired velocity in percentage (0-100%) with which position will be set + float force = 5; // Desired force limit of the gripper fingers in percentage (0-100%) +} + +// Command sent to a gripper +message Command { + MessageId command_id = 1; // MessageId + fixed32 flags = 2; // Flags + repeated MotorCommand motor_cmd = 3; // Array of finger commands, one for each finger of the gripper. +} + +// Status feedback from a single gripper motor +message MotorFeedback { + fixed32 motor_id = 1; // Motor ID (1, nb_motor) + float position = 4; // Position of the gripper fingers in percentage (0-100%) + float velocity = 5; // Velocity of the gripper fingers in percentage (0-100%) + float current_motor = 7; // Current comsumed by the gripper motor (mA) + float voltage = 8; // Motor Voltage (V) + float temperature_motor = 10; // Motor temperature. (degrees Celsius) +} + +// Status feedback from a gripper +message Feedback { + MessageId feedback_id = 1; // MessageId + fixed32 status_flags = 2; // Status flags (see GripperConfig.RobotiqGripperStatusFlags) + fixed32 fault_bank_a = 3; // Fault bank A (see GripperConfig.SafetyIdentifier) + fixed32 fault_bank_b = 4; // Fault bank B (see GripperConfig.SafetyIdentifier) + fixed32 warning_bank_a = 5; // Warning bank A (see GripperConfig.SafetyIdentifier) + fixed32 warning_bank_b = 6; // Warning bank B (see GripperConfig.SafetyIdentifier) + repeated MotorFeedback motor = 7; +} + +// Custom data +message CustomDataUnit { + fixed32 custom_data_0 = 1; // Custom data word 0 + fixed32 custom_data_1 = 2; // Custom data word 1 + fixed32 custom_data_2 = 3; // Custom data word 2 + fixed32 custom_data_3 = 4; // Custom data word 3 + fixed32 custom_data_4 = 5; // Custom data word 4 + fixed32 custom_data_5 = 6; // Custom data word 5 + fixed32 custom_data_6 = 7; // Custom data word 6 + fixed32 custom_data_7 = 8; // Custom data word 7 + fixed32 custom_data_8 = 9; // Custom data word 8 + fixed32 custom_data_9 = 10; // Custom data word 9 + fixed32 custom_data_10 = 11; // Custom data word 10 + fixed32 custom_data_11 = 12; // Custom data word 11 + fixed32 custom_data_12 = 13; // Custom data word 12 + fixed32 custom_data_13 = 14; // Custom data word 13 + fixed32 custom_data_14 = 15; // Custom data word 14 + fixed32 custom_data_15 = 16; // Custom data word 15 +} + +// Custom data from gripper and gripper motors +message CustomData { + MessageId custom_data_id = 1; // MessageId + CustomDataUnit gripper_custom_data = 2; + repeated CustomDataUnit motor_custom_data = 3; +} + diff --git a/ros_kortex/kortex_driver/protos/InterconnectConfig.proto b/ros_kortex/kortex_driver/protos/InterconnectConfig.proto new file mode 100644 index 0000000..819c2de --- /dev/null +++ b/ros_kortex/kortex_driver/protos/InterconnectConfig.proto @@ -0,0 +1,256 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.InterconnectConfig; + +// Service to get and set interface module (interconnect) configuration information, including user expansion +service InterconnectConfig {//@PROXY_ID=14 @ERROR=Kinova.Api.Error + + // Retrieves user UART configuration + rpc GetUARTConfiguration (Kinova.Api.Common.UARTDeviceIdentification) returns (Kinova.Api.Common.UARTConfiguration); //@RPC_ID=1 + + // Configures user UART + rpc SetUARTConfiguration (Kinova.Api.Common.UARTConfiguration) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Retrieves user Ethernet configuration + rpc GetEthernetConfiguration (EthernetDeviceIdentification) returns (EthernetConfiguration); //@RPC_ID=3 + + // Configures user Ethernet port + rpc SetEthernetConfiguration (EthernetConfiguration) returns (Kinova.Api.Common.Empty); //@RPC_ID=4 + + // Retrieves user GPIO configuration + rpc GetGPIOConfiguration (GPIOIdentification) returns (GPIOConfiguration); //@RPC_ID=5 + + // Configures user GPIO + rpc SetGPIOConfiguration (GPIOConfiguration) returns (Kinova.Api.Common.Empty); //@RPC_ID=6 + + // Retrieves user GPIO state + rpc GetGPIOState (GPIOIdentification) returns (GPIOState); //@RPC_ID=7 + + // Configures user GPIO state + rpc SetGPIOState (GPIOState) returns (Kinova.Api.Common.Empty); //@RPC_ID=8 + + // Retrieves user I2C configuration + rpc GetI2CConfiguration (I2CDeviceIdentification) returns (I2CConfiguration); //@RPC_ID=9 + + // Configures user I2C + rpc SetI2CConfiguration (I2CConfiguration) returns (Kinova.Api.Common.Empty); //@RPC_ID=10 + + // Performs an I2C read request + rpc I2CRead (I2CReadParameter) returns (I2CData); //@RPC_ID=11 + + // Performs an I2C read register request + rpc I2CReadRegister (I2CReadRegisterParameter) returns (I2CData); //@RPC_ID=12 + + // Performs an I2C write request + rpc I2CWrite (I2CWriteParameter) returns (Kinova.Api.Common.Empty); //@RPC_ID=13 + + // Performs an I2C write register request + rpc I2CWriteRegister (I2CWriteRegisterParameter) returns (Kinova.Api.Common.Empty); //@RPC_ID=14 +} + +// Identifies InterconnectConfig current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Admissible interface module safeties +enum SafetyIdentifier { + UNSPECIFIED_INTERCONNECT_SAFETY_IDENTIFIER = 0; // 0x0 - Unspecified actuator safety + MAXIMUM_MOTOR_CURRENT = 1; // 0x1 - Maximum motor current + MAXIMUM_VOLTAGE = 2; // 0x2 - Maximum voltage + MINIMUM_VOLTAGE = 4; // 0x4 - Minimum voltage + MAXIMUM_MOTOR_TEMPERATURE = 8; // 0x8 - Maximum motor temperature + MAXIMUM_CORE_TEMPERATURE = 16; // 0x10 - Maximum core temperature + NON_VOLATILE_MEMORY_CORRUPTED = 32; // 0x20 - Non-volatile memory corrupted + EMERGENCY_LINE_ASSERTED = 64; // 0x40 - Emergency line asserted + COMMUNICATION_TICK_LOST = 128; // 0x80 - Communication tick lost + WATCHDOG_TRIGGERED = 256; // 0x100 - Watchdog triggered +} + +// Admissible UART port +enum UARTPortId { + UART_PORT_UNSPECIFIED = 0; // Unspecified UART port + UART_PORT_EXPANSION = 1; // UART port located on the expansion connector +} + +// Admissible Ethernet device +enum EthernetDevice { + ETHERNET_DEVICE_UNSPECIFIED = 0; // Unspecified ethernet device + ETHERNET_DEVICE_EXPANSION = 1; // Ethernet port located on the expansion connector +} + +// Ethernet device identification +message EthernetDeviceIdentification { + EthernetDevice device = 1; // Ethernet device +} + +// Admissible Ethernet speed +enum EthernetSpeed { + ETHERNET_SPEED_UNSPECIFIED = 0; // Unspecified ethernet speed + ETHERNET_SPEED_10M = 1; // 10 Mbps + ETHERNET_SPEED_100M = 2; // 100 Mbps +} + +// Admissible Ethernet duplex mode +enum EthernetDuplex { + ETHERNET_DUPLEX_UNSPECIFIED = 0; // Unspecified ethernet duplex + ETHERNET_DUPLEX_HALF = 1; // Half duplex + ETHERNET_DUPLEX_FULL = 2; // Full duplex +} + +// Ethernet configuration information +message EthernetConfiguration { + EthernetDevice device = 1; // Device identification + bool enabled = 2; // True if the ethernet device is enabled, false otherwise + EthernetSpeed speed = 3; // Speed selection + EthernetDuplex duplex = 4; // Duplex mode +} + +// Admissible GPIO identifier +enum GPIOIdentifier { + GPIO_IDENTIFIER_UNSPECIFIED = 0; // Unspecified GPIO identifier + GPIO_IDENTIFIER_1 = 1; // GPIO identifier 1 + GPIO_IDENTIFIER_2 = 2; // GPIO identifier 2 + GPIO_IDENTIFIER_3 = 3; // GPIO identifier 3 + GPIO_IDENTIFIER_4 = 4; // GPIO identifier 4 +} + +// GPIO identification +message GPIOIdentification { + GPIOIdentifier identifier = 1; // GPIO identifier +} + +// Admissible GPIO mode +enum GPIOMode { + GPIO_MODE_UNSPECIFIED = 0; // Unspecified GPIO mode + GPIO_MODE_INPUT_FLOATING = 1; // Input floating + GPIO_MODE_OUTPUT_PUSH_PULL = 2; // Output push-pull + GPIO_MODE_OUTPUT_OPEN_DRAIN = 3; // Output open drain +} + +// Admissible GPIO pull mode +enum GPIOPull { + GPIO_PULL_UNSPECIFIED = 0; // Unspecified GPIO pull + GPIO_PULL_NONE = 1; // Pull none + GPIO_PULL_UP = 2; // Pull up + GPIO_PULL_DOWN = 3; // Pull down +} + +// Admissible GPIO value +enum GPIOValue { + GPIO_VALUE_UNSPECIFIED = 0; // Unspecified GPIO value + GPIO_VALUE_LOW = 1; // Low + GPIO_VALUE_HIGH = 2; // High +} + +// GPIO configuration information +message GPIOConfiguration { + GPIOIdentifier identifier = 1; // GPIO identifier + GPIOMode mode = 2; // Mode + GPIOPull pull = 3; // Pull mode + GPIOValue default_value = 4; // Default value at power on +} + +// GPIO state +message GPIOState { + GPIOIdentifier identifier = 1; // GPIO identifier + GPIOValue value = 2; // Value +} + +// Admissible I2C device +enum I2CDevice { + I2C_DEVICE_UNSPECIFIED = 0; // Unspecified I2C device + I2C_DEVICE_EXPANSION = 1; // I2C device located on the expansion connector +} + +// I2C device identification +message I2CDeviceIdentification { + I2CDevice device = 1; // I2C device +} + +// I2C mode +enum I2CMode { + I2C_MODE_UNSPECIFIED = 0; // Unspecified I2C mode + I2C_MODE_STANDARD = 1; // Standard mode + I2C_MODE_FAST = 2; // Fast mode + I2C_MODE_FAST_PLUS = 3; // Fast plus mode +} + +// I2C device addressing mode +enum I2CDeviceAddressing { + I2C_DEVICE_ADDRESSING_UNSPECIFIED = 0; // Unspecified device addressing + I2C_DEVICE_ADDRESSING_7_BITS = 1; // 7 bits device addressing + I2C_DEVICE_ADDRESSING_10_BITS = 2; // 10 bits device addressing +} + +// I2C register address size +enum I2CRegisterAddressSize { + I2C_REGISTER_ADDRESS_SIZE_UNSPECIFIED = 0; // Unspecified I2C register address size + I2C_REGISTER_ADDRESS_SIZE_8_BITS = 1; // 8 bits register address size + I2C_REGISTER_ADDRESS_SIZE_16_BITS = 2; // 16 bits register address size +} + +// I2C configuration information +message I2CConfiguration { + I2CDevice device = 1; // I2C device identification + bool enabled = 2; // True if I2C device is enabled, false otherwise + I2CMode mode = 3; // Mode + I2CDeviceAddressing addressing = 4; // Addressing mode +} + +// I2C read request +message I2CReadParameter { + I2CDevice device = 1; // I2C device identification + fixed32 device_address = 2; // I2C device address + fixed32 size = 5; // I2C number of bytes to read (max 128 bytes) + fixed32 timeout = 6; // Request timeout in milliseconds +} + +// I2C read register request +message I2CReadRegisterParameter { + I2CDevice device = 1; // I2C device identification + fixed32 device_address = 2; // I2C device address + fixed32 register_address = 3; // I2C register address (8 or 16 bits) + I2CRegisterAddressSize register_address_size = 4; // I2C register address size + fixed32 size = 5; // I2C number of bytes to read (max 128 bytes) + fixed32 timeout = 6; // Request timeout in milliseconds +} + +// I2C write request +message I2CWriteParameter { + I2CDevice device = 1; // I2C device identification + fixed32 device_address = 2; // I2C device address + fixed32 timeout = 5; // Request timeout in milliseconds + I2CData data = 6; // Data to write +} + +// I2C write register request +message I2CWriteRegisterParameter { + I2CDevice device = 1; // I2C device identification + fixed32 device_address = 2; // I2C device address + fixed32 register_address = 3; // I2C register address (8 or 16 bits) + I2CRegisterAddressSize register_address_size = 4; // I2C register address size + fixed32 timeout = 5; // Request timeout in milliseconds + I2CData data = 6; // Data to write +} + +// I2C data +message I2CData { + bytes data = 1; // Data byte(s) array (max 128 bytes) + fixed32 size = 2; // Data byte(s) array size +} diff --git a/ros_kortex/kortex_driver/protos/InterconnectCyclic.proto b/ros_kortex/kortex_driver/protos/InterconnectCyclic.proto new file mode 100644 index 0000000..aeb6832 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/InterconnectCyclic.proto @@ -0,0 +1,41 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; +import public "InterconnectCyclicMessage.proto"; + +package Kinova.Api.InterconnectCyclic; + +// Service to exchange cyclic data with interface module +service InterconnectCyclic {//@PROXY_ID=15 @ERROR=Kinova.Api.Error + + // Sends a command to the interface module and receive feedback about the actual status + rpc Refresh (Kinova.Api.InterconnectCyclic.Command) returns (Kinova.Api.InterconnectCyclic.Feedback); //@RPC_ID=1 + + // Sends a command to the interface module without receiving feedback + rpc RefreshCommand (Kinova.Api.InterconnectCyclic.Command) returns (Kinova.Api.Common.Empty); //@RPC_ID=2 + + // Obtains feedback from the interface module on its status + rpc RefreshFeedback (Kinova.Api.InterconnectCyclic.MessageId) returns (Kinova.Api.InterconnectCyclic.Feedback); //@RPC_ID=3 + + // Obtains custom data from the interface module + rpc RefreshCustomData (Kinova.Api.InterconnectCyclic.MessageId) returns (Kinova.Api.InterconnectCyclic.CustomData); //@RPC_ID=4 +} + + +// Identifies InterconnectCyclic service current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/protos/InterconnectCyclicMessage.proto b/ros_kortex/kortex_driver/protos/InterconnectCyclicMessage.proto new file mode 100644 index 0000000..94dc7f3 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/InterconnectCyclicMessage.proto @@ -0,0 +1,80 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + + syntax = "proto3"; + + import public "Common.proto"; + import public "GripperCyclicMessage.proto"; + + package Kinova.Api.InterconnectCyclic; + + + // Identifies a message + message MessageId { + fixed32 identifier = 1; // Message ID (first 2 bytes : device ID, last 2 bytes : sequence number) + } + + // Interface module command + message Command { + MessageId command_id = 1; // MessageId + fixed32 flags = 2; // Flags + oneof tool_command { + Kinova.Api.GripperCyclic.Command gripper_command = 3; // Gripper command + } + } + + // Defines the feedback provided by interface module + message Feedback { + MessageId feedback_id = 1; // MessageId + fixed32 status_flags = 2; // Status flags + fixed32 jitter_comm = 3; // Jitter from the communication (in microseconds) + float imu_acceleration_x = 4; // IMU Measured acceleration (X-Axis) of the interface module (in meters per second ^ squared) + float imu_acceleration_y = 5; // IMU Measured acceleration (Y-Axis) of the interface module (in meters per second ^ squared) + float imu_acceleration_z = 6; // IMU Measured acceleration (Z-Axis) of the interface module (in meters per second ^ squared) + float imu_angular_velocity_x = 7; // IMU Measured angular velocity (X-Axis) of the interface module (in degrees per second) + float imu_angular_velocity_y = 8; // IMU Measured angular velocity (Y-Axis) of the interface module (in degrees per second) + float imu_angular_velocity_z = 9; // IMU Measured angular velocity (Z-Axis) of the interface module (in degrees per second) + float voltage = 10; // Voltage of the main board (in Volt) + float temperature_core = 11; // Microcontroller temperature (in degrees Celsius) + fixed32 fault_bank_a = 12; // Fault bank A (see InterconnectConfig.SafetyIdentifier) + fixed32 fault_bank_b = 13; // Fault bank B (see InterconnectConfig.SafetyIdentifier) + fixed32 warning_bank_a = 14; // Warning bank A (see InterconnectConfig.SafetyIdentifier) + fixed32 warning_bank_b = 15; // Warning bank B (see InterconnectConfig.SafetyIdentifier) + oneof tool_feedback { + Kinova.Api.GripperCyclic.Feedback gripper_feedback = 18; // Gripper model tool feedback + } + } + + // Custom development data, content varies according to debugging needs + message CustomData { + MessageId custom_data_id = 1; // MessageId + fixed32 custom_data_0 = 2; // Custom data word 0 + fixed32 custom_data_1 = 3; // Custom data word 1 + fixed32 custom_data_2 = 4; // Custom data word 2 + fixed32 custom_data_3 = 5; // Custom data word 3 + fixed32 custom_data_4 = 6; // Custom data word 4 + fixed32 custom_data_5 = 7; // Custom data word 5 + fixed32 custom_data_6 = 8; // Custom data word 6 + fixed32 custom_data_7 = 9; // Custom data word 7 + fixed32 custom_data_8 = 10; // Custom data word 8 + fixed32 custom_data_9 = 11; // Custom data word 9 + fixed32 custom_data_10 = 12; // Custom data word 10 + fixed32 custom_data_11 = 13; // Custom data word 11 + fixed32 custom_data_12 = 14; // Custom data word 12 + fixed32 custom_data_13 = 15; // Custom data word 13 + fixed32 custom_data_14 = 16; // Custom data word 14 + fixed32 custom_data_15 = 17; // Custom data word 15 + oneof tool_customData { + Kinova.Api.GripperCyclic.CustomData gripper_custom_data = 18; + } + } + diff --git a/ros_kortex/kortex_driver/protos/ProductConfiguration.proto b/ros_kortex/kortex_driver/protos/ProductConfiguration.proto new file mode 100644 index 0000000..9a840bb --- /dev/null +++ b/ros_kortex/kortex_driver/protos/ProductConfiguration.proto @@ -0,0 +1,97 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2019 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; +package Kinova.Api.ProductConfiguration; + +import public "Common.proto"; + +// Admissible model identification +enum ModelId { + MODEL_ID_UNSPECIFIED = 0; // Unspecified Model identification + MODEL_ID_L53 = 1; // Gen3 Ultra Lightweight Robot + MODEL_ID_L31 = 2; // PICO + MODEL_ID_HDK = 3; // Hardware Development Kit +} + +// Admissible base types +enum BaseType { + BASE_TYPE_UNSPECIFIED = 0; // Unspecified base type + BASE_TYPE_L53_QUICK_CONNECT = 1; // L53 (Gen3) Quick Connect Base + BASE_TYPE_L53_FIXED = 2; // L53 (Gen3) Fixed Base + BASE_TYPE_L31_FIXED = 3; // L31 (PICO) Fixed Base + BASE_TYPE_HDK_FIXED = 4; // HDK Fixed Base +} + +// Admissible end-effector modules +enum EndEffectorType { + END_EFFECTOR_TYPE_UNSPECIFIED = 0; // Unspecified end-effector type + END_EFFECTOR_TYPE_NOT_INSTALLED = 1; // No gripper installed + END_EFFECTOR_TYPE_L31_GRIPPER_2F = 2; // L31 (PICO) gripper, 2 fingers + END_EFFECTOR_TYPE_ROBOTIQ_2F_85 = 3; // Robotiq 2F-85 gripper, 2 fingers + END_EFFECTOR_TYPE_ROBOTIQ_2F_140 = 4; // Robotiq 2F-140 gripper, 2 fingers +} + +// Admissible vision modules +enum VisionModuleType { + VISION_MODULE_TYPE_UNSPECIFIED = 0; // Unspecified vision module type + VISION_MODULE_TYPE_NOT_INSTALLED = 1; // Not Applicable / Not Installed + VISION_MODULE_TYPE_L53_2D3D = 2; // L53 (Gen3) Vision Module + VISION_MODULE_TYPE_L53_2D = 3; // L53 (Gen3) Vision Module without 3D sensor + VISION_MODULE_TYPE_EOD = 4; // EOD Vision Module +} + +// Admissible interface modules +enum InterfaceModuleType { + INTERFACE_MODULE_TYPE_UNSPECIFIED = 0; // Unspecified interface module type + INTERFACE_MODULE_TYPE_NOT_INSTALLED = 1; // Not Applicable / Not Installed + INTERFACE_MODULE_TYPE_L53 = 2; // L53 (Gen3) Interface Module + INTERFACE_MODULE_TYPE_L31 = 3; // L31 (PICO) Interface Module +} + +// Admissible arm laterality +enum ArmLaterality { + ARM_LATERALITY_UNSPECIFIED = 0; // Unspecified arm laterality + ARM_LATERALITY_NOT_APPLICABLE = 1; // Not Applicable + ARM_LATERALITY_LEFT = 2; // Left Laterality + ARM_LATERALITY_RIGHT = 3; // Right Laterality +} + +// Admissible wrist types +enum WristType { + WRIST_TYPE_UNSPECIFIED = 0; // Unspecified wrist type + WRIST_TYPE_NOT_APPLICABLE = 1; // Not Applicable + WRIST_TYPE_SPHERICAL = 2; // Spherical Wrist + WRIST_TYPE_CURVED = 3; // Curved Wrist +} + +// Complete configuration for a given device +message CompleteProductConfiguration { + string kin = 1; // Kinova Identification Number of the device + ModelId model = 2; // Model of the device + Kinova.Api.Common.CountryCode country_code = 3; // Country code for the device + string assembly_plant = 4; // Assembly plant of the device + string model_year = 5; // Year of the model + uint32 degree_of_freedom = 6; // Number of DOF for the device + BaseType base_type = 7; // Type of base for the device + EndEffectorType end_effector_type = 8; // End-effector type of the device + VisionModuleType vision_module_type = 9; // Vision module type of the device + InterfaceModuleType interface_module_type = 10; // Interface module type of the device + ArmLaterality arm_laterality = 11; // Arm laterality of the device + WristType wrist_type = 12; // Wrist type of the device +} + +// New end-effector installed on arm +message ProductConfigurationEndEffectorType { + EndEffectorType end_effector_type = 1; // New end-effector type +} + diff --git a/ros_kortex/kortex_driver/protos/VisionConfig.proto b/ros_kortex/kortex_driver/protos/VisionConfig.proto new file mode 100644 index 0000000..cc7a726 --- /dev/null +++ b/ros_kortex/kortex_driver/protos/VisionConfig.proto @@ -0,0 +1,282 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2018 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +syntax = "proto3"; + +import public "Common.proto"; + +package Kinova.Api.VisionConfig; + +// Service to configure the Vision Module +service VisionConfig {//@PROXY_ID=5 @ERROR=Kinova.Api.Error + + // Sets sensor settings (resolution, frame rate, etc) + rpc SetSensorSettings (SensorSettings) returns (Kinova.Api.Common.Empty);//@RPC_ID=1 + + // Retrieves sensor settings (resolution, frame rate, etc) + rpc GetSensorSettings (SensorIdentifier) returns (SensorSettings);//@RPC_ID=2 + + // Retrieves option value from the sensor + rpc GetOptionValue (OptionIdentifier) returns (OptionValue);//@RPC_ID=3 + + // Writes new value to sensor option + rpc SetOptionValue (OptionValue) returns (Kinova.Api.Common.Empty);//@RPC_ID=4 + + // Retrieves option information from the sensor + rpc GetOptionInformation (OptionIdentifier) returns (OptionInformation);//@RPC_ID=5 + + // Subscribes to Vision configuration notifications + rpc VisionTopic (Kinova.Api.Common.NotificationOptions) returns (Kinova.Api.Common.NotificationHandle);//@RPC_ID=6 @PUB_SUB=VisionNotification + + // Do a focus action + rpc DoSensorFocusAction (SensorFocusAction) returns (Kinova.Api.Common.Empty);//@RPC_ID=7 + + // Retrieves sensor intrinsic parameters + rpc GetIntrinsicParameters (SensorIdentifier) returns (IntrinsicParameters);//@RPC_ID=8 + + // Retrieves sensor intrinsic parameters for a specific profile + rpc GetIntrinsicParametersProfile (IntrinsicProfileIdentifier) returns (IntrinsicParameters);//@RPC_ID=9 + + // Sets sensor intrinsic parameters + rpc SetIntrinsicParameters (IntrinsicParameters) returns (Kinova.Api.Common.Empty);//@RPC_ID=10 + + // Retrieves sensor extrinsic parameters + rpc GetExtrinsicParameters (Kinova.Api.Common.Empty) returns (ExtrinsicParameters);//@RPC_ID=11 + + // Sets sensor extrinsic parameters + rpc SetExtrinsicParameters (ExtrinsicParameters) returns (Kinova.Api.Common.Empty);//@RPC_ID=12 +} + +// Identifies VisionConfig service current version +enum ServiceVersion { + RESERVED_0 = 0; // Reserved + CURRENT_VERSION = 1; // Current version +} + +// Main sensor settings - resolution, frame rate, bit rate - for the chosen sensor (color or depth). +message SensorSettings { + Sensor sensor = 1; // The sensor (color or depth) + Resolution resolution = 2; // The resolution setting + FrameRate frame_rate = 3; // Frame rate setting + BitRate bit_rate = 4; // Maximum encoded bit rate +} + +// Vision module sensor to configure +enum Sensor { + SENSOR_UNSPECIFIED = 0; // Unspecified Sensor + SENSOR_COLOR = 1; // Select the Vision module color sensor + SENSOR_DEPTH = 2; // Select the Vision module depth sensor +} + +// Sensor resolution. Note that some settings are only for the color sensor and some are only for the depth sensor. +enum Resolution { + RESOLUTION_UNSPECIFIED = 0; // Unspecified resolution + RESOLUTION_320x240 = 1; // 320 x 240 pixels (supported on color sensor only) + RESOLUTION_424x240 = 2; // 424 x 240 pixels (supported on depth sensor only) + RESOLUTION_480x270 = 3; // 480 x 270 pixels (supported on depth sensor only) + RESOLUTION_640x480 = 4; // 640 x 480 pixels (supported on color sensor only) + RESOLUTION_1280x720 = 5; // 1280 x 720 pixels (HD) (supported on color sensor only) + RESOLUTION_1920x1080 = 6; // 1920 x 1080 pixels (full HD) (supported on color sensor only) +} + +// Sensor frame rate +enum FrameRate { + FRAMERATE_UNSPECIFIED = 0; // Unspecified frame rate + FRAMERATE_6_FPS = 1; // 6 frames per second (supported on depth sensor only) + FRAMERATE_15_FPS = 2; // 15 frames per second + FRAMERATE_30_FPS = 3; // 30 frame per second +} + +// Maximum encoded bit rate, in Mbps +enum BitRate { + BITRATE_UNSPECIFIED = 0; // Unspecified bit rate (supported on depth sensor only) + BITRATE_10_MBPS = 1; // 10 Mbps maximum bit rate (supported on color sensor only) + BITRATE_15_MBPS = 2; // 15 Mbps maximum bit rate (supported on color sensor only) + BITRATE_20_MBPS = 3; // 20 Mbps maximum bit rate (supported on color sensor only) + BITRATE_25_MBPS = 4; // 25 Mbps maximum bit rate (supported on color sensor only) +} + +// Sensor to configure +message SensorIdentifier { + Sensor sensor = 1; // Sensor +} + +// Intrisic parameters profile to retrieve +message IntrinsicProfileIdentifier { + Sensor sensor = 1; // Sensor + Resolution resolution = 2; // Resolution +} + +// Sensor and the option to configure +message OptionIdentifier { + Sensor sensor = 1; // The sensor to configure + Option option = 2; // The option to configure on the sensor +} + +// Value of the particular option for the sensor +message OptionValue { + Sensor sensor = 1; // The sensor to configure (color or depth) + Option option = 2; // The option to configure + float value = 3; // The desired value for the option +} + +// Information about the optional settings for the chosen sensor +message OptionInformation { + Sensor sensor = 1; // The sensor (color or depth) + Option option = 2; // The option + bool supported = 3; // Is the option supported by the chosen sensor? + bool read_only = 4; // Is the option read-only, or can it be changed? + float minimum = 5; // Minimum value for the option + float maximum = 6; // Maximum value for the option + float step = 7; // Step size for the option value (if it takes on discrete values) + float default_value = 8; // Default value for the option +} + +// Admissible vision module sensor options. Note that some options are only available for the color sensor and some are only available for the depth sensor. +enum Option { + OPTION_UNSPECIFIED = 0; // Unspecifed Option + OPTION_BACKLIGHT_COMPENSATION = 1; // Enable / disable color backlight compensation (unsupported) + OPTION_BRIGHTNESS = 2; // Color image brightness (supported on color sensor only: -4.0 to 4.0, step 1.0) + OPTION_CONTRAST = 3; // Color image contrast (supported on color sensor only: -4.0 to 4.0, step 1.0) + OPTION_EXPOSURE = 4; // Controls exposure time of color camera. Setting any value will disable auto exposure (supported on depth sensor only: 20.0 to 166000.0, step 20.0) + OPTION_GAIN = 5; // Color image gain (supported on depth sensor only: 16.0 to 248.0, step 1.0) + OPTION_GAMMA = 6; // Color image gamma setting (unsupported) + OPTION_HUE = 7; // Color image hue (unsupported) + OPTION_SATURATION = 8; // Color image saturation setting (supported on color sensor only: -4.0 to 4.0, step 1.0) + OPTION_SHARPNESS = 9; // Color image sharpness setting (unsupported) + OPTION_WHITE_BALANCE = 10; // Controls white balance of color image. Setting any value will disable auto white balance (unsupported) + OPTION_ENABLE_AUTO_EXPOSURE = 11; // Enable / disable color image auto-exposure (supported on depth sensor only: 0.0 to 1.0, step 1.0) + OPTION_ENABLE_AUTO_WHITE_BALANCE = 12; // Enable / disable color image auto-white-balance (unsupported) + OPTION_VISUAL_PRESET = 13; // Provide access to several recommend sets of option presets for the depth camera (supported on depth sensor only: 0.0 to 5.0, step 1.0) + OPTION_LASER_POWER = 14; // Power of the projector, with 0 meaning projector off (unsupported) + OPTION_ACCURACY = 15; // Sets the number of patterns projected per frame. The higher the accuracy value the more patterns projected (unsupported) + OPTION_MOTION_RANGE = 16; // Motion vs. Range trade-off, with lower values allowing for better motion sensitivity and higher values allowing for better depth range (unsupported) + OPTION_FILTER_OPTION = 17; // Sets the filter to apply to each depth frame. Each one of the filter is optimized per the application requirements (unsupported) + OPTION_CONFIDENCE_THRESHOLD = 18; // The confidence level threshold used by the Depth algorithm pipe to set whether a pixel will get a valid range or will be marked with invalid range (unsupported) + OPTION_EMITTER_ENABLED = 19; // Laser Emitter enabled (unsupported) + OPTION_FRAMES_QUEUE_SIZE = 20; // Number of frames the user is allowed to keep per stream. Trying to hold-on to more frames will cause frame-drops (supported on depth sensor only: 0.0 to 32.0, step 1.0) + OPTION_TOTAL_FRAME_DROPS = 21; // Total number of detected frame drops from all streams (unsupported) + OPTION_AUTO_EXPOSURE_MODE = 22; // Auto-Exposure modes: Static, Anti-Flicker and Hybrid (unsupported) + OPTION_POWER_LINE_FREQUENCY = 23; // Power Line Frequency control for anti-flickering Off/50Hz/60Hz/Auto (unsupported) + OPTION_ASIC_TEMPERATURE = 24; // Current Asic Temperature (supported on depth sensor only: Read Only -40.0 to 125.0) + OPTION_ERROR_POLLING_ENABLED = 25; // Disable error handling (supported on depth sensor only: 0.0 to 1.0, step 1.0) + OPTION_PROJECTOR_TEMPERATURE = 26; // Current Projector Temperature (unsupported) + OPTION_OUTPUT_TRIGGER_ENABLED = 27; // Enable / disable trigger to be outputed from the camera to any external device on every depth frame (supported on depth sensor only: 0.0 to 1.0, step 1.0) + OPTION_MOTION_MODULE_TEMPERATURE = 28; // Current Motion-Module Temperature (unsupported) + OPTION_DEPTH_UNITS = 29; // Number of meters represented by a single depth unit (supported on depth sensor only: 0.0001 to 0.0100, step 0.000001) + OPTION_ENABLE_MOTION_CORRECTION = 30; // Enable/Disable automatic correction of the motion data (unsupported) + OPTION_AUTO_EXPOSURE_PRIORITY = 31; // Allows sensor to dynamically ajust the frame rate depending on lighting conditions (unsupported) + OPTION_COLOR_SCHEME = 32; // Color scheme for data visualization (unsupported) + OPTION_HISTOGRAM_EQUALIZATION_ENABLED = 33; // Perform histogram equalization post-processing on the depth data (unsupported) + OPTION_MIN_DISTANCE = 34; // Minimal distance to the target (unsupported) + OPTION_MAX_DISTANCE = 35; // Maximum distance to the target (unsupported) + OPTION_TEXTURE_SOURCE = 36; // Texture mapping stream unique ID (unsupported) + OPTION_FILTER_MAGNITUDE = 37; // The 2D-filter effect. The specific interpretation is given within the context of the filter (unsupported) + OPTION_FILTER_SMOOTH_ALPHA = 38; // 2D-filter parameter controls the weight/radius for smoothing (unsupported) + OPTION_FILTER_SMOOTH_DELTA = 39; // 2D-filter range/validity threshold (unsupported) + OPTION_HOLES_FILL = 40; // Enhance depth data post-processing with holes filling where appropriate (unsupported) + OPTION_STEREO_BASELINE = 41; // The distance in mm between the first and the second imagers in stereo-based depth cameras (supported on depth sensor only: 55.241055 to 55.241055, step 0.0) + OPTION_AUTO_EXPOSURE_CONVERGE_STEP = 42; // Allows dynamically ajust the converge step value of the target exposure in Auto-Exposure algorithm (unsupported) +} + +// Focus action to perform for the specified sensor +message SensorFocusAction { + Sensor sensor = 1; // The sensor on which to perform the focus action + FocusAction focus_action = 2; // The focus action to perform on the sensor + oneof action_parameters { + FocusPoint focus_point = 3; // The X-Y point on which to focus + ManualFocus manual_focus = 4; // The manual focus abstract value + } +} + +// Focus action to perform (start/pause continuous, focus now, disable). Supported only with Color sensor. +enum FocusAction { + FOCUSACTION_UNSPECIFIED = 0; // Unspecified focus action + FOCUSACTION_START_CONTINUOUS_FOCUS = 1; // Start continuous focus + FOCUSACTION_PAUSE_CONTINUOUS_FOCUS = 2; // Pause continuous focus + FOCUSACTION_FOCUS_NOW = 3; // Focus now (single-shot) + FOCUSACTION_DISABLE_FOCUS = 4; // Disable focus + FOCUSACTION_SET_FOCUS_POINT = 5; // Set a focus point + FOCUSACTION_SET_MANUAL_FOCUS = 6; // Set the manual focus distance +} + +// Focus point in the X-Y coordinates of the image +message FocusPoint { + uint32 x = 1; // Pixel value on the X axis, between 0 and the current resolution width - 1 + uint32 y = 2; // Pixel value on the Y axis, between 0 and the current resolution height - 1 +} + +// Abstract value that affects the focus distance +message ManualFocus { + uint32 value = 1; // Abstract value allowing to change the focus distance, between 0 (infinity) and 1023 (close plane) +} + +// Admissible Vision module events. +enum VisionEvent { + UNSPECIFIED_VISION_EVENT = 0; // Unspecified vision event + SENSOR_SETTINGS_CHANGED = 1; // Sensor setting changed event + OPTION_VALUE_CHANGED = 2; // Option value changed event +} + +// Notification about a single vision module event +message VisionNotification { + VisionEvent event = 1; // Vision event + Sensor sensor = 2; // The sensor that caused the notification (if applicable) + Option option = 3; // The option that caused the notification (if applicable) +} + +// Sensor intrinsic parameters +message IntrinsicParameters { + Sensor sensor = 1; // The sensor for which the parameters apply to + Resolution resolution = 2; // The resolution for which the parameters apply to + float principal_point_x = 3; // Horizontal coordinate of the principal point of the image, as a pixel offset from the left edge + float principal_point_y = 4; // Vertical coordinate of the principal point of the image, as a pixel offset from the top edge + float focal_length_x = 5; // Focal length of the image plane, as a multiple of pixel width + float focal_length_y = 6; // Focal length of the image plane, as a multiple of pixel height + DistortionCoefficients distortion_coeffs = 7; // Distortion coefficients +} + +// Distortion coefficients for sensor intrinsic parameters +message DistortionCoefficients { + float k1 = 1; // First radial distortion coefficient + float k2 = 2; // Second radial distortion coefficient + float k3 = 3; // Third radial distortion coefficient + float p1 = 4; // First tangential distortion coefficient + float p2 = 5; // Second tangential distortion coefficient +} + +// Sensor extrinsic parameters +message ExtrinsicParameters { + RotationMatrix rotation = 1; // The rotation matrix from depth sensor reference frame to color sensor reference frame + TranslationVector translation = 2; // The translation vector from depth sensor reference frame to color sensor reference frame +} + +// Representation of a 3x3 rotation matrix. To be a valid rotation matrix, the rows must be orthonormal (the rows must each have norm of 1 and the row vectors must be orthogonal to each other). The determinant must also be +1. +message RotationMatrix { + RotationMatrixRow row1 = 1; // First rotation matrix row + RotationMatrixRow row2 = 2; // Second rotation matrix row + RotationMatrixRow row3 = 3; // Third rotation matrix row +} + +// Single row of a 3x3 rotation matrix. To be a valid possible row of a rotation matrix, the norm of the row must be 1 (the sum of the squares of the row elements has to equal 1). +message RotationMatrixRow { + float column1 = 1; // Value between -1.0 and 1.0 + float column2 = 2; // Value between -1.0 and 1.0 + float column3 = 3; // Value between -1.0 and 1.0 +} + +// Provides a 3x1 translation vector configuration +message TranslationVector { + float t_x = 1; // Translation in meters in the x axis + float t_y = 2; // Translation in meters in the y axis + float t_z = 3; // Translation in meters in the z axis +} diff --git a/ros_kortex/kortex_driver/readme.md b/ros_kortex/kortex_driver/readme.md new file mode 100644 index 0000000..47351ff --- /dev/null +++ b/ros_kortex/kortex_driver/readme.md @@ -0,0 +1,311 @@ + + +# Kortex Driver + +# **Note:** There have been many changes made between versions 1.1.7 and 2.0.0 of the ROS driver. You can view the changes and learn the steps to follow to adapt your code in [this section](#compatibility). + + +## Table of contents + +1. [Overview](#overview) +1. [Usage](#usage) +1. [Topics](#topics) +1. [Services](#services) +1. [Compatibility break between v1.1.X and v2.0.X](#compatibility) +1. [About Conan](#conan) +1. [Support for multiple arms](#multiple) +1. [Generation (advanced)](#generation) + + + + +## Overview +This node allows communication between a ROS node and a Kinova Gen3 or Gen3 lite robot. + +### License + +The source code is released under a [BSD 3-Clause license](../LICENSE). + +**Author: Kinova inc.
+Affiliation: [Kinova inc.](https://www.kinovarobotics.com/)
+Maintainer: Kinova inc. support@kinovarobotics.com** + +This package has been tested under ROS Kinetic (Ubuntu 16.04) and ROS Melodic (Ubuntu 18.04). + + +## Usage + +The `kortex_driver` node is the node responsible for the communication between the ROS network and the Kortex-compatible Kinova robots. It publishes topics that users can subscribe to. It also advertises services that users can call from the command line or from their own code to configure or control the robot arm or its sub-devices (actuators, vision module, interface module). + +**Arguments**: +- **arm** : Name of your robot arm model. See the `kortex_description/arms` folder to see the available robot models. The default value is **gen3**. +- **dof** : Number of DOFs of your robot. The default value is for Gen3 is **7** and the default value for Gen3 lite is **6**. You will have to specify this value only if you have a Gen3 6DOF. +- **vision** : Boolean value to indicate if your arm has a Vision Module. The default value is for Gen3 is **true** and the default value for Gen3 lite is **false**. You will have to specify this value only if you have a Gen3 6DOF without a Vision Module. This argument only affects the visual representation of the arm in RViz. +- **gripper** : Name of your robot arm's tool / gripper. See the `kortex_description/grippers` folder to see the available end effector models (or to add your own). The default value is **""**. For Gen3, you can also put **robotiq_2f_85** or **robotiq_2f_140**. For Gen3 lite, the default (and only) gripper is **gen3_lite_2f**. +- **robot_name** : This is the namespace in which the driver will run. It defaults to **my_$(arg arm)** (so "my_gen3" for arm="gen3"). +- **prefix** : This is an optional prefix for all joint and link names in the kortex_description. It is used to allow differentiating between different arms in the same URDF. It defaults to **an empty string**. **Note** : Changing the prefix invalidates the MoveIt! configuration, and requires modifying said configuration, plus the .yaml files with harcoded joint names. +- **ip_address** : The IP address of the robot you're connecting to. The default value is **192.168.1.10**. +- **username** : The username for the robot connection. The default value is **admin**. +- **password** : The password for the robot connection. The default value is **admin**. +- **use_hard_limits** : [**Gen3 only**] If set to **true**, the arm's soft speed and acceleration limits are set to the hard limits and the MoveIt configuration uses those limits for the trajectories. If **false**, the default soft limit values are used. The default value for the parameter is **false**. **Be aware that setting this argument to true will set you arm's speed and acceleration limits to the maximum, so it will move way faster! Be cautious when using it for the first time as it may cause unwanted behaviour.** +- **cyclic_data_publish_rate** : Publish rate of the *base_feedback* and *joint_state* topics, in Hz. The default value is **100** Hz. +- **api_rpc_timeout_ms** : The default X-axis position of the robot in Gazebo. The default value is **0.0**. +- **api_session_inactivity_timeout_ms** : The duration after which the robot will clean the client session if the client hangs up the connection brutally (should not happen with the ROS driver). The default value is **35000** ms and is not normally changed. +- **api_connection_inactivity_timeout_ms** : The duration after which a connection is destroyed by the robot if no communication is detected between the client and the robot. The default value is **20000** ms and is not normally changed. +- **start_rviz** : If this argument is true, RViz will be launched. The default value is **true**. +- **start_moveit** : If this argument is true, a MoveIt! MoveGroup will be launched for the robot. The default value is **true**. + +- **default_goal_time_tolerance** : The default goal time tolerance for the `FollowJointTrajectory` action server, in seconds. This value is used if no default goal time tolerance is specified in the trajectory. The default value is **0.5** seconds. +- **default_goal_tolerance** : The default goal tolerance for the `FollowJointTrajectory` action server, in radians. This value is used if no default goal tolerance is specified in the trajectory for the joint positions reached at the end of the trajectory. The default value is **0.005** radians. + +To launch it with default arguments, run the following command in a terminal : + +`roslaunch kortex_driver kortex_driver.launch` + +To launch it with optional arguments, specify the argument name, then ":=", then the value you want. For example, : + +`roslaunch kortex_driver kortex_driver.launch ip_address:=10.0.100.239 start_rviz:=false robot_name:=terminator` + +You can also have a look at the [roslaunch documentation](http://wiki.ros.org/roslaunch/Commandline%20Tools) for more details. + +If everything goes well, you will see a "**The Kortex driver has been initialized correctly!**" message. If you also start MoveIt!, the `kortex_driver` output may be flooded in the `move_group` output, so pay attention to the warning and error messages! If the node fails to start for any reason, you will get an error message followed by a "**process has died**" message. + +You will read below about the topics and services the driver offers. To read more about how to use those tools, [go to the kortex_examples documentation](../kortex_examples/readme.md). + + +## Topics + +### Robot control topics (in) + +You can publish on those topics for joint or Cartesian velocity control of the robot. You can also quickly stop its motion, apply the emergency stop (which will trigger a robot Fault state) and clear the Fault state with the corresponding topics. + +**Note: the robot's high level commands function at a rate of 40Hz. This will be improved in a future release.** + +* **`/your_robot_name/in/joint_velocity`** + + Publishing joint velocities (radians/second) on this topic will move the arm until it reaches a limit, or until you send a zero-velocity command or a Stop. You can see the message description [here](msg/generated/base/JointSpeeds.msg). + + From the command line, with your robot name being "my_gen3", you can publish a joint velocity to joint 0 to this topic like so: + ``` + rostopic pub /my_gen3/in/joint_velocity kortex_driver/JointSpeeds "joint_speeds: + - joint_identifier: 0 + value: 0.57 + duration: 0" + ``` + +* **`/your_robot_name/in/cartesian_velocity`** + + Publishing a Cartesian velocity (meters/second for linear, rad/second for angular) on this topic will move the arm until it reaches a limit, or until you send a zero-velocity command or a Stop. You can see the message description [here](msg/generated/base/TwistCommand.msg). + + From the command line, with your robot name being "my_gen3", you can publish a twist to this topic like so: + ``` + rostopic pub /my_gen3/in/cartesian_velocity kortex_driver/TwistCommand "reference_frame: 0 + twist: {linear_x: 0.0, linear_y: 0.0, linear_z: 0.05, angular_x: 0.0, angular_y: 0.0, + angular_z: 0.0} + duration: 0" + ``` + +* **`/your_robot_name/in/clear_faults`** + + This clears the robot's fault state (if the faults are clearable). + + From the command line, with your robot name being "my_gen3", you can publish to this topic like so: + ``` + rostopic pub /my_gen3/in/clear_faults std_msgs/Empty "{}" + ``` + +* **`/your_robot_name/in/stop`** + + This stops the robot's motion smoothly. + + From the command line, with your robot name being "my_gen3", you can publish to this topic like so: + ``` + rostopic pub /my_gen3/in/stop std_msgs/Empty "{}" + ``` + +* **`/your_robot_name/in/emergency_stop`** + + This triggers a robot fault. + + From the command line, with your robot name being "my_gen3", you can publish to this topic like so: + ``` + rostopic pub /my_gen3/in/emergency_stop std_msgs/Empty "{}" + ``` + +### Robot feedback topics (out) + +The robot feedback topics are always published by the `kortex_driver`. You don't have to activate them. + +* **`/your_robot_name/kortex_error`** + + Every Kortex error will be published here. You can see the message description [here](msg/non_generated/KortexError.msg). + +* **`/your_robot_name/base_feedback`** + + The feedback from the robot is published on this topic at a rate of **cyclic_data_publish_rate**. You can see the message description [here](msg/generated/base_cyclic/BaseCyclic_Feedback.msg). + +* **`/your_robot_name/joint_state`** + + The feedback from the robot is converted to a [sensor_msgs/JointState](http://docs.ros.org/kinetic/api/sensor_msgs/html/msg/JointState.html) and published on this topic at a rate of **cyclic_data_publish_rate**. + +### Notification topics (out) + +The notification topics are only published by the `kortex_driver` if you activate them by first calling an activation service. Once activated, a notification topic will be activated until the node is shutdown. + +Subscribing to all the notifications causes a heavy load on the robot CPU. That is why the notification topics were designed in such a way. The users also typically only use one or two notifications, if at all. + +For example, if a user wants to subscribe to the **/my_robot_name/network_topic** (the message type is [NetworkNotification](msg/generated/base/NetworkNotification.msg)), he will have to: +1. Call the **/my_robot_name/base/activate_publishing_of_network_notification** service to enable the publishing of the topic +2. Subscribe to the **/my_robot_name/network_topic** topic +3. Process the notifications when he receives them in his code + + +## Services +Most of the services supported by this node are generated from the [C++ Kortex API](https://github.com/Kinovarobotics/kortex). You can find the documentation [here](https://github.com/Kinovarobotics/kortex/blob/master/api_cpp/doc/markdown/index.md). + +### Understanding packages + +The *.srv* files are generated in different sub-folders depending on the sub-module they affect. For example, all the RPC calls used to configure the vision module are generated in `srv/generated/vision_config` and all the RPC calls common to all devices are generated in `srv/generated/device_config`. Here is a list of the packages with a short explanation of the services they have to offer: + +* **actuator_config** : This package contains the functions used to configure a single actuator. +**Note:** To choose the actuator you want to configure, you have to call the **/my_robot_name/actuator_config/set_device_id** service and specify the device identifier of the actuator you want to configure. You get the device identifiers of actuators when you launch the node, when you parse the output of the [ReadAllDevices](srv/generated/device_manager/ReadAllDevices.srv) service or in the Kinova Kortex *Web App*. + +* **base** : This package contains : + * Services to read and update the configuration of the robot + * Services to send high level commands to the robot + * Services to read and update the Product Configuration + * Services to activate the publishing of notifications + * Services to read and update the user-related information +**Note:** The base high level commands are treated every 25 ms inside the robot. High level control cannot be achieved at a rate faster than 40 Hz for now. + +* **control_config** : This package contains the functions used to configure the control-related features on the robot. This includes : + * Reading and setting the cartesian reference frame + * Reading and setting the gravity vector + * Reading and setting the payload information + * Reading and setting the tool configuration + +* **device_config** : This package contains the functions used to configure a generic Kortex device. This includes : + * Reading and setting safety configurations + * Reading general information on the specified device (software versions, serial numbers, MAC address, IPv4 settings, etc.) +**Note:** To choose the device you want to configure, you have to call the **/my_robot_name/device_config/set_device_id** service and specify the device identifier of the device you want to configure. You get the device identifiers when you launch the node, when you parse the output of the [ReadAllDevices](srv/generated/device_manager/ReadAllDevices.srv) service or in the WebApp. + +* **device_manager** : This package contains [ReadAllDevices](srv/generated/device_manager/ReadAllDevices.srv) service, which is used to get the list of connected device and various informations on each device. + +* **interconnect_config** : This package contains the functions used to configure the interface module on the robot. +**Note:** You don't have to call the `SetDeviceID` service before calling the **interconnect_config** services, because the `kortex_driver` node goes through the list of connected devices and automatically sets the correct device ID for the **interconnect_config** services. + +* **vision_config** : This package contains the functions used to configure the vision module on the robot. +**Note:** You don't have to call the SetDeviceID service before calling the **vision_config** services, because the kortex_driver node goes through the list of connected devices and automatically sets the correct device ID for the **vision_config** services. + + +## Compatibility break between v1.1.7 and v2.0.0 + +Many things have been changed in the ros_kortex repository between versions 1.1.7 and 2.0.0 and you will have to modify your code if you don't want it to break. + +* The `kortex_actuator_driver`, `kortex_vision_config_driver` and `kortex_device_manager` packages were removed and only the `kortex_driver` package remains (one driver to rule them all). +* Since we only have one driver and the ROS message generation does not deal with namespaces, the messages and services that are duplicated are now named differently. For example, the **Feedback** message exists within the `BaseCyclic`, `ActuatorCyclic`, `InterconnectCyclic` and `GripperCyclic` Protocol Buffers .proto files. In ROS, this is now translated as a "PackageName_" prefix before the message name. So, for the **Feedback** message, the **BaseCyclic_Feedback**, **ActuatorCyclic_Feedback**, **InterconnectCyclic_Feedback** and **GripperCyclic_Feedback** ROS messages have been automatically generated. You may encounter build errors (in C++) or runtime errors (in Python) because of this change. You can just go in the `msg/generated` folder and look for the problematic message to find its new name to change the occurrences in your code. +* The services are now all **lowercase_with_underscores** instead of **UpperCase**. +* The services are now advertised in **/my_robot_name/my_package_name/desired_service** (see the [Services section](#services) to learn about the packages). You can also visualize it if you start the node and type `rosservice list` in a terminal. +* The topics are now all **lowercase_with_underscores** instead of **UpperCase**. +* The **/my_robot_name/base_feedback/joint_state** topic is now advertised as **/my_robot_name/joint_state**. +* The [kortex_driver launch file](launch/kortex_driver.launch) is now located in the `kortex_driver` package instead of the `kortex_bringup` package, which was deleted. Some arguments were added to the file. + + +## About Conan + +From release 2.2.0 onwards, the Kortex API is automatically downloaded from our Artifactory Conan server. The steps to install and setup Conan have been added to the root readme file. Conan downloads the binaries and header files in the Conan cache, by default situated in the `~/.conan/` directory. + +If you want to learn more about Conan, you can read about it [on their website](https://conan.io/). + +If you still want to download the ZIP files for the API, you can find the link in the [Kortex repository](https://github.com/Kinovarobotics/kortex). + +You will have to extract the API in the `kortex_api` folder as such: +```sh +kortex_api/ +┬ +├ include/ +└ lib/ +``` + +You will then have to build the catkin workspace and pass it the option to disable Conan so it links with your local API: +```sh +catkin_make -DUSE_CONAN=OFF +``` + + +## Support for multiple arms + +The [kortex_driver launch file](launch/kortex_driver.launch) is primarily used to define one-armed robots. +Having more than one arm requires prefixing the joints and links to protect against ambiguity when refering those. +To this end, a [kortex_dual_driver launch file](launch/kortex_dual_driver.launch) has been made to demonstrate running a two-armed robot. +The same pattern could be repeated to describe a robot with any number of arms. + +**Note**: This launch file is intended as a starting point showing how to launch a robot with two arms. When using this launch file for a specific robot, it should be modified to fit the robot's description. + +The launch file uses the same parameters as the one-armed version, except that most parameters are to be defined individually for each arm (with the **left_** and **right_** prefixes). + +The prefixes used in the joints and links names can be changed using the following parameters: +- `left_prefix` +- `right_prefix` + +The following parameters are to be specified for each robot (using `left_` and `right_` prefixes): +- `arm` +- `dof` +- `vision` +- `gripper` +- `ip_address` +- `username` +- `password` +- `cyclic_data_publish_rate` +- `api_rpc_timeout_ms` +- `api_session_inactivity_timeout_ms` +- `api_connection_inactivity_timeout_ms` +- `default_goal_time_tolerance` +- `default_goal_tolerance` + + +The folowing parameters are **NOT** to be prefixed: +- `robot_name` +- `start_rviz` +- `start_moveit` +- `cyclic_data_publish_rate` + +These parameters are common to both arms. + +Example use : `roslaunch kortex_driver kortex_dual_driver.launch robot_name:=terminator left_ip_address:=192.168.1.11 left_arm:=gen3 left_gripper:=robotiq_2f_85 right_ip_address:=192.168.1.12 right_arm:=gen3 right_gripper:=robotiq_2f_85 start_moveit:=false` + + + +## Generation (**advanced**) + +Some source code as well as most of the .MSG and .SRV files in this package are automatically generated, but the generated files are given on GitHub so that users don't have to generate them. However, if you have a special version of the Kortex API and want to generate those files yourself, it is possible. You will first need to follow the instructions to install Protocol Buffers. + +The generation process is based on a custom `protoc` plugin. Basically, most of the generation process is in the [scripts/ros_kortex_generator.py](scripts/ros_kortex_generator.py). Before launching the generation ensure that you have the Python JINJA2 module installed. + +To launch the generation of this package: + +1. Open a terminal window. +2. Browse the /scripts directory of this package +3. Ensure that the generate_protobuf_wrapper_files.sh file can be executed. If not then run: chmod +x generate_protobuf_wrapper_files.sh +4. Run the command: ./generate_protobuf_wrapper_files.sh +5. The result of the generation should be in the following folders: + * `/include/kortex_driver/generated` + * `/msg/generated` + * `/src/generated` + * `/srv/generated` + +### Protos files +The **protos** directory contains the Protobuf files from which the MSG, SRV and source files are generated. The content of this folder should not be modified. + +### Template files +The **templates** directory contains all the JINJA2 files needed by the `protoc` generator. diff --git a/ros_kortex/kortex_driver/scripts/generate_protobuf_wrapper_files.sh b/ros_kortex/kortex_driver/scripts/generate_protobuf_wrapper_files.sh new file mode 100755 index 0000000..4ef56cb --- /dev/null +++ b/ros_kortex/kortex_driver/scripts/generate_protobuf_wrapper_files.sh @@ -0,0 +1,6 @@ +#!/bin/sh + +export PYTHONUNBUFFERED=1 +mkdir build +protoc --plugin=protoc-gen-custom=ros_kortex_generator.py -I../protos/ --custom_out=./build ../protos/*.proto +rm -rf build diff --git a/ros_kortex/kortex_driver/scripts/ros_kortex_generator.py b/ros_kortex/kortex_driver/scripts/ros_kortex_generator.py new file mode 100755 index 0000000..8d46ad3 --- /dev/null +++ b/ros_kortex/kortex_driver/scripts/ros_kortex_generator.py @@ -0,0 +1,599 @@ +#!/usr/bin/env python3 +### +# KINOVA (R) KORTEX (TM) +# +# Copyright (c) 2019 Kinova inc. All rights reserved. +# +# This software may be modified and distributed +# under the terms of the BSD 3-Clause license. +# +# Refer to the LICENSE file for details. +# +### + +import sys + +from google.protobuf.compiler import plugin_pb2 as plugin +from google.protobuf import json_format as json_f + +import jinja2 + +import itertools +import json +import types +import os +import shutil +import sys +import re +from pathlib import PurePath + +from enum import Enum +from collections import OrderedDict + +from google.protobuf.descriptor_pb2 import DescriptorProto, EnumDescriptorProto, ServiceDescriptorProto, FieldDescriptorProto, OneofDescriptorProto +from google.protobuf.descriptor import FieldDescriptor +# Some names cause generation bugs and we have to hardcode them in here +# Reboot in Base.proto auto-generates the RebootRequest and RebootResponse classes, but RebootResponse RPC already exists in DeviceConfig.proto +# Refresh* RPCs have to be called at exactly 1kHz and ROS 1 cannot achieve this so they are removed +# RPCs for internal use have also been removed from the ROS driver +FORBIDDEN_RPC_METHODS = ["Reboot", \ + "Refresh", "RefreshCommand", "RefreshCustomData", "RefreshFeedback", \ + "ReadTorqueCalibration", "WriteTorqueCalibration", "GetVectorDriveParameters", "SetVectorDriveParameters", "GetEncoderDerivativeParameters", "SetEncoderDerivativeParameters", "StartFrequencyResponse", "StopFrequencyResponse", "StartStepResponse", "StopStepResponse", "StartRampResponse", "StopRampResponse", \ + "ReadCapSenseRegister", "WriteCapSenseRegister"] + +# There are some packages we don't want to generate because the use of their RPC's as ROS services doesn't make sense at all and could cause some undefined behaviour +NON_GENERATED_PACKAGES = ["Session"] +PROTO_FILES_RELATIVE_PATH = PurePath("..", "protos") + +class DetailedOneOf: + ''' + Class that holds a one_of and the fields in the one_of + + Attributes : + - name: Name of the one_of [string] + - fields: Protobuf FieldDescriptor's that are in the one_of [list of FieldDescriptorProto] + - duplicated_fields: Names of the fields that are duplicated in the generation context (ex. Feedback) [list of strings] + + Usage : Create the DetailedOneOf with its name, then use the addField() method to populate the fields list (automatically populates the duplicated_fields list) + ''' + def __init__(self, one_of_name = ""): + ''' + Constructor for the DetailedOneOf + + Arguments: + - one_of_name: Name of the one_of [string] + ''' + self.name = one_of_name + self.fields = [] + self.duplicated_fields = [] + + def addField(self, field, is_field_duplicated): + ''' + Adds a field to the one_of + + Arguments: + - field: Field to add [FieldDescriptor] + - is_field_duplicated: True if the field_type is duplicated in the generation context (ex. Feedback) [bool] + + Returns: None + ''' + self.fields.append(field) + if is_field_duplicated: + self.duplicated_fields.append(field.type_name.split(".")[-1]) + +class DetailedMessage: + ''' + Class that holds a message or an enum (all but a ServiceDescriptorProto) + + Attributes: + - name: Name of the message or enum [string] + - name_lowercase_with_underscores: Name of the message in lowercase with underscores (following the ROS convention) [string] + - message: Protobuf Descriptor [DescriptorProto] + - cpp_namespace: Full C++ namespace for the message (ex. Kinova::Api::Common) [string] + - full_proto_package_name: Full name of the Protobuf package with point delimiters (ex. Kinova.Api.Common) [string] + - duplicated_fields: Names of the fields that are duplicated in the generation context (ex. Feedback) [list of strings] + - containing_folder: Name of the subfolder in which the msg file will be generated, determined with the C++ namespace (ex. "ActuatorCyclic/"). If the namespace is Kinova::Api, then subfolder is equal to an empty string. [string] + - prepend_message_name: If the message is duplicated in the generation context, this attribute is in the form of "ActuatorCyclic_". This is prepended to the message name to ensure there is no naming clash during the ROS message generation. [string] + - one_of_list: List of DetailedOneOf's present in the message fields. [list of DetailedOneOf] + + Usage: Create the DetailedMessage, then use the addDetailedOneOf() method to populate the one_of_list attribute + ''' + def __init__(self, message, package, is_message_duplicated, duplicatedFields=[]): + ''' + Constructor for the DetailedMessage + + Arguments: + - message: Protobuf object for the message [DescriptorProto] + - package: Full name of the message's package (ex. "Kinova.Api.Common") [string] + - is_message_duplicated: True if the message type is duplicated in the generation context (ex. Feedback) [bool] + - duplicated_fields: Names of the fields that are duplicated in the generation context (ex. Feedback) (empty by default) [list of strings] + ''' + self.name = message.name + self.name_lowercase_with_underscores = '_'.join(re.findall('[A-Z][^A-Z]*', self.name)).lower() + self.message = message + + self.cpp_namespace = package.replace(".", "::") + self.full_proto_package_name = package + + # Some fields's type may be duplicated messages + self.duplicated_fields = [] + for df in duplicatedFields: + self.duplicated_fields.append(df.type_name.split(".")[-1]) + + # Sub-folder in which messages are generated + # Corresponds to the Protobuf Service they relate to + # Those without a service (Frame, Errors) are generated directly in /msg + self.containing_folder = "_".join(re.findall('[A-Z][^A-Z]*', package.split(".")[-1])).lower() + "/" + if self.containing_folder == "api/": + self.containing_folder = "" + + # If it is a duplicated message, we prepend it with the Protobuf Service name (because ROS messages don't handle C++ namespaces) + if is_message_duplicated: + self.prepend_message_name = package.split(".")[-1] + "_" + else: + self.prepend_message_name = "" + + # List of all the DetailedOneof's in the message + self.one_of_list = [] + + # Method to add the DetailedOneOf's in the DetailedMessage + def addDetailedOneOf(self, one_of): + ''' + Adds a DetailedOneOf to the message's one_of_list + + Arguments: + - one_of: One_of to add to the message [DetailedOneOf] + + Returns: None + ''' + self.one_of_list.append(one_of) + + def isEnum(self): + ''' + Returns True if the message is an enum (Protobuf message is of type EnumDescriptorProto) + + Arguments: None + + Returns: Boolean + ''' + return isinstance(self.message, EnumDescriptorProto) + +# Class that holds a protobuf service and some other details needed by the generator(Jinja2 template) +class DetailedPackage: + ''' + Class that holds a Protobuf package + + Attributes: + - name: Name of the package delimited with points (ex. "Kinova.Api.Common") [string] + - short_name: Short name of the package (ex. "Common" for "Kinova.Api.Common") [string] + - short_name_lowercase_with_underscores: Short name of the package in lowercase with underscores (following the ROS convention) [string] + - cpp_namespace: Full C++ namespace for the package (ex. Kinova::Api::Common) [string] + - messages: List of messages in the package [list of DetailedMessage] + - methods: List of RPC methods in the package [list of DetailedRPC] + - enums: List of enums in the package [list of DetailedMessage] + + Usage: Create the DetailedPackage, then add the messages, enums and RPC's with the corresponding methods. + ''' + def __init__(self, package): + ''' + Constructor for the DetailedPackage + + Arguments: + - package: Full name of the message's package (ex. "Kinova.Api.Common") [string] + ''' + self.name = package + self.short_name = self.name.split(".")[-1] + self.short_name_lowercase_with_underscores = '_'.join(re.findall('[A-Z][^A-Z]*', self.short_name)).lower() + self.cpp_namespace = self.name.replace(".", "::") + self.messages = [] # list of DetailedMessage + self.methods = [] # list of DetailedRPC + self.enums = [] # list of DetailedMessage + + def addMessage(self, detailed_message): + ''' + Adds a message to the package's messages list + + Arguments: + - detailed_message: Message to add to the package [DetailedMessage] + + Returns: None + ''' + self.messages.append(detailed_message) + + def addRPC(self, detailed_rpc): + ''' + Adds a RPC to the package's methods list + + Arguments: + - detailed_rpc: RPC to add to the package [DetailedRPC] + + Returns: None + ''' + self.methods.append(detailed_rpc) + + def addEnum(self, detailed_enum): + ''' + Adds an enum to the package's enums list + + Arguments: + - detailed_enum: Enum to add to the package [DetailedMessage] + + Returns: None + ''' + self.enums.append(detailed_enum) + +class DetailedRPC: + ''' + Class that holds a Protobuf RPC + + Attributes: + - name: Name of the RPC [string] + - name_lowercase_with_underscores: Name of the RPC in lowercase with underscores (following the ROS convention) [string] + - rpc: Protobuf object for the RPC [ServiceDescriptorProto] + - cpp_namespace: Full C++ namespace for the RPC (ex. Kinova::Api::BaseCyclic) [string] + - full_proto_package_name: Full name of the Protobuf package with point delimiters (ex. Kinova.Api.Common) [string] + - is_rpc_duplicated: True if the message type is duplicated in the generation context (ex. Feedback) [bool] + - prepend_rpc_package_name: If the RPC is duplicated in the generation context, this string will be populated with the RPC package's short name (ex. "BaseCyclic_" for Feedback RPC). Empty otherwise. [string] + + - is_input_type_duplicated: True if the input type of the RPC is duplicated in the generation context [bool] + - ros_service_input_name: Type of the ROS service input, modified according to the is_input_type_duplicated parameter [string] + - input_type_short_name: Short name of the input (ex. "Command" for "Kinova.Api.BaseCyclic.Command") [string] + - input_type_cpp_namespace: Full C++ namespace for the RPC (ex. Kinova::Api::BaseCyclic) [string] + + - is_output_type_duplicated: True if the output type of the RPC is duplicated in the generation context [bool] + - ros_service_output_name: Type of the ROS service output, modified according to the is_output_type_duplicated parameter [string] + - output_type_short_name: Short name of the output (ex. "Feedback" for "Kinova.Api.BaseCyclic.Feedback") [string] + - output_type_cpp_namespace: Full C++ namespace for the RPC (ex. Kinova::Api::BaseCyclic) [string] + + - is_notification_rpc: True if the RPC is a Notification RPC (ends with "Topic") + - prepend_on_notification: If the RPC is a Notification RPC, is put to "OnNotification". Otherwise, it is empty [string] + - notification_message_cpp_namespace: Full C++ namespace of the message that corresponds to the Notification RPC ("SafetyNotification" for the RPC "SafetyTopic") [string] + ''' + def __init__(self, rpc, package, is_rpc_duplicated, is_rpc_deprecated, is_input_type_duplicated, is_output_type_duplicated, notification_message=None): + ''' + Constructor for the DetailedRPC + + Arguments: + - rpc: Protobuf object for the RPC [ServiceDescriptorProto] + - package: Full name of the message's package (ex. "Kinova.Api.Common") [string] + - is_rpc_duplicated: True if the message type is duplicated in the generation context (ex. Feedback) [bool] + - is_rpc_deprecated: True if the message type is deprecated in the C++ Kortex API [bool] + - is_input_type_duplicated: True if the input type of the RPC is duplicated in the generation context [bool] + - is_output_type_duplicated: True if the output type of the RPC is duplicated in the generation context [bool] + - notification_message: Protobuf object for the Notification message that corresponds to the Notification RPC (optional) [DescrptorProto] + ''' + self.name = rpc.name + self.name_lowercase_with_underscores = '_'.join(re.findall('[A-Z][^A-Z]*', self.name)).lower() + self.rpc = rpc + self.is_rpc_deprecated = is_rpc_deprecated + + self.cpp_namespace = package.replace(".", "::") + self.full_proto_package_name = package + + # If it is a duplicated RPC, we prepend it with the Protobuf Service name (because ROS services don't handle C++ namespaces) + if is_rpc_duplicated: + self.prepend_rpc_package_name = package.split(".")[-1] + "_" + else: + self.prepend_rpc_package_name = "" + + # Helper variables for input and output types + if is_input_type_duplicated: + self.ros_service_input_name = rpc.input_type.split(".")[-2] + "_" + rpc.input_type.split(".")[-1] + else: + self.ros_service_input_name = rpc.input_type.split(".")[-1] + + + self.input_type_short_name = rpc.input_type.split(".")[-1] + self.input_type_cpp_namespace = "::".join(rpc.input_type.split(".")[:-1])[2:] + + if is_output_type_duplicated: + self.ros_service_output_name = rpc.output_type.split(".")[-2] + "_" + rpc.output_type.split(".")[-1] + else: + self.ros_service_output_name = rpc.output_type.split(".")[-1] + + self.output_type_short_name = rpc.output_type.split(".")[-1] + self.output_type_cpp_namespace = "::".join(rpc.output_type.split(".")[:-1])[2:] + + # Notifications have the word 'Topic' at the end of the RPC name + self.is_notification_rpc = re.match(r"\w+Topic", rpc.name) + if self.is_notification_rpc: + self.prepend_on_notification = "OnNotification" + self.notification_message_cpp_namespace = notification_message[0].cpp_namespace + else: + self.prepend_on_notification = "" + self.notification_message_cpp_namespace = "" + +# Jinja2 function to render a file from a template +def render(tpl_path, context): + path, filename = os.path.split(tpl_path) + return jinja2.Environment(loader=jinja2.FileSystemLoader(path or './')).get_template(filename).render(**context) + +# Main plugin function +def generate_code(request, response): + + # MainFilePath = os.path.join(".", "src/main.cpp") + # Find all proto files + file_map = OrderedDict() + for proto_file in request.proto_file: + file_map[proto_file.name] = proto_file + + # Create an ordered dictionary for all Protobuf packages + packages_dict = OrderedDict() + + # Find the *Notification messages to add them to a list + notification_messages_list = [] + + # Find Messages and RPC's that have the same name within the proto files because ROS doesn't handle namespaces + messages_unordered_set = set() + rpcs_unordered_set = set() + duplicated_messages_unordered_set = set() + duplicated_rpcs_unordered_set = set() + deprecated_rpcs_dict_of_lists = OrderedDict() + for filename, proto_file in file_map.items(): + # Traverse proto files with the recursive calls + for item, package in traverse(proto_file): + + # Skip the packages we don't want to generate + if package.split(".")[-1] in NON_GENERATED_PACKAGES: + continue + + packages_dict[package] = DetailedPackage(package) + # If the item is a message or an enum + if not isinstance(item, ServiceDescriptorProto): + if item.name not in messages_unordered_set: + messages_unordered_set.add(item.name) + # Add the notifications to a list to match them to their respective RPCs later (because there package may differ from the RPC's) + if re.match(r"\w+Notification", item.name): + notification_messages_list.append(DetailedMessage(item, package, False)) + else: + duplicated_messages_unordered_set.add(item.name) + # If the item is a Protobuf service (a collection of methods) + else: + for method in item.method: + if method.name not in rpcs_unordered_set: + rpcs_unordered_set.add(method.name) + else: + duplicated_rpcs_unordered_set.add(method.name) + + # Parse through the proto files to find deprecation tags that the recursive function cannot find + proto_file_reader = open(str(PurePath(PROTO_FILES_RELATIVE_PATH, filename)), encoding='utf8', mode='r') + filename_without_extension = filename.replace('.proto', '') + deprecated_rpcs_dict_of_lists[filename_without_extension] = list() + RPC_REGULAR_EXPRESSION = r'.*rpc (\w*) * \((\S*)\) *returns* \((\S*)\).*' + text_line = "_" + while text_line != "": + text_line = proto_file_reader.readline() + if "rpc " in text_line: + if re.search(r'@DEPRECATED', text_line): + rpc_name = re.sub(RPC_REGULAR_EXPRESSION, r'\1', text_line).strip() + deprecated_rpcs_dict_of_lists[filename_without_extension].append(rpc_name) + + # print (deprecated_rpcs_dict_of_lists.items()) + + # Remove old generated files and create new directories + for package in packages_dict.values(): + for s in ['srv', 'msg']: + shutil.rmtree("../{}/generated/{}".format(s, package.short_name_lowercase_with_underscores), ignore_errors=True) + os.makedirs("../{}/generated/{}".format(s, package.short_name_lowercase_with_underscores)) + shutil.rmtree("../src/generated", ignore_errors=True) + shutil.rmtree("../include/kortex_driver/generated", ignore_errors=True) + os.makedirs("../src/generated/robot") + os.makedirs("../src/generated/simulation") + os.makedirs("../include/kortex_driver/generated/interfaces") + os.makedirs("../include/kortex_driver/generated/robot") + os.makedirs("../include/kortex_driver/generated/simulation") + + ########################################### + # Parse the proto files to add the messages and RPC's to the DetailedPackage's + for filename, proto_file in file_map.items(): + + # For every item in the current proto file + for item, package in traverse(proto_file): + + # Skip the packages we don't want to generate + if package.split(".")[-1] in NON_GENERATED_PACKAGES: + continue + + current_package = packages_dict[package] + + # If this is an enum + if isinstance(item, EnumDescriptorProto): + is_enum_duplicated = item.name in duplicated_messages_unordered_set + current_package.addEnum(DetailedMessage(item, package, is_enum_duplicated)) + + # If this is a message + if isinstance(item, DescriptorProto): + is_message_duplicated = item.name in duplicated_messages_unordered_set + duplicated_fields = filter(lambda x : x.type_name.split(".")[-1] in duplicated_messages_unordered_set, item.field) + temp_message = DetailedMessage(item, package, is_message_duplicated, duplicated_fields) + # Find if the message contains oneof + message_contains_one_of = False + for member in item.field: + # If a member is part of a one_of, it will have this additional field. + if member.HasField("oneof_index"): + message_contains_one_of = True + break + + # Register every one_of in the message + if message_contains_one_of: + + # Find the one_of names + for one_of in item.ListFields()[-1][1]: # This is the very obscure way to get the one_of's name + temp_message.one_of_list.append(DetailedOneOf(one_of.name)) + + # Find the fields and what one_of they belong to + for member in item.field: + # If a member is part of a one_of, add it to the DetailedOneOf it belongs to + if member.HasField("oneof_index"): + is_field_duplicated = member.type_name.split(".")[-1] in duplicated_messages_unordered_set + temp_message.one_of_list[member.oneof_index].addField(member, is_field_duplicated) + + current_package.addMessage(temp_message) + + # If this is a Protobuf service (a group of RPC's) + if isinstance(item, ServiceDescriptorProto): + # Get sublist of all deprecated methods in this service + deprecated_rpcs_in_this_service = deprecated_rpcs_dict_of_lists[item.name] + # Register every RPC in the Protobuf service + for rpc in item.method: + # Do not generate the services that cause generation bugs + if rpc.name in FORBIDDEN_RPC_METHODS: + continue + is_rpc_duplicated = rpc.name in duplicated_rpcs_unordered_set + is_input_type_duplicated = rpc.input_type.split(".")[-1] in duplicated_messages_unordered_set + is_output_type_duplicated = rpc.output_type.split(".")[-1] in duplicated_messages_unordered_set + notification_message = list(filter(lambda x: x.name == rpc.name.replace("Topic", "Notification") , notification_messages_list)) + + # Find out if this RPC is deprecated + is_rpc_deprecated = True if rpc.name in deprecated_rpcs_in_this_service else False + + temp_rpc = DetailedRPC(rpc, package, is_rpc_duplicated, is_rpc_deprecated, is_input_type_duplicated, is_output_type_duplicated, notification_message) + current_package.addRPC(temp_rpc) + + ########################################### + # Generate the include names with the packages that contain messages + packages_with_messages = filter(lambda x: len(x.messages) > 0 , packages_dict.values()) + include_file_names = [] + for p in packages_with_messages: + for s in ["proto", "ros"]: + include_file_names.append("kortex_driver/generated/robot/{}_{}_converter.h".format(p.short_name.lower(), s)) + + # Generate the ROS files for each package + for package in packages_dict.values(): + + # Generate the enums + for enum in package.enums: + this_enum_context = types.SimpleNamespace() + this_enum_context.item = enum + ros_enum_path = os.path.join("..", "msg/generated/{}{}{}.msg".format(enum.containing_folder, enum.prepend_message_name, enum.name)) + with open(ros_enum_path, 'wt') as serviceFile: + serviceFile.write(render("../templates/ros_enum.msg.jinja2", this_enum_context.__dict__)) + + # Generate the messages + for message in package.messages: + this_message_context = types.SimpleNamespace() + this_message_context.item = message + this_message_context.field_descriptor_class = FieldDescriptor + + # Generate the one_of's for the message + for detailed_one_of in message.one_of_list: # not empty + this_message_context.detailed_one_of = detailed_one_of + ros_oneofPath = os.path.join("..", "msg/generated/{}{}{}_{}.msg".format(message.containing_folder, message.prepend_message_name, message.name, detailed_one_of.name)) + with open(ros_oneofPath, 'wt') as serviceFile: + serviceFile.write(render("../templates/ros_oneof.msg.jinja2", this_message_context.__dict__)) + + # Generate the message + ros_messagePath = os.path.join("..", "msg/generated/{}{}{}.msg".format(message.containing_folder, message.prepend_message_name, message.name)) + with open(ros_messagePath, 'wt') as serviceFile: + serviceFile.write(render("../templates/ros_message.msg.jinja2", this_message_context.__dict__)) + + # Generate the RPC's + for rpc in package.methods: + this_rpc_context = types.SimpleNamespace() + this_rpc_context.item = rpc + ros_servicePath = os.path.join("..", "srv/generated/{}/{}{}{}.srv".format(package.short_name_lowercase_with_underscores, rpc.prepend_rpc_package_name, rpc.prepend_on_notification, rpc.name)) + with open(ros_servicePath, 'wt') as serviceFile: + serviceFile.write(render("../templates/ros_service.srv.jinja2", this_rpc_context.__dict__)) + + # Generate the Proto-ROS converters (C++ files) + this_package_context = types.SimpleNamespace() + this_package_context.package = package + + if package.messages: # package contains at least one message + # Proto converter header file + current_header_filename = "kortex_driver/generated/robot/{}_proto_converter.h".format(package.short_name.lower()) + this_package_context.include_file_names = filter(lambda x : "proto_converter" in x and x != current_header_filename, include_file_names) + with open(os.path.join("..", "include/" + current_header_filename), 'wt') as converterFile: + converterFile.write(render("../templates/proto_converter.h.jinja2", this_package_context.__dict__)) + # Proto converter cpp file + this_package_context.current_header_filename = current_header_filename + with open(os.path.join("..", "src/generated/robot/{}_proto_converter.cpp".format(package.short_name.lower())), 'wt') as converterFile: + converterFile.write(render("../templates/proto_converter.cpp.jinja2", this_package_context.__dict__)) + # ROS converter header file + current_header_filename = "kortex_driver/generated/robot/{}_ros_converter.h".format(package.short_name.lower()) + this_package_context.include_file_names = filter(lambda x : "ros_converter" in x and x != current_header_filename, include_file_names) + with open(os.path.join("..", "include/" + current_header_filename), 'wt') as converterFile: + converterFile.write(render("../templates/ros_converter.h.jinja2", this_package_context.__dict__)) + # ROS converter cpp file + this_package_context.current_header_filename = current_header_filename + with open(os.path.join("..", "src/generated/robot/{}_ros_converter.cpp".format(package.short_name.lower())), 'wt') as converterFile: + converterFile.write(render("../templates/ros_converter.cpp.jinja2", this_package_context.__dict__)) + + # Generate the ServiceProxy's for every Kortex API method + if package.methods: # package contains at least one RPC + # Generate interface files + current_header_filename = "kortex_driver/generated/interfaces/{}_services_interface.h".format(package.short_name.lower()) + current_interface_header_filename = current_header_filename + this_package_context.current_interface_header_filename = current_interface_header_filename + with open(os.path.join("..", "include/" + current_header_filename), 'wt') as services_file: + services_file.write(render("../templates/services_interface.h.jinja2", this_package_context.__dict__)) + + # Generate robot files + current_header_filename = "kortex_driver/generated/robot/{}_services.h".format(package.short_name.lower()) + this_package_context.current_header_filename = current_header_filename + this_package_context.include_file_names = include_file_names + with open(os.path.join("..", "include/" + current_header_filename), 'wt') as services_file: + services_file.write(render("../templates/services_robot.h.jinja2", this_package_context.__dict__)) + with open(os.path.join("..", "src/generated/robot/{}_services.cpp".format(package.short_name.lower())), 'wt') as services_file: + services_file.write(render("../templates/services_robot.cpp.jinja2", this_package_context.__dict__)) + + # Generate simulation files + current_header_filename = "kortex_driver/generated/simulation/{}_services.h".format(package.short_name.lower()) + this_package_context.current_header_filename = current_header_filename + this_package_context.include_file_names = include_file_names + with open(os.path.join("..", "include/" + current_header_filename), 'wt') as services_file: + services_file.write(render("../templates/services_simulation.h.jinja2", this_package_context.__dict__)) + with open(os.path.join("..", "src/generated/simulation/{}_services.cpp".format(package.short_name.lower())), 'wt') as services_file: + services_file.write(render("../templates/services_simulation.cpp.jinja2", this_package_context.__dict__)) + + # Delete unused folders we created for None + for package in packages_dict.values(): + for s in ['srv', 'msg']: + if len(os.listdir('../{}/generated/{}'.format(s, package.short_name_lowercase_with_underscores))) == 0: + shutil.rmtree("../{}/generated/{}".format(s, package.short_name_lowercase_with_underscores)) + +def traverse(proto_file): + # recursive function that browses a protobof item + def _traverse(package, items): + for item in items: + yield item, package + + if isinstance(item, DescriptorProto): + for enum in item.enum_type: + yield enum, package + + for nested in item.nested_type: + nested_package = package + item.name + + for nested_item in _traverse(nested, nested_package): + yield nested_item, nested_package + if isinstance(item, ServiceDescriptorProto): + for rpc in item.method: + yield rpc, package + + # returns a list of everything found in the proto file + return itertools.chain( + _traverse(proto_file.package, proto_file.enum_type), + _traverse(proto_file.package, proto_file.message_type), + _traverse(proto_file.package, proto_file.service), + ) + +if __name__ == '__main__': + # reads request message from stdin + data = sys.stdin.buffer.read() + + # parses request + request = plugin.CodeGeneratorRequest() + request.ParseFromString(data) + + # creates response + response = plugin.CodeGeneratorResponse() + + # generates code + generate_code(request, response) + + # serialises response message + output = response.SerializeToString() + + # writes to stdout + sys.stdout.buffer.write(output) \ No newline at end of file diff --git a/ros_kortex/kortex_driver/scripts/source_and_build_workspace.bash b/ros_kortex/kortex_driver/scripts/source_and_build_workspace.bash new file mode 100755 index 0000000..0730101 --- /dev/null +++ b/ros_kortex/kortex_driver/scripts/source_and_build_workspace.bash @@ -0,0 +1,9 @@ +#!/bin/bash + +# This is a helper script that sources ROS, cleans and builds the catkin workspace +# It is meant to be run from the root of the workspace +# Can be used by end users, but mainly used because Docker (for CI) needs en executable file and cannot take multiple bash commands + +source /opt/ros/kinetic/setup.bash +rm -rf devel/ build/ +catkin_make -DGENERATE_PROTO_ROS_WRAPPER=OFF diff --git a/ros_kortex/kortex_driver/scripts/tests/build_workspace_and_tests.bash b/ros_kortex/kortex_driver/scripts/tests/build_workspace_and_tests.bash new file mode 100755 index 0000000..98ab2ed --- /dev/null +++ b/ros_kortex/kortex_driver/scripts/tests/build_workspace_and_tests.bash @@ -0,0 +1,12 @@ +#!/bin/bash + +# This is a helper script that sources ROS, cleans and builds the catkin workspace and the tests, and installs the missing rosdep +# It is meant to be run from the root of the workspace +rosdep update +apt-get update +rosdep -y install --from-paths src --ignore-src +rm -rf devel/ build/ +catkin_make +catkin_make tests +echo 'Finished building the package!' +exit 0 diff --git a/ros_kortex/kortex_driver/scripts/tests/launch_test.py b/ros_kortex/kortex_driver/scripts/tests/launch_test.py new file mode 100644 index 0000000..4abdd9f --- /dev/null +++ b/ros_kortex/kortex_driver/scripts/tests/launch_test.py @@ -0,0 +1,67 @@ +#!/usr/bin/env python3 +import argparse +import subprocess +import time +import os +import signal + +# Get arguments +parser = argparse.ArgumentParser(description='Launch ROS examples or ROS driver automated tests for a given arm configuration.') +parser.add_argument('--no-vision', action='store_true', help='Add this option if the arm doesn\'t have a vision module') +parser.add_argument('ip', type = str, help='Arm IP address (enter \'none\' if testing Gazebo)') +parser.add_argument('arm', choices = ['gen3', 'gen3_lite'], help='Arm type') +parser.add_argument('dof', type = int, help='Number of DOF for the arm') +parser.add_argument('gripper', choices = ['robotiq_2f_85', 'robotiq_2f_140', 'gen3_lite_2f', 'none'], help='Gripper type') +parser.add_argument('test_case', choices = ['driver', 'examples', 'gazebo'], help='Test case to run') + +args = parser.parse_args() + +# Create the command for the driver +command = [] +if args.test_case == 'driver' or args.test_case == 'examples': + if args.test_case == 'driver': + command.append("rostest") + command.append("--reuse-master") + elif args.test_case == 'examples': + command.append("roslaunch") + command.append("kortex_driver") + command.append("kortex_driver.launch") + command.append("ip_address:={}".format(args.ip)) + command.append("start_moveit:=true") +elif args.test_case == 'gazebo': + command.append("rostest") + command.append("--reuse-master") + command.append("kortex_gazebo") + command.append("spawn_kortex_robot.launch") + command.append("gazebo_gui:=false") + command.append("start_delay_seconds:=20") #longer load time for Gazebo in Docker +command.append("start_rviz:=false") +command.append("arm:={}".format(args.arm)) +command.append("dof:={}".format(args.dof)) +# Add vision option +if args.no_vision: + command.append("vision:=false") +else: + command.append("vision:=true") +# Add gripper option +if args.gripper != 'none': + command.append("gripper:={}".format(args.gripper)) + +try: + ros_master_process = subprocess.Popen(['roscore'], stdout=subprocess.DEVNULL) + time.sleep(3) + # If we want to run the tests for the driver + if args.test_case == 'driver': + subprocess.run(command) + # If we want to test the examples + elif args.test_case == 'examples': + driver_roslaunch_process = subprocess.Popen(command, stdout=subprocess.DEVNULL) + print ("Starting the ROS Kortex driver...") + time.sleep(10) + examples_tests_process = subprocess.Popen(['rostest', '--reuse-master', 'kortex_examples', 'run_all_examples.launch', 'robot_name:=my_{}'.format(args.arm)]) + examples_tests_process.wait() + elif args.test_case == 'gazebo': + subprocess.run(command) + +finally: + os.killpg(os.getpid(), signal.SIGTERM) diff --git a/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_proto_converter.cpp new file mode 100644 index 0000000..454a5fa --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_proto_converter.cpp @@ -0,0 +1,189 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" + +int ToProtoData(kortex_driver::AxisPosition input, Kinova::Api::ActuatorConfig::AxisPosition *output) +{ + + output->set_position(input.position); + + return 0; +} +int ToProtoData(kortex_driver::AxisOffsets input, Kinova::Api::ActuatorConfig::AxisOffsets *output) +{ + + output->set_absolute_offset(input.absolute_offset); + output->set_relative_offset(input.relative_offset); + + return 0; +} +int ToProtoData(kortex_driver::TorqueCalibration input, Kinova::Api::ActuatorConfig::TorqueCalibration *output) +{ + + output->set_global_gain(input.global_gain); + output->set_global_offset(input.global_offset); + output->clear_gain(); + for(int i = 0; i < input.gain.size(); i++) + { + output->add_gain(input.gain[i]); + } + output->clear_offset(); + for(int i = 0; i < input.offset.size(); i++) + { + output->add_offset(input.offset[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::TorqueOffset input, Kinova::Api::ActuatorConfig::TorqueOffset *output) +{ + + output->set_torque_offset(input.torque_offset); + + return 0; +} +int ToProtoData(kortex_driver::ActuatorConfig_ControlModeInformation input, Kinova::Api::ActuatorConfig::ControlModeInformation *output) +{ + + output->set_control_mode((Kinova::Api::ActuatorConfig::ControlMode)input.control_mode); + + return 0; +} +int ToProtoData(kortex_driver::ControlLoop input, Kinova::Api::ActuatorConfig::ControlLoop *output) +{ + + output->set_control_loop(input.control_loop); + + return 0; +} +int ToProtoData(kortex_driver::LoopSelection input, Kinova::Api::ActuatorConfig::LoopSelection *output) +{ + + output->set_loop_selection((Kinova::Api::ActuatorConfig::ControlLoopSelection)input.loop_selection); + + return 0; +} +int ToProtoData(kortex_driver::VectorDriveParameters input, Kinova::Api::ActuatorConfig::VectorDriveParameters *output) +{ + + output->set_kpq(input.kpq); + output->set_kiq(input.kiq); + output->set_kpd(input.kpd); + output->set_kid(input.kid); + + return 0; +} +int ToProtoData(kortex_driver::EncoderDerivativeParameters input, Kinova::Api::ActuatorConfig::EncoderDerivativeParameters *output) +{ + + output->set_max_window_width(input.max_window_width); + output->set_min_angle(input.min_angle); + + return 0; +} +int ToProtoData(kortex_driver::ControlLoopParameters input, Kinova::Api::ActuatorConfig::ControlLoopParameters *output) +{ + + output->set_loop_selection((Kinova::Api::ActuatorConfig::ControlLoopSelection)input.loop_selection); + output->set_error_saturation(input.error_saturation); + output->set_output_saturation(input.output_saturation); + output->clear_kaz(); + for(int i = 0; i < input.kAz.size(); i++) + { + output->add_kaz(input.kAz[i]); + } + output->clear_kbz(); + for(int i = 0; i < input.kBz.size(); i++) + { + output->add_kbz(input.kBz[i]); + } + output->set_error_dead_band(input.error_dead_band); + + return 0; +} +int ToProtoData(kortex_driver::FrequencyResponse input, Kinova::Api::ActuatorConfig::FrequencyResponse *output) +{ + + output->set_loop_selection((Kinova::Api::ActuatorConfig::ControlLoopSelection)input.loop_selection); + output->set_min_frequency(input.min_frequency); + output->set_max_frequency(input.max_frequency); + output->set_amplitude(input.amplitude); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::StepResponse input, Kinova::Api::ActuatorConfig::StepResponse *output) +{ + + output->set_loop_selection((Kinova::Api::ActuatorConfig::ControlLoopSelection)input.loop_selection); + output->set_amplitude(input.amplitude); + output->set_step_delay(input.step_delay); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::RampResponse input, Kinova::Api::ActuatorConfig::RampResponse *output) +{ + + output->set_loop_selection((Kinova::Api::ActuatorConfig::ControlLoopSelection)input.loop_selection); + output->set_slope(input.slope); + output->set_ramp_delay(input.ramp_delay); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::CustomDataSelection input, Kinova::Api::ActuatorConfig::CustomDataSelection *output) +{ + + output->clear_channel(); + for(int i = 0; i < input.channel.size(); i++) + { + output->add_channel((Kinova::Api::ActuatorConfig::CustomDataIndex)input.channel[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::CommandModeInformation input, Kinova::Api::ActuatorConfig::CommandModeInformation *output) +{ + + output->set_command_mode((Kinova::Api::ActuatorConfig::CommandMode)input.command_mode); + + return 0; +} +int ToProtoData(kortex_driver::Servoing input, Kinova::Api::ActuatorConfig::Servoing *output) +{ + + output->set_enabled(input.enabled); + + return 0; +} +int ToProtoData(kortex_driver::PositionCommand input, Kinova::Api::ActuatorConfig::PositionCommand *output) +{ + + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_acceleration(input.acceleration); + + return 0; +} +int ToProtoData(kortex_driver::CoggingFeedforwardModeInformation input, Kinova::Api::ActuatorConfig::CoggingFeedforwardModeInformation *output) +{ + + output->set_cogging_feedforward_mode((Kinova::Api::ActuatorConfig::CoggingFeedforwardMode)input.cogging_feedforward_mode); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_ros_converter.cpp new file mode 100644 index 0000000..d6fbfea --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_ros_converter.cpp @@ -0,0 +1,225 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" + +int ToRosData(Kinova::Api::ActuatorConfig::AxisPosition input, kortex_driver::AxisPosition &output) +{ + + output.position = input.position(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::AxisOffsets input, kortex_driver::AxisOffsets &output) +{ + + output.absolute_offset = input.absolute_offset(); + output.relative_offset = input.relative_offset(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::TorqueCalibration input, kortex_driver::TorqueCalibration &output) +{ + + output.global_gain = input.global_gain(); + output.global_offset = input.global_offset(); + output.gain.clear(); + for(int i = 0; i < input.gain_size(); i++) + { + output.gain.push_back(input.gain(i)); + } + output.offset.clear(); + for(int i = 0; i < input.offset_size(); i++) + { + output.offset.push_back(input.offset(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::TorqueOffset input, kortex_driver::TorqueOffset &output) +{ + + output.torque_offset = input.torque_offset(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::ControlModeInformation input, kortex_driver::ActuatorConfig_ControlModeInformation &output) +{ + + output.control_mode = input.control_mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::ControlLoop input, kortex_driver::ControlLoop &output) +{ + + output.control_loop = input.control_loop(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::LoopSelection input, kortex_driver::LoopSelection &output) +{ + + output.loop_selection = input.loop_selection(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::VectorDriveParameters input, kortex_driver::VectorDriveParameters &output) +{ + + output.kpq = input.kpq(); + output.kiq = input.kiq(); + output.kpd = input.kpd(); + output.kid = input.kid(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::EncoderDerivativeParameters input, kortex_driver::EncoderDerivativeParameters &output) +{ + + output.max_window_width = input.max_window_width(); + output.min_angle = input.min_angle(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::ControlLoopParameters input, kortex_driver::ControlLoopParameters &output) +{ + + output.loop_selection = input.loop_selection(); + output.error_saturation = input.error_saturation(); + output.output_saturation = input.output_saturation(); + output.kAz.clear(); + for(int i = 0; i < input.kaz_size(); i++) + { + output.kAz.push_back(input.kaz(i)); + } + output.kBz.clear(); + for(int i = 0; i < input.kbz_size(); i++) + { + output.kBz.push_back(input.kbz(i)); + } + output.error_dead_band = input.error_dead_band(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::FrequencyResponse input, kortex_driver::FrequencyResponse &output) +{ + + output.loop_selection = input.loop_selection(); + output.min_frequency = input.min_frequency(); + output.max_frequency = input.max_frequency(); + output.amplitude = input.amplitude(); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::StepResponse input, kortex_driver::StepResponse &output) +{ + + output.loop_selection = input.loop_selection(); + output.amplitude = input.amplitude(); + output.step_delay = input.step_delay(); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::RampResponse input, kortex_driver::RampResponse &output) +{ + + output.loop_selection = input.loop_selection(); + output.slope = input.slope(); + output.ramp_delay = input.ramp_delay(); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::CustomDataSelection input, kortex_driver::CustomDataSelection &output) +{ + + output.channel.clear(); + for(int i = 0; i < input.channel_size(); i++) + { + output.channel.push_back(input.channel(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::CommandModeInformation input, kortex_driver::CommandModeInformation &output) +{ + + output.command_mode = input.command_mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::Servoing input, kortex_driver::Servoing &output) +{ + + output.enabled = input.enabled(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::PositionCommand input, kortex_driver::PositionCommand &output) +{ + + output.position = input.position(); + output.velocity = input.velocity(); + output.acceleration = input.acceleration(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorConfig::CoggingFeedforwardModeInformation input, kortex_driver::CoggingFeedforwardModeInformation &output) +{ + + output.cogging_feedforward_mode = input.cogging_feedforward_mode(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_services.cpp new file mode 100644 index 0000000..e9a3971 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/actuatorconfig_services.cpp @@ -0,0 +1,741 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_services.h" + +ActuatorConfigRobotServices::ActuatorConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::ActuatorConfig::ActuatorConfigClient* actuatorconfig, uint32_t device_id, uint32_t timeout_ms): + IActuatorConfigServices(node_handle), + m_actuatorconfig(actuatorconfig), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + + m_serviceSetDeviceID = m_node_handle.advertiseService("actuator_config/set_device_id", &ActuatorConfigRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("actuator_config/set_api_options", &ActuatorConfigRobotServices::SetApiOptions, this); + + m_serviceGetAxisOffsets = m_node_handle.advertiseService("actuator_config/get_axis_offsets", &ActuatorConfigRobotServices::GetAxisOffsets, this); + m_serviceSetAxisOffsets = m_node_handle.advertiseService("actuator_config/set_axis_offsets", &ActuatorConfigRobotServices::SetAxisOffsets, this); + m_serviceSetTorqueOffset = m_node_handle.advertiseService("actuator_config/set_torque_offset", &ActuatorConfigRobotServices::SetTorqueOffset, this); + m_serviceActuatorConfig_GetControlMode = m_node_handle.advertiseService("actuator_config/get_control_mode", &ActuatorConfigRobotServices::ActuatorConfig_GetControlMode, this); + m_serviceSetControlMode = m_node_handle.advertiseService("actuator_config/set_control_mode", &ActuatorConfigRobotServices::SetControlMode, this); + m_serviceGetActivatedControlLoop = m_node_handle.advertiseService("actuator_config/get_activated_control_loop", &ActuatorConfigRobotServices::GetActivatedControlLoop, this); + m_serviceSetActivatedControlLoop = m_node_handle.advertiseService("actuator_config/set_activated_control_loop", &ActuatorConfigRobotServices::SetActivatedControlLoop, this); + m_serviceGetControlLoopParameters = m_node_handle.advertiseService("actuator_config/get_control_loop_parameters", &ActuatorConfigRobotServices::GetControlLoopParameters, this); + m_serviceSetControlLoopParameters = m_node_handle.advertiseService("actuator_config/set_control_loop_parameters", &ActuatorConfigRobotServices::SetControlLoopParameters, this); + m_serviceSelectCustomData = m_node_handle.advertiseService("actuator_config/select_custom_data", &ActuatorConfigRobotServices::SelectCustomData, this); + m_serviceGetSelectedCustomData = m_node_handle.advertiseService("actuator_config/get_selected_custom_data", &ActuatorConfigRobotServices::GetSelectedCustomData, this); + m_serviceSetCommandMode = m_node_handle.advertiseService("actuator_config/set_command_mode", &ActuatorConfigRobotServices::SetCommandMode, this); + m_serviceActuatorConfig_ClearFaults = m_node_handle.advertiseService("actuator_config/clear_faults", &ActuatorConfigRobotServices::ActuatorConfig_ClearFaults, this); + m_serviceSetServoing = m_node_handle.advertiseService("actuator_config/set_servoing", &ActuatorConfigRobotServices::SetServoing, this); + m_serviceMoveToPosition = m_node_handle.advertiseService("actuator_config/move_to_position", &ActuatorConfigRobotServices::MoveToPosition, this); + m_serviceGetCommandMode = m_node_handle.advertiseService("actuator_config/get_command_mode", &ActuatorConfigRobotServices::GetCommandMode, this); + m_serviceGetServoing = m_node_handle.advertiseService("actuator_config/get_servoing", &ActuatorConfigRobotServices::GetServoing, this); + m_serviceGetTorqueOffset = m_node_handle.advertiseService("actuator_config/get_torque_offset", &ActuatorConfigRobotServices::GetTorqueOffset, this); + m_serviceSetCoggingFeedforwardMode = m_node_handle.advertiseService("actuator_config/set_cogging_feedforward_mode", &ActuatorConfigRobotServices::SetCoggingFeedforwardMode, this); + m_serviceGetCoggingFeedforwardMode = m_node_handle.advertiseService("actuator_config/get_cogging_feedforward_mode", &ActuatorConfigRobotServices::GetCoggingFeedforwardMode, this); +} + +bool ActuatorConfigRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool ActuatorConfigRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool ActuatorConfigRobotServices::GetAxisOffsets(kortex_driver::GetAxisOffsets::Request &req, kortex_driver::GetAxisOffsets::Response &res) +{ + + Kinova::Api::ActuatorConfig::AxisOffsets output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetAxisOffsets(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::SetAxisOffsets(kortex_driver::SetAxisOffsets::Request &req, kortex_driver::SetAxisOffsets::Response &res) +{ + + Kinova::Api::ActuatorConfig::AxisPosition input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetAxisOffsets(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::SetTorqueOffset(kortex_driver::SetTorqueOffset::Request &req, kortex_driver::SetTorqueOffset::Response &res) +{ + + Kinova::Api::ActuatorConfig::TorqueOffset input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetTorqueOffset(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::ActuatorConfig_GetControlMode(kortex_driver::ActuatorConfig_GetControlMode::Request &req, kortex_driver::ActuatorConfig_GetControlMode::Response &res) +{ + + Kinova::Api::ActuatorConfig::ControlModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetControlMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::SetControlMode(kortex_driver::SetControlMode::Request &req, kortex_driver::SetControlMode::Response &res) +{ + + Kinova::Api::ActuatorConfig::ControlModeInformation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetControlMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::GetActivatedControlLoop(kortex_driver::GetActivatedControlLoop::Request &req, kortex_driver::GetActivatedControlLoop::Response &res) +{ + + Kinova::Api::ActuatorConfig::ControlLoop output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetActivatedControlLoop(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::SetActivatedControlLoop(kortex_driver::SetActivatedControlLoop::Request &req, kortex_driver::SetActivatedControlLoop::Response &res) +{ + + Kinova::Api::ActuatorConfig::ControlLoop input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetActivatedControlLoop(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::GetControlLoopParameters(kortex_driver::GetControlLoopParameters::Request &req, kortex_driver::GetControlLoopParameters::Response &res) +{ + + Kinova::Api::ActuatorConfig::LoopSelection input; + ToProtoData(req.input, &input); + Kinova::Api::ActuatorConfig::ControlLoopParameters output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetControlLoopParameters(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::SetControlLoopParameters(kortex_driver::SetControlLoopParameters::Request &req, kortex_driver::SetControlLoopParameters::Response &res) +{ + + Kinova::Api::ActuatorConfig::ControlLoopParameters input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetControlLoopParameters(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::SelectCustomData(kortex_driver::SelectCustomData::Request &req, kortex_driver::SelectCustomData::Response &res) +{ + + Kinova::Api::ActuatorConfig::CustomDataSelection input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SelectCustomData(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::GetSelectedCustomData(kortex_driver::GetSelectedCustomData::Request &req, kortex_driver::GetSelectedCustomData::Response &res) +{ + + Kinova::Api::ActuatorConfig::CustomDataSelection output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetSelectedCustomData(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::SetCommandMode(kortex_driver::SetCommandMode::Request &req, kortex_driver::SetCommandMode::Response &res) +{ + + Kinova::Api::ActuatorConfig::CommandModeInformation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetCommandMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::ActuatorConfig_ClearFaults(kortex_driver::ActuatorConfig_ClearFaults::Request &req, kortex_driver::ActuatorConfig_ClearFaults::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->ClearFaults(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::SetServoing(kortex_driver::SetServoing::Request &req, kortex_driver::SetServoing::Response &res) +{ + + Kinova::Api::ActuatorConfig::Servoing input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetServoing(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::MoveToPosition(kortex_driver::MoveToPosition::Request &req, kortex_driver::MoveToPosition::Response &res) +{ + + Kinova::Api::ActuatorConfig::PositionCommand input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->MoveToPosition(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::GetCommandMode(kortex_driver::GetCommandMode::Request &req, kortex_driver::GetCommandMode::Response &res) +{ + + Kinova::Api::ActuatorConfig::CommandModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetCommandMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::GetServoing(kortex_driver::GetServoing::Request &req, kortex_driver::GetServoing::Response &res) +{ + + Kinova::Api::ActuatorConfig::Servoing output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetServoing(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::GetTorqueOffset(kortex_driver::GetTorqueOffset::Request &req, kortex_driver::GetTorqueOffset::Response &res) +{ + + Kinova::Api::ActuatorConfig::TorqueOffset output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetTorqueOffset(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ActuatorConfigRobotServices::SetCoggingFeedforwardMode(kortex_driver::SetCoggingFeedforwardMode::Request &req, kortex_driver::SetCoggingFeedforwardMode::Response &res) +{ + + Kinova::Api::ActuatorConfig::CoggingFeedforwardModeInformation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_actuatorconfig->SetCoggingFeedforwardMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ActuatorConfigRobotServices::GetCoggingFeedforwardMode(kortex_driver::GetCoggingFeedforwardMode::Request &req, kortex_driver::GetCoggingFeedforwardMode::Response &res) +{ + + Kinova::Api::ActuatorConfig::CoggingFeedforwardModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_actuatorconfig->GetCoggingFeedforwardMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/actuatorcyclic_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/actuatorcyclic_proto_converter.cpp new file mode 100644 index 0000000..6d7744f --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/actuatorcyclic_proto_converter.cpp @@ -0,0 +1,80 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" + +int ToProtoData(kortex_driver::ActuatorCyclic_MessageId input, Kinova::Api::ActuatorCyclic::MessageId *output) +{ + + output->set_identifier(input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::ActuatorCyclic_Command input, Kinova::Api::ActuatorCyclic::Command *output) +{ + + ToProtoData(input.command_id, output->mutable_command_id()); + output->set_flags(input.flags); + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_torque_joint(input.torque_joint); + output->set_current_motor(input.current_motor); + + return 0; +} +int ToProtoData(kortex_driver::ActuatorCyclic_Feedback input, Kinova::Api::ActuatorCyclic::Feedback *output) +{ + + ToProtoData(input.feedback_id, output->mutable_feedback_id()); + output->set_status_flags(input.status_flags); + output->set_jitter_comm(input.jitter_comm); + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_torque(input.torque); + output->set_current_motor(input.current_motor); + output->set_voltage(input.voltage); + output->set_temperature_motor(input.temperature_motor); + output->set_temperature_core(input.temperature_core); + output->set_fault_bank_a(input.fault_bank_a); + output->set_fault_bank_b(input.fault_bank_b); + output->set_warning_bank_a(input.warning_bank_a); + output->set_warning_bank_b(input.warning_bank_b); + + return 0; +} +int ToProtoData(kortex_driver::ActuatorCyclic_CustomData input, Kinova::Api::ActuatorCyclic::CustomData *output) +{ + + ToProtoData(input.custom_data_id, output->mutable_custom_data_id()); + output->set_custom_data_0(input.custom_data_0); + output->set_custom_data_1(input.custom_data_1); + output->set_custom_data_2(input.custom_data_2); + output->set_custom_data_3(input.custom_data_3); + output->set_custom_data_4(input.custom_data_4); + output->set_custom_data_5(input.custom_data_5); + output->set_custom_data_6(input.custom_data_6); + output->set_custom_data_7(input.custom_data_7); + output->set_custom_data_8(input.custom_data_8); + output->set_custom_data_9(input.custom_data_9); + output->set_custom_data_10(input.custom_data_10); + output->set_custom_data_11(input.custom_data_11); + output->set_custom_data_12(input.custom_data_12); + output->set_custom_data_13(input.custom_data_13); + output->set_custom_data_14(input.custom_data_14); + output->set_custom_data_15(input.custom_data_15); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/actuatorcyclic_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/actuatorcyclic_ros_converter.cpp new file mode 100644 index 0000000..4e2e5ef --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/actuatorcyclic_ros_converter.cpp @@ -0,0 +1,88 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" + +int ToRosData(Kinova::Api::ActuatorCyclic::MessageId input, kortex_driver::ActuatorCyclic_MessageId &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorCyclic::Command input, kortex_driver::ActuatorCyclic_Command &output) +{ + + ToRosData(input.command_id(), output.command_id); + output.flags = input.flags(); + output.position = input.position(); + output.velocity = input.velocity(); + output.torque_joint = input.torque_joint(); + output.current_motor = input.current_motor(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorCyclic::Feedback input, kortex_driver::ActuatorCyclic_Feedback &output) +{ + + ToRosData(input.feedback_id(), output.feedback_id); + output.status_flags = input.status_flags(); + output.jitter_comm = input.jitter_comm(); + output.position = input.position(); + output.velocity = input.velocity(); + output.torque = input.torque(); + output.current_motor = input.current_motor(); + output.voltage = input.voltage(); + output.temperature_motor = input.temperature_motor(); + output.temperature_core = input.temperature_core(); + output.fault_bank_a = input.fault_bank_a(); + output.fault_bank_b = input.fault_bank_b(); + output.warning_bank_a = input.warning_bank_a(); + output.warning_bank_b = input.warning_bank_b(); + + + + return 0; +} +int ToRosData(Kinova::Api::ActuatorCyclic::CustomData input, kortex_driver::ActuatorCyclic_CustomData &output) +{ + + ToRosData(input.custom_data_id(), output.custom_data_id); + output.custom_data_0 = input.custom_data_0(); + output.custom_data_1 = input.custom_data_1(); + output.custom_data_2 = input.custom_data_2(); + output.custom_data_3 = input.custom_data_3(); + output.custom_data_4 = input.custom_data_4(); + output.custom_data_5 = input.custom_data_5(); + output.custom_data_6 = input.custom_data_6(); + output.custom_data_7 = input.custom_data_7(); + output.custom_data_8 = input.custom_data_8(); + output.custom_data_9 = input.custom_data_9(); + output.custom_data_10 = input.custom_data_10(); + output.custom_data_11 = input.custom_data_11(); + output.custom_data_12 = input.custom_data_12(); + output.custom_data_13 = input.custom_data_13(); + output.custom_data_14 = input.custom_data_14(); + output.custom_data_15 = input.custom_data_15(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/base_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/base_proto_converter.cpp new file mode 100644 index 0000000..1cefcb7 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/base_proto_converter.cpp @@ -0,0 +1,1684 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/base_proto_converter.h" + +int ToProtoData(kortex_driver::FullUserProfile input, Kinova::Api::Base::FullUserProfile *output) +{ + + ToProtoData(input.user_profile, output->mutable_user_profile()); + output->set_password(input.password); + + return 0; +} +int ToProtoData(kortex_driver::UserProfile input, Kinova::Api::Base::UserProfile *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_username(input.username); + output->set_firstname(input.firstname); + output->set_lastname(input.lastname); + output->set_application_data(input.application_data); + + return 0; +} +int ToProtoData(kortex_driver::UserProfileList input, Kinova::Api::Base::UserProfileList *output) +{ + + output->clear_user_profiles(); + for(int i = 0; i < input.user_profiles.size(); i++) + { + ToProtoData(input.user_profiles[i], output->add_user_profiles()); + } + + return 0; +} +int ToProtoData(kortex_driver::UserList input, Kinova::Api::Base::UserList *output) +{ + + output->clear_user_handles(); + for(int i = 0; i < input.user_handles.size(); i++) + { + ToProtoData(input.user_handles[i], output->add_user_handles()); + } + + return 0; +} +int ToProtoData(kortex_driver::PasswordChange input, Kinova::Api::Base::PasswordChange *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_old_password(input.old_password); + output->set_new_password(input.new_password); + + return 0; +} +int ToProtoData(kortex_driver::SequenceHandle input, Kinova::Api::Base::SequenceHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::AdvancedSequenceHandle input, Kinova::Api::Base::AdvancedSequenceHandle *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_in_loop(input.in_loop); + + return 0; +} +int ToProtoData(kortex_driver::SequenceTaskHandle input, Kinova::Api::Base::SequenceTaskHandle *output) +{ + + ToProtoData(input.sequence_handle, output->mutable_sequence_handle()); + output->set_task_index(input.task_index); + + return 0; +} +int ToProtoData(kortex_driver::SequenceTask input, Kinova::Api::Base::SequenceTask *output) +{ + + output->set_group_identifier(input.group_identifier); + ToProtoData(input.action, output->mutable_action()); + output->set_application_data(input.application_data); + + return 0; +} +int ToProtoData(kortex_driver::SequenceTasks input, Kinova::Api::Base::SequenceTasks *output) +{ + + output->clear_sequence_tasks(); + for(int i = 0; i < input.sequence_tasks.size(); i++) + { + ToProtoData(input.sequence_tasks[i], output->add_sequence_tasks()); + } + + return 0; +} +int ToProtoData(kortex_driver::SequenceTasksConfiguration input, Kinova::Api::Base::SequenceTasksConfiguration *output) +{ + + ToProtoData(input.sequence_task_handle, output->mutable_sequence_task_handle()); + output->clear_sequence_tasks(); + for(int i = 0; i < input.sequence_tasks.size(); i++) + { + ToProtoData(input.sequence_tasks[i], output->add_sequence_tasks()); + } + + return 0; +} +int ToProtoData(kortex_driver::SequenceTaskConfiguration input, Kinova::Api::Base::SequenceTaskConfiguration *output) +{ + + ToProtoData(input.sequence_task_handle, output->mutable_sequence_task_handle()); + ToProtoData(input.sequence_task, output->mutable_sequence_task()); + + return 0; +} +int ToProtoData(kortex_driver::SequenceTasksRange input, Kinova::Api::Base::SequenceTasksRange *output) +{ + + output->set_first_task_index(input.first_task_index); + output->set_second_task_index(input.second_task_index); + + return 0; +} +int ToProtoData(kortex_driver::SequenceTasksPair input, Kinova::Api::Base::SequenceTasksPair *output) +{ + + ToProtoData(input.sequence_handle, output->mutable_sequence_handle()); + output->set_first_task_index(input.first_task_index); + output->set_second_task_index(input.second_task_index); + + return 0; +} +int ToProtoData(kortex_driver::Sequence input, Kinova::Api::Base::Sequence *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_name(input.name); + output->set_application_data(input.application_data); + output->clear_tasks(); + for(int i = 0; i < input.tasks.size(); i++) + { + ToProtoData(input.tasks[i], output->add_tasks()); + } + + return 0; +} +int ToProtoData(kortex_driver::SequenceList input, Kinova::Api::Base::SequenceList *output) +{ + + output->clear_sequence_list(); + for(int i = 0; i < input.sequence_list.size(); i++) + { + ToProtoData(input.sequence_list[i], output->add_sequence_list()); + } + + return 0; +} +int ToProtoData(kortex_driver::AppendActionInformation input, Kinova::Api::Base::AppendActionInformation *output) +{ + + ToProtoData(input.sequence_handle, output->mutable_sequence_handle()); + ToProtoData(input.action, output->mutable_action()); + + return 0; +} +int ToProtoData(kortex_driver::ActionHandle input, Kinova::Api::Base::ActionHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_action_type((Kinova::Api::Base::ActionType)input.action_type); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::RequestedActionType input, Kinova::Api::Base::RequestedActionType *output) +{ + + output->set_action_type((Kinova::Api::Base::ActionType)input.action_type); + + return 0; +} +int ToProtoData(kortex_driver::Action input, Kinova::Api::Base::Action *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_name(input.name); + output->set_application_data(input.application_data); + if(input.oneof_action_parameters.send_twist_command.size() > 0) + { + ToProtoData(input.oneof_action_parameters.send_twist_command[0], output->mutable_send_twist_command()); + } + if(input.oneof_action_parameters.send_wrench_command.size() > 0) + { + ToProtoData(input.oneof_action_parameters.send_wrench_command[0], output->mutable_send_wrench_command()); + } + if(input.oneof_action_parameters.send_joint_speeds.size() > 0) + { + ToProtoData(input.oneof_action_parameters.send_joint_speeds[0], output->mutable_send_joint_speeds()); + } + if(input.oneof_action_parameters.reach_pose.size() > 0) + { + ToProtoData(input.oneof_action_parameters.reach_pose[0], output->mutable_reach_pose()); + } + if(input.oneof_action_parameters.reach_joint_angles.size() > 0) + { + ToProtoData(input.oneof_action_parameters.reach_joint_angles[0], output->mutable_reach_joint_angles()); + } + if(input.oneof_action_parameters.toggle_admittance_mode.size() > 0) + { + output->set_toggle_admittance_mode((Kinova::Api::Base::AdmittanceMode)input.oneof_action_parameters.toggle_admittance_mode[0]); + } + if(input.oneof_action_parameters.snapshot.size() > 0) + { + ToProtoData(input.oneof_action_parameters.snapshot[0], output->mutable_snapshot()); + } + if(input.oneof_action_parameters.switch_control_mapping.size() > 0) + { + ToProtoData(input.oneof_action_parameters.switch_control_mapping[0], output->mutable_switch_control_mapping()); + } + if(input.oneof_action_parameters.navigate_joints.size() > 0) + { + output->set_navigate_joints((Kinova::Api::Base::JointNavigationDirection)input.oneof_action_parameters.navigate_joints[0]); + } + if(input.oneof_action_parameters.navigate_mappings.size() > 0) + { + output->set_navigate_mappings((Kinova::Api::Base::NavigationDirection)input.oneof_action_parameters.navigate_mappings[0]); + } + if(input.oneof_action_parameters.change_twist.size() > 0) + { + ToProtoData(input.oneof_action_parameters.change_twist[0], output->mutable_change_twist()); + } + if(input.oneof_action_parameters.change_joint_speeds.size() > 0) + { + ToProtoData(input.oneof_action_parameters.change_joint_speeds[0], output->mutable_change_joint_speeds()); + } + if(input.oneof_action_parameters.change_wrench.size() > 0) + { + ToProtoData(input.oneof_action_parameters.change_wrench[0], output->mutable_change_wrench()); + } + if(input.oneof_action_parameters.apply_emergency_stop.size() > 0) + { + ToProtoData(input.oneof_action_parameters.apply_emergency_stop[0], output->mutable_apply_emergency_stop()); + } + if(input.oneof_action_parameters.clear_faults.size() > 0) + { + ToProtoData(input.oneof_action_parameters.clear_faults[0], output->mutable_clear_faults()); + } + if(input.oneof_action_parameters.delay.size() > 0) + { + ToProtoData(input.oneof_action_parameters.delay[0], output->mutable_delay()); + } + if(input.oneof_action_parameters.execute_action.size() > 0) + { + ToProtoData(input.oneof_action_parameters.execute_action[0], output->mutable_execute_action()); + } + if(input.oneof_action_parameters.send_gripper_command.size() > 0) + { + ToProtoData(input.oneof_action_parameters.send_gripper_command[0], output->mutable_send_gripper_command()); + } + if(input.oneof_action_parameters.stop_action.size() > 0) + { + ToProtoData(input.oneof_action_parameters.stop_action[0], output->mutable_stop_action()); + } + if(input.oneof_action_parameters.play_pre_computed_trajectory.size() > 0) + { + ToProtoData(input.oneof_action_parameters.play_pre_computed_trajectory[0], output->mutable_play_pre_computed_trajectory()); + } + + return 0; +} +int ToProtoData(kortex_driver::Snapshot input, Kinova::Api::Base::Snapshot *output) +{ + + output->set_snapshot_type((Kinova::Api::Base::SnapshotType)input.snapshot_type); + + return 0; +} +int ToProtoData(kortex_driver::SwitchControlMapping input, Kinova::Api::Base::SwitchControlMapping *output) +{ + + output->set_controller_identifier(input.controller_identifier); + ToProtoData(input.map_group_handle, output->mutable_map_group_handle()); + ToProtoData(input.map_handle, output->mutable_map_handle()); + + return 0; +} +int ToProtoData(kortex_driver::ChangeTwist input, Kinova::Api::Base::ChangeTwist *output) +{ + + output->set_linear(input.linear); + output->set_angular(input.angular); + + return 0; +} +int ToProtoData(kortex_driver::ChangeJointSpeeds input, Kinova::Api::Base::ChangeJointSpeeds *output) +{ + + ToProtoData(input.joint_speeds, output->mutable_joint_speeds()); + + return 0; +} +int ToProtoData(kortex_driver::ChangeWrench input, Kinova::Api::Base::ChangeWrench *output) +{ + + output->set_force(input.force); + output->set_torque(input.torque); + + return 0; +} +int ToProtoData(kortex_driver::EmergencyStop input, Kinova::Api::Base::EmergencyStop *output) +{ + + + return 0; +} +int ToProtoData(kortex_driver::Faults input, Kinova::Api::Base::Faults *output) +{ + + + return 0; +} +int ToProtoData(kortex_driver::Delay input, Kinova::Api::Base::Delay *output) +{ + + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::Base_Stop input, Kinova::Api::Base::Stop *output) +{ + + + return 0; +} +int ToProtoData(kortex_driver::ActionList input, Kinova::Api::Base::ActionList *output) +{ + + output->clear_action_list(); + for(int i = 0; i < input.action_list.size(); i++) + { + ToProtoData(input.action_list[i], output->add_action_list()); + } + + return 0; +} +int ToProtoData(kortex_driver::Timeout input, Kinova::Api::Base::Timeout *output) +{ + + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::Ssid input, Kinova::Api::Base::Ssid *output) +{ + + output->set_identifier(input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::CommunicationInterfaceConfiguration input, Kinova::Api::Base::CommunicationInterfaceConfiguration *output) +{ + + output->set_type((Kinova::Api::Base::NetworkType)input.type); + output->set_enable(input.enable); + + return 0; +} +int ToProtoData(kortex_driver::NetworkHandle input, Kinova::Api::Base::NetworkHandle *output) +{ + + output->set_type((Kinova::Api::Base::NetworkType)input.type); + + return 0; +} +int ToProtoData(kortex_driver::IPv4Configuration input, Kinova::Api::Base::IPv4Configuration *output) +{ + + output->set_ip_address(input.ip_address); + output->set_subnet_mask(input.subnet_mask); + output->set_default_gateway(input.default_gateway); + output->set_dhcp_enabled(input.dhcp_enabled); + + return 0; +} +int ToProtoData(kortex_driver::IPv4Information input, Kinova::Api::Base::IPv4Information *output) +{ + + output->set_ip_address(input.ip_address); + output->set_subnet_mask(input.subnet_mask); + output->set_default_gateway(input.default_gateway); + + return 0; +} +int ToProtoData(kortex_driver::FullIPv4Configuration input, Kinova::Api::Base::FullIPv4Configuration *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + ToProtoData(input.ipv4_configuration, output->mutable_ipv4_configuration()); + + return 0; +} +int ToProtoData(kortex_driver::WifiInformation input, Kinova::Api::Base::WifiInformation *output) +{ + + ToProtoData(input.ssid, output->mutable_ssid()); + output->set_security_type(input.security_type); + output->set_encryption_type(input.encryption_type); + output->set_signal_quality((Kinova::Api::Base::SignalQuality)input.signal_quality); + output->set_signal_strength(input.signal_strength); + output->set_frequency(input.frequency); + output->set_channel(input.channel); + + return 0; +} +int ToProtoData(kortex_driver::WifiInformationList input, Kinova::Api::Base::WifiInformationList *output) +{ + + output->clear_wifi_information_list(); + for(int i = 0; i < input.wifi_information_list.size(); i++) + { + ToProtoData(input.wifi_information_list[i], output->add_wifi_information_list()); + } + + return 0; +} +int ToProtoData(kortex_driver::WifiConfiguration input, Kinova::Api::Base::WifiConfiguration *output) +{ + + ToProtoData(input.ssid, output->mutable_ssid()); + output->set_security_key(input.security_key); + output->set_connect_automatically(input.connect_automatically); + + return 0; +} +int ToProtoData(kortex_driver::WifiConfigurationList input, Kinova::Api::Base::WifiConfigurationList *output) +{ + + output->clear_wifi_configuration_list(); + for(int i = 0; i < input.wifi_configuration_list.size(); i++) + { + ToProtoData(input.wifi_configuration_list[i], output->add_wifi_configuration_list()); + } + + return 0; +} +int ToProtoData(kortex_driver::ProtectionZoneHandle input, Kinova::Api::Base::ProtectionZoneHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::Base_RotationMatrixRow input, Kinova::Api::Base::RotationMatrixRow *output) +{ + + output->set_column1(input.column1); + output->set_column2(input.column2); + output->set_column3(input.column3); + + return 0; +} +int ToProtoData(kortex_driver::Base_RotationMatrix input, Kinova::Api::Base::RotationMatrix *output) +{ + + ToProtoData(input.row1, output->mutable_row1()); + ToProtoData(input.row2, output->mutable_row2()); + ToProtoData(input.row3, output->mutable_row3()); + + return 0; +} +int ToProtoData(kortex_driver::Point input, Kinova::Api::Base::Point *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + output->set_z(input.z); + + return 0; +} +int ToProtoData(kortex_driver::ZoneShape input, Kinova::Api::Base::ZoneShape *output) +{ + + output->set_shape_type((Kinova::Api::Base::ShapeType)input.shape_type); + ToProtoData(input.origin, output->mutable_origin()); + ToProtoData(input.orientation, output->mutable_orientation()); + output->clear_dimensions(); + for(int i = 0; i < input.dimensions.size(); i++) + { + output->add_dimensions(input.dimensions[i]); + } + output->set_envelope_thickness(input.envelope_thickness); + + return 0; +} +int ToProtoData(kortex_driver::ProtectionZone input, Kinova::Api::Base::ProtectionZone *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_name(input.name); + output->set_application_data(input.application_data); + output->set_is_enabled(input.is_enabled); + ToProtoData(input.shape, output->mutable_shape()); + output->clear_limitations(); + for(int i = 0; i < input.limitations.size(); i++) + { + ToProtoData(input.limitations[i], output->add_limitations()); + } + output->clear_envelope_limitations(); + for(int i = 0; i < input.envelope_limitations.size(); i++) + { + ToProtoData(input.envelope_limitations[i], output->add_envelope_limitations()); + } + + return 0; +} +int ToProtoData(kortex_driver::ProtectionZoneList input, Kinova::Api::Base::ProtectionZoneList *output) +{ + + output->clear_protection_zones(); + for(int i = 0; i < input.protection_zones.size(); i++) + { + ToProtoData(input.protection_zones[i], output->add_protection_zones()); + } + + return 0; +} +int ToProtoData(kortex_driver::CartesianLimitation input, Kinova::Api::Base::CartesianLimitation *output) +{ + + output->set_type((Kinova::Api::Base::LimitationType)input.type); + output->set_translation(input.translation); + output->set_orientation(input.orientation); + + return 0; +} +int ToProtoData(kortex_driver::TwistLimitation input, Kinova::Api::Base::TwistLimitation *output) +{ + + output->set_linear(input.linear); + output->set_angular(input.angular); + + return 0; +} +int ToProtoData(kortex_driver::WrenchLimitation input, Kinova::Api::Base::WrenchLimitation *output) +{ + + output->set_force(input.force); + output->set_torque(input.torque); + + return 0; +} +int ToProtoData(kortex_driver::CartesianLimitationList input, Kinova::Api::Base::CartesianLimitationList *output) +{ + + output->clear_limitations(); + for(int i = 0; i < input.limitations.size(); i++) + { + ToProtoData(input.limitations[i], output->add_limitations()); + } + + return 0; +} +int ToProtoData(kortex_driver::JointLimitation input, Kinova::Api::Base::JointLimitation *output) +{ + + output->set_joint_identifier(input.joint_identifier); + output->set_type((Kinova::Api::Base::LimitationType)input.type); + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::JointsLimitationsList input, Kinova::Api::Base::JointsLimitationsList *output) +{ + + output->clear_joints_limitations(); + for(int i = 0; i < input.joints_limitations.size(); i++) + { + ToProtoData(input.joints_limitations[i], output->add_joints_limitations()); + } + + return 0; +} +int ToProtoData(kortex_driver::Query input, Kinova::Api::Base::Query *output) +{ + + ToProtoData(input.start_timestamp, output->mutable_start_timestamp()); + ToProtoData(input.end_timestamp, output->mutable_end_timestamp()); + output->set_username(input.username); + + return 0; +} +int ToProtoData(kortex_driver::ConfigurationChangeNotification input, Kinova::Api::Base::ConfigurationChangeNotification *output) +{ + + output->set_event((Kinova::Api::Base::ConfigurationNotificationEvent)input.event); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + if(input.oneof_configuration_change.sequence_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.sequence_handle[0], output->mutable_sequence_handle()); + } + if(input.oneof_configuration_change.action_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.action_handle[0], output->mutable_action_handle()); + } + if(input.oneof_configuration_change.mapping_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.mapping_handle[0], output->mutable_mapping_handle()); + } + if(input.oneof_configuration_change.map_group_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.map_group_handle[0], output->mutable_map_group_handle()); + } + if(input.oneof_configuration_change.map_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.map_handle[0], output->mutable_map_handle()); + } + if(input.oneof_configuration_change.user_profile_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.user_profile_handle[0], output->mutable_user_profile_handle()); + } + if(input.oneof_configuration_change.protection_zone_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.protection_zone_handle[0], output->mutable_protection_zone_handle()); + } + if(input.oneof_configuration_change.safety_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.safety_handle[0], output->mutable_safety_handle()); + } + if(input.oneof_configuration_change.network_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.network_handle[0], output->mutable_network_handle()); + } + if(input.oneof_configuration_change.ssid.size() > 0) + { + ToProtoData(input.oneof_configuration_change.ssid[0], output->mutable_ssid()); + } + if(input.oneof_configuration_change.controller_handle.size() > 0) + { + ToProtoData(input.oneof_configuration_change.controller_handle[0], output->mutable_controller_handle()); + } + + return 0; +} +int ToProtoData(kortex_driver::MappingInfoNotification input, Kinova::Api::Base::MappingInfoNotification *output) +{ + + output->set_controller_identifier(input.controller_identifier); + ToProtoData(input.active_map_handle, output->mutable_active_map_handle()); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + ToProtoData(input.mapping_handle, output->mutable_mapping_handle()); + + return 0; +} +int ToProtoData(kortex_driver::Base_ControlModeInformation input, Kinova::Api::Base::ControlModeInformation *output) +{ + + output->set_mode((Kinova::Api::Base::ControlMode)input.mode); + + return 0; +} +int ToProtoData(kortex_driver::ControlModeNotification input, Kinova::Api::Base::ControlModeNotification *output) +{ + + output->set_control_mode((Kinova::Api::Base::ControlMode)input.control_mode); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::ServoingModeInformation input, Kinova::Api::Base::ServoingModeInformation *output) +{ + + output->set_servoing_mode((Kinova::Api::Base::ServoingMode)input.servoing_mode); + + return 0; +} +int ToProtoData(kortex_driver::OperatingModeInformation input, Kinova::Api::Base::OperatingModeInformation *output) +{ + + output->set_operating_mode((Kinova::Api::Base::OperatingMode)input.operating_mode); + ToProtoData(input.device_handle, output->mutable_device_handle()); + + return 0; +} +int ToProtoData(kortex_driver::OperatingModeNotification input, Kinova::Api::Base::OperatingModeNotification *output) +{ + + output->set_operating_mode((Kinova::Api::Base::OperatingMode)input.operating_mode); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + ToProtoData(input.device_handle, output->mutable_device_handle()); + + return 0; +} +int ToProtoData(kortex_driver::ServoingModeNotification input, Kinova::Api::Base::ServoingModeNotification *output) +{ + + output->set_servoing_mode((Kinova::Api::Base::ServoingMode)input.servoing_mode); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::SequenceInfoNotification input, Kinova::Api::Base::SequenceInfoNotification *output) +{ + + output->set_event_identifier((Kinova::Api::Base::EventIdSequenceInfoNotification)input.event_identifier); + ToProtoData(input.sequence_handle, output->mutable_sequence_handle()); + output->set_task_index(input.task_index); + output->set_group_identifier(input.group_identifier); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + output->set_abort_details((Kinova::Api::SubErrorCodes)input.abort_details); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::SequenceInformation input, Kinova::Api::Base::SequenceInformation *output) +{ + + output->set_event_identifier((Kinova::Api::Base::EventIdSequenceInfoNotification)input.event_identifier); + output->set_task_index(input.task_index); + output->set_task_identifier(input.task_identifier); + + return 0; +} +int ToProtoData(kortex_driver::ProtectionZoneNotification input, Kinova::Api::Base::ProtectionZoneNotification *output) +{ + + output->set_event((Kinova::Api::Base::ProtectionZoneEvent)input.event); + ToProtoData(input.handle, output->mutable_handle()); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::ProtectionZoneInformation input, Kinova::Api::Base::ProtectionZoneInformation *output) +{ + + output->set_event((Kinova::Api::Base::ProtectionZoneEvent)input.event); + + return 0; +} +int ToProtoData(kortex_driver::UserNotification input, Kinova::Api::Base::UserNotification *output) +{ + + output->set_user_event((Kinova::Api::Base::UserEvent)input.user_event); + ToProtoData(input.modified_user, output->mutable_modified_user()); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::ControllerHandle input, Kinova::Api::Base::ControllerHandle *output) +{ + + output->set_type((Kinova::Api::Base::ControllerType)input.type); + output->set_controller_identifier(input.controller_identifier); + + return 0; +} +int ToProtoData(kortex_driver::ControllerElementHandle input, Kinova::Api::Base::ControllerElementHandle *output) +{ + + ToProtoData(input.controller_handle, output->mutable_controller_handle()); + if(input.oneof_identifier.button.size() > 0) + { + output->set_button(input.oneof_identifier.button[0]); + } + if(input.oneof_identifier.axis.size() > 0) + { + output->set_axis(input.oneof_identifier.axis[0]); + } + + return 0; +} +int ToProtoData(kortex_driver::ControllerNotification input, Kinova::Api::Base::ControllerNotification *output) +{ + + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + if(input.oneof_state.controller_state.size() > 0) + { + ToProtoData(input.oneof_state.controller_state[0], output->mutable_controller_state()); + } + if(input.oneof_state.controller_element.size() > 0) + { + ToProtoData(input.oneof_state.controller_element[0], output->mutable_controller_element()); + } + + return 0; +} +int ToProtoData(kortex_driver::ControllerList input, Kinova::Api::Base::ControllerList *output) +{ + + output->clear_handles(); + for(int i = 0; i < input.handles.size(); i++) + { + ToProtoData(input.handles[i], output->add_handles()); + } + + return 0; +} +int ToProtoData(kortex_driver::ControllerState input, Kinova::Api::Base::ControllerState *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_event_type((Kinova::Api::Base::ControllerEventType)input.event_type); + + return 0; +} +int ToProtoData(kortex_driver::ControllerElementState input, Kinova::Api::Base::ControllerElementState *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_event_type((Kinova::Api::Base::ControllerElementEventType)input.event_type); + output->set_axis_value(input.axis_value); + + return 0; +} +int ToProtoData(kortex_driver::ActionNotification input, Kinova::Api::Base::ActionNotification *output) +{ + + output->set_action_event((Kinova::Api::Base::ActionEvent)input.action_event); + ToProtoData(input.handle, output->mutable_handle()); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + output->set_abort_details((Kinova::Api::SubErrorCodes)input.abort_details); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::ActionExecutionState input, Kinova::Api::Base::ActionExecutionState *output) +{ + + output->set_action_event((Kinova::Api::Base::ActionEvent)input.action_event); + ToProtoData(input.handle, output->mutable_handle()); + + return 0; +} +int ToProtoData(kortex_driver::RobotEventNotification input, Kinova::Api::Base::RobotEventNotification *output) +{ + + output->set_event((Kinova::Api::Base::RobotEvent)input.event); + ToProtoData(input.handle, output->mutable_handle()); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::FactoryNotification input, Kinova::Api::Base::FactoryNotification *output) +{ + + output->set_event((Kinova::Api::Base::FactoryEvent)input.event); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::NetworkNotification input, Kinova::Api::Base::NetworkNotification *output) +{ + + output->set_event((Kinova::Api::Base::NetworkEvent)input.event); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::ConfigurationChangeNotificationList input, Kinova::Api::Base::ConfigurationChangeNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::MappingInfoNotificationList input, Kinova::Api::Base::MappingInfoNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::ControlModeNotificationList input, Kinova::Api::Base::ControlModeNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::OperatingModeNotificationList input, Kinova::Api::Base::OperatingModeNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::ServoingModeNotificationList input, Kinova::Api::Base::ServoingModeNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::SequenceInfoNotificationList input, Kinova::Api::Base::SequenceInfoNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::ProtectionZoneNotificationList input, Kinova::Api::Base::ProtectionZoneNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::UserNotificationList input, Kinova::Api::Base::UserNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::SafetyNotificationList input, Kinova::Api::Base::SafetyNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::ControllerNotificationList input, Kinova::Api::Base::ControllerNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::ActionNotificationList input, Kinova::Api::Base::ActionNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::RobotEventNotificationList input, Kinova::Api::Base::RobotEventNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::NetworkNotificationList input, Kinova::Api::Base::NetworkNotificationList *output) +{ + + output->clear_notifications(); + for(int i = 0; i < input.notifications.size(); i++) + { + ToProtoData(input.notifications[i], output->add_notifications()); + } + + return 0; +} +int ToProtoData(kortex_driver::MappingHandle input, Kinova::Api::Base::MappingHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::SafetyEvent input, Kinova::Api::Base::SafetyEvent *output) +{ + + ToProtoData(input.safety_handle, output->mutable_safety_handle()); + + return 0; +} +int ToProtoData(kortex_driver::ControllerEvent input, Kinova::Api::Base::ControllerEvent *output) +{ + + output->set_input_type((Kinova::Api::Base::ControllerInputType)input.input_type); + output->set_behavior((Kinova::Api::Base::ControllerBehavior)input.behavior); + output->set_input_identifier(input.input_identifier); + + return 0; +} +int ToProtoData(kortex_driver::GpioEvent input, Kinova::Api::Base::GpioEvent *output) +{ + + output->set_input_type((Kinova::Api::Base::ControllerInputType)input.input_type); + output->set_behavior((Kinova::Api::Base::GpioBehavior)input.behavior); + output->set_input_identifier(input.input_identifier); + + return 0; +} +int ToProtoData(kortex_driver::MapEvent input, Kinova::Api::Base::MapEvent *output) +{ + + output->set_name(input.name); + if(input.oneof_events.safety_event.size() > 0) + { + ToProtoData(input.oneof_events.safety_event[0], output->mutable_safety_event()); + } + if(input.oneof_events.gpio_event.size() > 0) + { + ToProtoData(input.oneof_events.gpio_event[0], output->mutable_gpio_event()); + } + if(input.oneof_events.controller_event.size() > 0) + { + ToProtoData(input.oneof_events.controller_event[0], output->mutable_controller_event()); + } + + return 0; +} +int ToProtoData(kortex_driver::MapElement input, Kinova::Api::Base::MapElement *output) +{ + + ToProtoData(input.event, output->mutable_event()); + ToProtoData(input.action, output->mutable_action()); + output->set_name(input.name); + + return 0; +} +int ToProtoData(kortex_driver::ActivateMapHandle input, Kinova::Api::Base::ActivateMapHandle *output) +{ + + ToProtoData(input.mapping_handle, output->mutable_mapping_handle()); + ToProtoData(input.map_group_handle, output->mutable_map_group_handle()); + ToProtoData(input.map_handle, output->mutable_map_handle()); + + return 0; +} +int ToProtoData(kortex_driver::Map input, Kinova::Api::Base::Map *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_name(input.name); + output->clear_elements(); + for(int i = 0; i < input.elements.size(); i++) + { + ToProtoData(input.elements[i], output->add_elements()); + } + + return 0; +} +int ToProtoData(kortex_driver::MapHandle input, Kinova::Api::Base::MapHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::MapList input, Kinova::Api::Base::MapList *output) +{ + + output->clear_map_list(); + for(int i = 0; i < input.map_list.size(); i++) + { + ToProtoData(input.map_list[i], output->add_map_list()); + } + + return 0; +} +int ToProtoData(kortex_driver::MapGroupHandle input, Kinova::Api::Base::MapGroupHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::MapGroup input, Kinova::Api::Base::MapGroup *output) +{ + + ToProtoData(input.group_handle, output->mutable_group_handle()); + output->set_name(input.name); + ToProtoData(input.related_mapping_handle, output->mutable_related_mapping_handle()); + ToProtoData(input.parent_group_handle, output->mutable_parent_group_handle()); + output->clear_children_map_group_handles(); + for(int i = 0; i < input.children_map_group_handles.size(); i++) + { + ToProtoData(input.children_map_group_handles[i], output->add_children_map_group_handles()); + } + output->clear_map_handles(); + for(int i = 0; i < input.map_handles.size(); i++) + { + ToProtoData(input.map_handles[i], output->add_map_handles()); + } + output->set_application_data(input.application_data); + + return 0; +} +int ToProtoData(kortex_driver::MapGroupList input, Kinova::Api::Base::MapGroupList *output) +{ + + output->clear_map_groups(); + for(int i = 0; i < input.map_groups.size(); i++) + { + ToProtoData(input.map_groups[i], output->add_map_groups()); + } + + return 0; +} +int ToProtoData(kortex_driver::Mapping input, Kinova::Api::Base::Mapping *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_name(input.name); + output->set_controller_identifier(input.controller_identifier); + ToProtoData(input.active_map_group_handle, output->mutable_active_map_group_handle()); + output->clear_map_group_handles(); + for(int i = 0; i < input.map_group_handles.size(); i++) + { + ToProtoData(input.map_group_handles[i], output->add_map_group_handles()); + } + ToProtoData(input.active_map_handle, output->mutable_active_map_handle()); + output->clear_map_handles(); + for(int i = 0; i < input.map_handles.size(); i++) + { + ToProtoData(input.map_handles[i], output->add_map_handles()); + } + output->set_application_data(input.application_data); + + return 0; +} +int ToProtoData(kortex_driver::MappingList input, Kinova::Api::Base::MappingList *output) +{ + + output->clear_mappings(); + for(int i = 0; i < input.mappings.size(); i++) + { + ToProtoData(input.mappings[i], output->add_mappings()); + } + + return 0; +} +int ToProtoData(kortex_driver::TransformationMatrix input, Kinova::Api::Base::TransformationMatrix *output) +{ + + ToProtoData(input.r0, output->mutable_r0()); + ToProtoData(input.r1, output->mutable_r1()); + ToProtoData(input.r2, output->mutable_r2()); + ToProtoData(input.r3, output->mutable_r3()); + + return 0; +} +int ToProtoData(kortex_driver::TransformationRow input, Kinova::Api::Base::TransformationRow *output) +{ + + output->set_c0(input.c0); + output->set_c1(input.c1); + output->set_c2(input.c2); + output->set_c3(input.c3); + + return 0; +} +int ToProtoData(kortex_driver::Pose input, Kinova::Api::Base::Pose *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + output->set_z(input.z); + output->set_theta_x(input.theta_x); + output->set_theta_y(input.theta_y); + output->set_theta_z(input.theta_z); + + return 0; +} +int ToProtoData(kortex_driver::Base_Position input, Kinova::Api::Base::Position *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + output->set_z(input.z); + + return 0; +} +int ToProtoData(kortex_driver::Orientation input, Kinova::Api::Base::Orientation *output) +{ + + output->set_theta_x(input.theta_x); + output->set_theta_y(input.theta_y); + output->set_theta_z(input.theta_z); + + return 0; +} +int ToProtoData(kortex_driver::CartesianSpeed input, Kinova::Api::Base::CartesianSpeed *output) +{ + + output->set_translation(input.translation); + output->set_orientation(input.orientation); + + return 0; +} +int ToProtoData(kortex_driver::CartesianTrajectoryConstraint input, Kinova::Api::Base::CartesianTrajectoryConstraint *output) +{ + + if(input.oneof_type.speed.size() > 0) + { + ToProtoData(input.oneof_type.speed[0], output->mutable_speed()); + } + if(input.oneof_type.duration.size() > 0) + { + output->set_duration(input.oneof_type.duration[0]); + } + + return 0; +} +int ToProtoData(kortex_driver::JointTrajectoryConstraint input, Kinova::Api::Base::JointTrajectoryConstraint *output) +{ + + output->set_type((Kinova::Api::Base::JointTrajectoryConstraintType)input.type); + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::Wrench input, Kinova::Api::Base::Wrench *output) +{ + + output->set_force_x(input.force_x); + output->set_force_y(input.force_y); + output->set_force_z(input.force_z); + output->set_torque_x(input.torque_x); + output->set_torque_y(input.torque_y); + output->set_torque_z(input.torque_z); + + return 0; +} +int ToProtoData(kortex_driver::Twist input, Kinova::Api::Base::Twist *output) +{ + + output->set_linear_x(input.linear_x); + output->set_linear_y(input.linear_y); + output->set_linear_z(input.linear_z); + output->set_angular_x(input.angular_x); + output->set_angular_y(input.angular_y); + output->set_angular_z(input.angular_z); + + return 0; +} +int ToProtoData(kortex_driver::Admittance input, Kinova::Api::Base::Admittance *output) +{ + + output->set_admittance_mode((Kinova::Api::Base::AdmittanceMode)input.admittance_mode); + + return 0; +} +int ToProtoData(kortex_driver::ConstrainedPose input, Kinova::Api::Base::ConstrainedPose *output) +{ + + ToProtoData(input.target_pose, output->mutable_target_pose()); + ToProtoData(input.constraint, output->mutable_constraint()); + + return 0; +} +int ToProtoData(kortex_driver::ConstrainedPosition input, Kinova::Api::Base::ConstrainedPosition *output) +{ + + ToProtoData(input.target_position, output->mutable_target_position()); + ToProtoData(input.constraint, output->mutable_constraint()); + + return 0; +} +int ToProtoData(kortex_driver::ConstrainedOrientation input, Kinova::Api::Base::ConstrainedOrientation *output) +{ + + ToProtoData(input.target_orientation, output->mutable_target_orientation()); + ToProtoData(input.constraint, output->mutable_constraint()); + + return 0; +} +int ToProtoData(kortex_driver::WrenchCommand input, Kinova::Api::Base::WrenchCommand *output) +{ + + output->set_reference_frame((Kinova::Api::Common::CartesianReferenceFrame)input.reference_frame); + output->set_mode((Kinova::Api::Base::WrenchMode)input.mode); + ToProtoData(input.wrench, output->mutable_wrench()); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::TwistCommand input, Kinova::Api::Base::TwistCommand *output) +{ + + output->set_reference_frame((Kinova::Api::Common::CartesianReferenceFrame)input.reference_frame); + ToProtoData(input.twist, output->mutable_twist()); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::ConstrainedJointAngles input, Kinova::Api::Base::ConstrainedJointAngles *output) +{ + + ToProtoData(input.joint_angles, output->mutable_joint_angles()); + ToProtoData(input.constraint, output->mutable_constraint()); + + return 0; +} +int ToProtoData(kortex_driver::ConstrainedJointAngle input, Kinova::Api::Base::ConstrainedJointAngle *output) +{ + + output->set_joint_identifier(input.joint_identifier); + output->set_value(input.value); + ToProtoData(input.constraint, output->mutable_constraint()); + + return 0; +} +int ToProtoData(kortex_driver::JointAngles input, Kinova::Api::Base::JointAngles *output) +{ + + output->clear_joint_angles(); + for(int i = 0; i < input.joint_angles.size(); i++) + { + ToProtoData(input.joint_angles[i], output->add_joint_angles()); + } + + return 0; +} +int ToProtoData(kortex_driver::JointAngle input, Kinova::Api::Base::JointAngle *output) +{ + + output->set_joint_identifier(input.joint_identifier); + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::Base_JointSpeeds input, Kinova::Api::Base::JointSpeeds *output) +{ + + output->clear_joint_speeds(); + for(int i = 0; i < input.joint_speeds.size(); i++) + { + ToProtoData(input.joint_speeds[i], output->add_joint_speeds()); + } + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::JointSpeed input, Kinova::Api::Base::JointSpeed *output) +{ + + output->set_joint_identifier(input.joint_identifier); + output->set_value(input.value); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::JointTorques input, Kinova::Api::Base::JointTorques *output) +{ + + output->clear_joint_torques(); + for(int i = 0; i < input.joint_torques.size(); i++) + { + ToProtoData(input.joint_torques[i], output->add_joint_torques()); + } + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::JointTorque input, Kinova::Api::Base::JointTorque *output) +{ + + output->set_joint_identifier(input.joint_identifier); + output->set_value(input.value); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::GripperCommand input, Kinova::Api::Base::GripperCommand *output) +{ + + output->set_mode((Kinova::Api::Base::GripperMode)input.mode); + ToProtoData(input.gripper, output->mutable_gripper()); + output->set_duration(input.duration); + + return 0; +} +int ToProtoData(kortex_driver::GripperRequest input, Kinova::Api::Base::GripperRequest *output) +{ + + output->set_mode((Kinova::Api::Base::GripperMode)input.mode); + + return 0; +} +int ToProtoData(kortex_driver::Gripper input, Kinova::Api::Base::Gripper *output) +{ + + output->clear_finger(); + for(int i = 0; i < input.finger.size(); i++) + { + ToProtoData(input.finger[i], output->add_finger()); + } + + return 0; +} +int ToProtoData(kortex_driver::Finger input, Kinova::Api::Base::Finger *output) +{ + + output->set_finger_identifier(input.finger_identifier); + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::SystemTime input, Kinova::Api::Base::SystemTime *output) +{ + + output->set_sec(input.sec); + output->set_min(input.min); + output->set_hour(input.hour); + output->set_mday(input.mday); + output->set_mon(input.mon); + output->set_year(input.year); + + return 0; +} +int ToProtoData(kortex_driver::ControllerConfigurationMode input, Kinova::Api::Base::ControllerConfigurationMode *output) +{ + + output->set_enable(input.enable); + + return 0; +} +int ToProtoData(kortex_driver::ControllerConfiguration input, Kinova::Api::Base::ControllerConfiguration *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_name(input.name); + ToProtoData(input.active_mapping_handle, output->mutable_active_mapping_handle()); + output->set_analog_input_identifier_enum(input.analog_input_identifier_enum); + output->set_digital_input_identifier_enum(input.digital_input_identifier_enum); + + return 0; +} +int ToProtoData(kortex_driver::ControllerConfigurationList input, Kinova::Api::Base::ControllerConfigurationList *output) +{ + + output->clear_controller_configurations(); + for(int i = 0; i < input.controller_configurations.size(); i++) + { + ToProtoData(input.controller_configurations[i], output->add_controller_configurations()); + } + + return 0; +} +int ToProtoData(kortex_driver::ActuatorInformation input, Kinova::Api::Base::ActuatorInformation *output) +{ + + output->set_count(input.count); + + return 0; +} +int ToProtoData(kortex_driver::ArmStateInformation input, Kinova::Api::Base::ArmStateInformation *output) +{ + + output->set_active_state((Kinova::Api::Common::ArmState)input.active_state); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::ArmStateNotification input, Kinova::Api::Base::ArmStateNotification *output) +{ + + output->set_active_state((Kinova::Api::Common::ArmState)input.active_state); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::Base_CapSenseConfig input, Kinova::Api::Base::CapSenseConfig *output) +{ + + output->set_identifier(input.identifier); + output->set_mode((Kinova::Api::Base::CapSenseMode)input.mode); + output->set_threshold_a(input.threshold_a); + output->set_threshold_b(input.threshold_b); + output->set_sensitivity_a(input.sensitivity_a); + output->set_sensitivity_b(input.sensitivity_b); + + return 0; +} +int ToProtoData(kortex_driver::BridgeList input, Kinova::Api::Base::BridgeList *output) +{ + + output->clear_bridgeconfig(); + for(int i = 0; i < input.bridgeConfig.size(); i++) + { + ToProtoData(input.bridgeConfig[i], output->add_bridgeconfig()); + } + + return 0; +} +int ToProtoData(kortex_driver::BridgeResult input, Kinova::Api::Base::BridgeResult *output) +{ + + ToProtoData(input.bridge_id, output->mutable_bridge_id()); + output->set_status((Kinova::Api::Base::BridgeStatus)input.status); + + return 0; +} +int ToProtoData(kortex_driver::BridgeIdentifier input, Kinova::Api::Base::BridgeIdentifier *output) +{ + + output->set_bridge_id(input.bridge_id); + + return 0; +} +int ToProtoData(kortex_driver::BridgeConfig input, Kinova::Api::Base::BridgeConfig *output) +{ + + output->set_device_identifier(input.device_identifier); + output->set_bridgetype((Kinova::Api::Base::BridgeType)input.bridgetype); + ToProtoData(input.port_config, output->mutable_port_config()); + ToProtoData(input.bridge_id, output->mutable_bridge_id()); + + return 0; +} +int ToProtoData(kortex_driver::BridgePortConfig input, Kinova::Api::Base::BridgePortConfig *output) +{ + + output->set_target_port(input.target_port); + output->set_out_port(input.out_port); + + return 0; +} +int ToProtoData(kortex_driver::PreComputedJointTrajectory input, Kinova::Api::Base::PreComputedJointTrajectory *output) +{ + + output->set_mode((Kinova::Api::Base::TrajectoryContinuityMode)input.mode); + output->clear_trajectory_elements(); + for(int i = 0; i < input.trajectory_elements.size(); i++) + { + ToProtoData(input.trajectory_elements[i], output->add_trajectory_elements()); + } + + return 0; +} +int ToProtoData(kortex_driver::PreComputedJointTrajectoryElement input, Kinova::Api::Base::PreComputedJointTrajectoryElement *output) +{ + + output->clear_joint_angles(); + for(int i = 0; i < input.joint_angles.size(); i++) + { + output->add_joint_angles(input.joint_angles[i]); + } + output->clear_joint_speeds(); + for(int i = 0; i < input.joint_speeds.size(); i++) + { + output->add_joint_speeds(input.joint_speeds[i]); + } + output->clear_joint_accelerations(); + for(int i = 0; i < input.joint_accelerations.size(); i++) + { + output->add_joint_accelerations(input.joint_accelerations[i]); + } + output->set_time_from_start(input.time_from_start); + + return 0; +} +int ToProtoData(kortex_driver::TrajectoryErrorElement input, Kinova::Api::Base::TrajectoryErrorElement *output) +{ + + output->set_error_type((Kinova::Api::Base::TrajectoryErrorType)input.error_type); + output->set_error_identifier((Kinova::Api::Base::TrajectoryErrorIdentifier)input.error_identifier); + output->set_error_value(input.error_value); + output->set_min_value(input.min_value); + output->set_max_value(input.max_value); + output->set_index(input.index); + output->set_message(input.message); + + return 0; +} +int ToProtoData(kortex_driver::TrajectoryErrorReport input, Kinova::Api::Base::TrajectoryErrorReport *output) +{ + + output->clear_trajectory_error_elements(); + for(int i = 0; i < input.trajectory_error_elements.size(); i++) + { + ToProtoData(input.trajectory_error_elements[i], output->add_trajectory_error_elements()); + } + + return 0; +} +int ToProtoData(kortex_driver::FirmwareBundleVersions input, Kinova::Api::Base::FirmwareBundleVersions *output) +{ + + output->set_main_bundle_version(input.main_bundle_version); + output->clear_components_versions(); + for(int i = 0; i < input.components_versions.size(); i++) + { + ToProtoData(input.components_versions[i], output->add_components_versions()); + } + + return 0; +} +int ToProtoData(kortex_driver::FirmwareComponentVersion input, Kinova::Api::Base::FirmwareComponentVersion *output) +{ + + output->set_name(input.name); + output->set_version(input.version); + output->set_device_id(input.device_id); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/base_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/base_ros_converter.cpp new file mode 100644 index 0000000..6ac426c --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/base_ros_converter.cpp @@ -0,0 +1,2248 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/base_ros_converter.h" + +int ToRosData(Kinova::Api::Base::FullUserProfile input, kortex_driver::FullUserProfile &output) +{ + + ToRosData(input.user_profile(), output.user_profile); + output.password = input.password(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::UserProfile input, kortex_driver::UserProfile &output) +{ + + ToRosData(input.handle(), output.handle); + output.username = input.username(); + output.firstname = input.firstname(); + output.lastname = input.lastname(); + output.application_data = input.application_data(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::UserProfileList input, kortex_driver::UserProfileList &output) +{ + + output.user_profiles.clear(); + for(int i = 0; i < input.user_profiles_size(); i++) + { + kortex_driver::UserProfile temp; + ToRosData(input.user_profiles(i), temp); + output.user_profiles.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::UserList input, kortex_driver::UserList &output) +{ + + output.user_handles.clear(); + for(int i = 0; i < input.user_handles_size(); i++) + { + kortex_driver::UserProfileHandle temp; + ToRosData(input.user_handles(i), temp); + output.user_handles.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::PasswordChange input, kortex_driver::PasswordChange &output) +{ + + ToRosData(input.handle(), output.handle); + output.old_password = input.old_password(); + output.new_password = input.new_password(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceHandle input, kortex_driver::SequenceHandle &output) +{ + + output.identifier = input.identifier(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::AdvancedSequenceHandle input, kortex_driver::AdvancedSequenceHandle &output) +{ + + ToRosData(input.handle(), output.handle); + output.in_loop = input.in_loop(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTaskHandle input, kortex_driver::SequenceTaskHandle &output) +{ + + ToRosData(input.sequence_handle(), output.sequence_handle); + output.task_index = input.task_index(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTask input, kortex_driver::SequenceTask &output) +{ + + output.group_identifier = input.group_identifier(); + ToRosData(input.action(), output.action); + output.application_data = input.application_data(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTasks input, kortex_driver::SequenceTasks &output) +{ + + output.sequence_tasks.clear(); + for(int i = 0; i < input.sequence_tasks_size(); i++) + { + kortex_driver::SequenceTask temp; + ToRosData(input.sequence_tasks(i), temp); + output.sequence_tasks.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTasksConfiguration input, kortex_driver::SequenceTasksConfiguration &output) +{ + + ToRosData(input.sequence_task_handle(), output.sequence_task_handle); + output.sequence_tasks.clear(); + for(int i = 0; i < input.sequence_tasks_size(); i++) + { + kortex_driver::SequenceTask temp; + ToRosData(input.sequence_tasks(i), temp); + output.sequence_tasks.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTaskConfiguration input, kortex_driver::SequenceTaskConfiguration &output) +{ + + ToRosData(input.sequence_task_handle(), output.sequence_task_handle); + ToRosData(input.sequence_task(), output.sequence_task); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTasksRange input, kortex_driver::SequenceTasksRange &output) +{ + + output.first_task_index = input.first_task_index(); + output.second_task_index = input.second_task_index(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceTasksPair input, kortex_driver::SequenceTasksPair &output) +{ + + ToRosData(input.sequence_handle(), output.sequence_handle); + output.first_task_index = input.first_task_index(); + output.second_task_index = input.second_task_index(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Sequence input, kortex_driver::Sequence &output) +{ + + ToRosData(input.handle(), output.handle); + output.name = input.name(); + output.application_data = input.application_data(); + output.tasks.clear(); + for(int i = 0; i < input.tasks_size(); i++) + { + kortex_driver::SequenceTask temp; + ToRosData(input.tasks(i), temp); + output.tasks.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceList input, kortex_driver::SequenceList &output) +{ + + output.sequence_list.clear(); + for(int i = 0; i < input.sequence_list_size(); i++) + { + kortex_driver::Sequence temp; + ToRosData(input.sequence_list(i), temp); + output.sequence_list.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::AppendActionInformation input, kortex_driver::AppendActionInformation &output) +{ + + ToRosData(input.sequence_handle(), output.sequence_handle); + ToRosData(input.action(), output.action); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActionHandle input, kortex_driver::ActionHandle &output) +{ + + output.identifier = input.identifier(); + output.action_type = input.action_type(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::RequestedActionType input, kortex_driver::RequestedActionType &output) +{ + + output.action_type = input.action_type(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Action input, kortex_driver::Action &output) +{ + + ToRosData(input.handle(), output.handle); + output.name = input.name(); + output.application_data = input.application_data(); + + + auto oneof_type_action_parameters = input.action_parameters_case(); + switch(oneof_type_action_parameters) + { + + case Kinova::Api::Base::Action::kSendTwistCommand: + { + decltype(output.oneof_action_parameters.send_twist_command)::value_type temp; + ToRosData(input.send_twist_command(), temp); + output.oneof_action_parameters.send_twist_command.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kSendWrenchCommand: + { + decltype(output.oneof_action_parameters.send_wrench_command)::value_type temp; + ToRosData(input.send_wrench_command(), temp); + output.oneof_action_parameters.send_wrench_command.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kSendJointSpeeds: + { + decltype(output.oneof_action_parameters.send_joint_speeds)::value_type temp; + ToRosData(input.send_joint_speeds(), temp); + output.oneof_action_parameters.send_joint_speeds.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kReachPose: + { + decltype(output.oneof_action_parameters.reach_pose)::value_type temp; + ToRosData(input.reach_pose(), temp); + output.oneof_action_parameters.reach_pose.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kReachJointAngles: + { + decltype(output.oneof_action_parameters.reach_joint_angles)::value_type temp; + ToRosData(input.reach_joint_angles(), temp); + output.oneof_action_parameters.reach_joint_angles.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kToggleAdmittanceMode: + { + output.oneof_action_parameters.toggle_admittance_mode.push_back(input.toggle_admittance_mode()); + + break; + } + + case Kinova::Api::Base::Action::kSnapshot: + { + decltype(output.oneof_action_parameters.snapshot)::value_type temp; + ToRosData(input.snapshot(), temp); + output.oneof_action_parameters.snapshot.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kSwitchControlMapping: + { + decltype(output.oneof_action_parameters.switch_control_mapping)::value_type temp; + ToRosData(input.switch_control_mapping(), temp); + output.oneof_action_parameters.switch_control_mapping.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kNavigateJoints: + { + output.oneof_action_parameters.navigate_joints.push_back(input.navigate_joints()); + + break; + } + + case Kinova::Api::Base::Action::kNavigateMappings: + { + output.oneof_action_parameters.navigate_mappings.push_back(input.navigate_mappings()); + + break; + } + + case Kinova::Api::Base::Action::kChangeTwist: + { + decltype(output.oneof_action_parameters.change_twist)::value_type temp; + ToRosData(input.change_twist(), temp); + output.oneof_action_parameters.change_twist.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kChangeJointSpeeds: + { + decltype(output.oneof_action_parameters.change_joint_speeds)::value_type temp; + ToRosData(input.change_joint_speeds(), temp); + output.oneof_action_parameters.change_joint_speeds.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kChangeWrench: + { + decltype(output.oneof_action_parameters.change_wrench)::value_type temp; + ToRosData(input.change_wrench(), temp); + output.oneof_action_parameters.change_wrench.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kApplyEmergencyStop: + { + decltype(output.oneof_action_parameters.apply_emergency_stop)::value_type temp; + ToRosData(input.apply_emergency_stop(), temp); + output.oneof_action_parameters.apply_emergency_stop.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kClearFaults: + { + decltype(output.oneof_action_parameters.clear_faults)::value_type temp; + ToRosData(input.clear_faults(), temp); + output.oneof_action_parameters.clear_faults.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kDelay: + { + decltype(output.oneof_action_parameters.delay)::value_type temp; + ToRosData(input.delay(), temp); + output.oneof_action_parameters.delay.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kExecuteAction: + { + decltype(output.oneof_action_parameters.execute_action)::value_type temp; + ToRosData(input.execute_action(), temp); + output.oneof_action_parameters.execute_action.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kSendGripperCommand: + { + decltype(output.oneof_action_parameters.send_gripper_command)::value_type temp; + ToRosData(input.send_gripper_command(), temp); + output.oneof_action_parameters.send_gripper_command.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kStopAction: + { + decltype(output.oneof_action_parameters.stop_action)::value_type temp; + ToRosData(input.stop_action(), temp); + output.oneof_action_parameters.stop_action.push_back(temp); + break; + } + + case Kinova::Api::Base::Action::kPlayPreComputedTrajectory: + { + decltype(output.oneof_action_parameters.play_pre_computed_trajectory)::value_type temp; + ToRosData(input.play_pre_computed_trajectory(), temp); + output.oneof_action_parameters.play_pre_computed_trajectory.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::Base::Snapshot input, kortex_driver::Snapshot &output) +{ + + output.snapshot_type = input.snapshot_type(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SwitchControlMapping input, kortex_driver::SwitchControlMapping &output) +{ + + output.controller_identifier = input.controller_identifier(); + ToRosData(input.map_group_handle(), output.map_group_handle); + ToRosData(input.map_handle(), output.map_handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ChangeTwist input, kortex_driver::ChangeTwist &output) +{ + + output.linear = input.linear(); + output.angular = input.angular(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ChangeJointSpeeds input, kortex_driver::ChangeJointSpeeds &output) +{ + + ToRosData(input.joint_speeds(), output.joint_speeds); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ChangeWrench input, kortex_driver::ChangeWrench &output) +{ + + output.force = input.force(); + output.torque = input.torque(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::EmergencyStop input, kortex_driver::EmergencyStop &output) +{ + + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Faults input, kortex_driver::Faults &output) +{ + + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Delay input, kortex_driver::Delay &output) +{ + + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Stop input, kortex_driver::Base_Stop &output) +{ + + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActionList input, kortex_driver::ActionList &output) +{ + + output.action_list.clear(); + for(int i = 0; i < input.action_list_size(); i++) + { + kortex_driver::Action temp; + ToRosData(input.action_list(i), temp); + output.action_list.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Timeout input, kortex_driver::Timeout &output) +{ + + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Ssid input, kortex_driver::Ssid &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::CommunicationInterfaceConfiguration input, kortex_driver::CommunicationInterfaceConfiguration &output) +{ + + output.type = input.type(); + output.enable = input.enable(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::NetworkHandle input, kortex_driver::NetworkHandle &output) +{ + + output.type = input.type(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::IPv4Configuration input, kortex_driver::IPv4Configuration &output) +{ + + output.ip_address = input.ip_address(); + output.subnet_mask = input.subnet_mask(); + output.default_gateway = input.default_gateway(); + output.dhcp_enabled = input.dhcp_enabled(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::IPv4Information input, kortex_driver::IPv4Information &output) +{ + + output.ip_address = input.ip_address(); + output.subnet_mask = input.subnet_mask(); + output.default_gateway = input.default_gateway(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::FullIPv4Configuration input, kortex_driver::FullIPv4Configuration &output) +{ + + ToRosData(input.handle(), output.handle); + ToRosData(input.ipv4_configuration(), output.ipv4_configuration); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::WifiInformation input, kortex_driver::WifiInformation &output) +{ + + ToRosData(input.ssid(), output.ssid); + output.security_type = input.security_type(); + output.encryption_type = input.encryption_type(); + output.signal_quality = input.signal_quality(); + output.signal_strength = input.signal_strength(); + output.frequency = input.frequency(); + output.channel = input.channel(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::WifiInformationList input, kortex_driver::WifiInformationList &output) +{ + + output.wifi_information_list.clear(); + for(int i = 0; i < input.wifi_information_list_size(); i++) + { + kortex_driver::WifiInformation temp; + ToRosData(input.wifi_information_list(i), temp); + output.wifi_information_list.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::WifiConfiguration input, kortex_driver::WifiConfiguration &output) +{ + + ToRosData(input.ssid(), output.ssid); + output.security_key = input.security_key(); + output.connect_automatically = input.connect_automatically(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::WifiConfigurationList input, kortex_driver::WifiConfigurationList &output) +{ + + output.wifi_configuration_list.clear(); + for(int i = 0; i < input.wifi_configuration_list_size(); i++) + { + kortex_driver::WifiConfiguration temp; + ToRosData(input.wifi_configuration_list(i), temp); + output.wifi_configuration_list.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ProtectionZoneHandle input, kortex_driver::ProtectionZoneHandle &output) +{ + + output.identifier = input.identifier(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::RotationMatrixRow input, kortex_driver::Base_RotationMatrixRow &output) +{ + + output.column1 = input.column1(); + output.column2 = input.column2(); + output.column3 = input.column3(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::RotationMatrix input, kortex_driver::Base_RotationMatrix &output) +{ + + ToRosData(input.row1(), output.row1); + ToRosData(input.row2(), output.row2); + ToRosData(input.row3(), output.row3); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Point input, kortex_driver::Point &output) +{ + + output.x = input.x(); + output.y = input.y(); + output.z = input.z(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ZoneShape input, kortex_driver::ZoneShape &output) +{ + + output.shape_type = input.shape_type(); + ToRosData(input.origin(), output.origin); + ToRosData(input.orientation(), output.orientation); + output.dimensions.clear(); + for(int i = 0; i < input.dimensions_size(); i++) + { + output.dimensions.push_back(input.dimensions(i)); + } + output.envelope_thickness = input.envelope_thickness(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ProtectionZone input, kortex_driver::ProtectionZone &output) +{ + + ToRosData(input.handle(), output.handle); + output.name = input.name(); + output.application_data = input.application_data(); + output.is_enabled = input.is_enabled(); + ToRosData(input.shape(), output.shape); + output.limitations.clear(); + for(int i = 0; i < input.limitations_size(); i++) + { + kortex_driver::CartesianLimitation temp; + ToRosData(input.limitations(i), temp); + output.limitations.push_back(temp); + } + output.envelope_limitations.clear(); + for(int i = 0; i < input.envelope_limitations_size(); i++) + { + kortex_driver::CartesianLimitation temp; + ToRosData(input.envelope_limitations(i), temp); + output.envelope_limitations.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ProtectionZoneList input, kortex_driver::ProtectionZoneList &output) +{ + + output.protection_zones.clear(); + for(int i = 0; i < input.protection_zones_size(); i++) + { + kortex_driver::ProtectionZone temp; + ToRosData(input.protection_zones(i), temp); + output.protection_zones.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::CartesianLimitation input, kortex_driver::CartesianLimitation &output) +{ + + output.type = input.type(); + output.translation = input.translation(); + output.orientation = input.orientation(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::TwistLimitation input, kortex_driver::TwistLimitation &output) +{ + + output.linear = input.linear(); + output.angular = input.angular(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::WrenchLimitation input, kortex_driver::WrenchLimitation &output) +{ + + output.force = input.force(); + output.torque = input.torque(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::CartesianLimitationList input, kortex_driver::CartesianLimitationList &output) +{ + + output.limitations.clear(); + for(int i = 0; i < input.limitations_size(); i++) + { + kortex_driver::CartesianLimitation temp; + ToRosData(input.limitations(i), temp); + output.limitations.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointLimitation input, kortex_driver::JointLimitation &output) +{ + + output.joint_identifier = input.joint_identifier(); + output.type = input.type(); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointsLimitationsList input, kortex_driver::JointsLimitationsList &output) +{ + + output.joints_limitations.clear(); + for(int i = 0; i < input.joints_limitations_size(); i++) + { + kortex_driver::JointLimitation temp; + ToRosData(input.joints_limitations(i), temp); + output.joints_limitations.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Query input, kortex_driver::Query &output) +{ + + ToRosData(input.start_timestamp(), output.start_timestamp); + ToRosData(input.end_timestamp(), output.end_timestamp); + output.username = input.username(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConfigurationChangeNotification input, kortex_driver::ConfigurationChangeNotification &output) +{ + + output.event = input.event(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + auto oneof_type_configuration_change = input.configuration_change_case(); + switch(oneof_type_configuration_change) + { + + case Kinova::Api::Base::ConfigurationChangeNotification::kSequenceHandle: + { + decltype(output.oneof_configuration_change.sequence_handle)::value_type temp; + ToRosData(input.sequence_handle(), temp); + output.oneof_configuration_change.sequence_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kActionHandle: + { + decltype(output.oneof_configuration_change.action_handle)::value_type temp; + ToRosData(input.action_handle(), temp); + output.oneof_configuration_change.action_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kMappingHandle: + { + decltype(output.oneof_configuration_change.mapping_handle)::value_type temp; + ToRosData(input.mapping_handle(), temp); + output.oneof_configuration_change.mapping_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kMapGroupHandle: + { + decltype(output.oneof_configuration_change.map_group_handle)::value_type temp; + ToRosData(input.map_group_handle(), temp); + output.oneof_configuration_change.map_group_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kMapHandle: + { + decltype(output.oneof_configuration_change.map_handle)::value_type temp; + ToRosData(input.map_handle(), temp); + output.oneof_configuration_change.map_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kUserProfileHandle: + { + decltype(output.oneof_configuration_change.user_profile_handle)::value_type temp; + ToRosData(input.user_profile_handle(), temp); + output.oneof_configuration_change.user_profile_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kProtectionZoneHandle: + { + decltype(output.oneof_configuration_change.protection_zone_handle)::value_type temp; + ToRosData(input.protection_zone_handle(), temp); + output.oneof_configuration_change.protection_zone_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kSafetyHandle: + { + decltype(output.oneof_configuration_change.safety_handle)::value_type temp; + ToRosData(input.safety_handle(), temp); + output.oneof_configuration_change.safety_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kNetworkHandle: + { + decltype(output.oneof_configuration_change.network_handle)::value_type temp; + ToRosData(input.network_handle(), temp); + output.oneof_configuration_change.network_handle.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kSsid: + { + decltype(output.oneof_configuration_change.ssid)::value_type temp; + ToRosData(input.ssid(), temp); + output.oneof_configuration_change.ssid.push_back(temp); + break; + } + + case Kinova::Api::Base::ConfigurationChangeNotification::kControllerHandle: + { + decltype(output.oneof_configuration_change.controller_handle)::value_type temp; + ToRosData(input.controller_handle(), temp); + output.oneof_configuration_change.controller_handle.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::Base::MappingInfoNotification input, kortex_driver::MappingInfoNotification &output) +{ + + output.controller_identifier = input.controller_identifier(); + ToRosData(input.active_map_handle(), output.active_map_handle); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + ToRosData(input.mapping_handle(), output.mapping_handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControlModeInformation input, kortex_driver::Base_ControlModeInformation &output) +{ + + output.mode = input.mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControlModeNotification input, kortex_driver::ControlModeNotification &output) +{ + + output.control_mode = input.control_mode(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ServoingModeInformation input, kortex_driver::ServoingModeInformation &output) +{ + + output.servoing_mode = input.servoing_mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::OperatingModeInformation input, kortex_driver::OperatingModeInformation &output) +{ + + output.operating_mode = input.operating_mode(); + ToRosData(input.device_handle(), output.device_handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::OperatingModeNotification input, kortex_driver::OperatingModeNotification &output) +{ + + output.operating_mode = input.operating_mode(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + ToRosData(input.device_handle(), output.device_handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ServoingModeNotification input, kortex_driver::ServoingModeNotification &output) +{ + + output.servoing_mode = input.servoing_mode(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceInfoNotification input, kortex_driver::SequenceInfoNotification &output) +{ + + output.event_identifier = input.event_identifier(); + ToRosData(input.sequence_handle(), output.sequence_handle); + output.task_index = input.task_index(); + output.group_identifier = input.group_identifier(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + output.abort_details = input.abort_details(); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceInformation input, kortex_driver::SequenceInformation &output) +{ + + output.event_identifier = input.event_identifier(); + output.task_index = input.task_index(); + output.task_identifier = input.task_identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ProtectionZoneNotification input, kortex_driver::ProtectionZoneNotification &output) +{ + + output.event = input.event(); + ToRosData(input.handle(), output.handle); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ProtectionZoneInformation input, kortex_driver::ProtectionZoneInformation &output) +{ + + output.event = input.event(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::UserNotification input, kortex_driver::UserNotification &output) +{ + + output.user_event = input.user_event(); + ToRosData(input.modified_user(), output.modified_user); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerHandle input, kortex_driver::ControllerHandle &output) +{ + + output.type = input.type(); + output.controller_identifier = input.controller_identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerElementHandle input, kortex_driver::ControllerElementHandle &output) +{ + + ToRosData(input.controller_handle(), output.controller_handle); + + + auto oneof_type_identifier = input.identifier_case(); + switch(oneof_type_identifier) + { + + case Kinova::Api::Base::ControllerElementHandle::kButton: + { + break; + } + + case Kinova::Api::Base::ControllerElementHandle::kAxis: + { + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerNotification input, kortex_driver::ControllerNotification &output) +{ + + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + auto oneof_type_state = input.state_case(); + switch(oneof_type_state) + { + + case Kinova::Api::Base::ControllerNotification::kControllerState: + { + decltype(output.oneof_state.controller_state)::value_type temp; + ToRosData(input.controller_state(), temp); + output.oneof_state.controller_state.push_back(temp); + break; + } + + case Kinova::Api::Base::ControllerNotification::kControllerElement: + { + decltype(output.oneof_state.controller_element)::value_type temp; + ToRosData(input.controller_element(), temp); + output.oneof_state.controller_element.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerList input, kortex_driver::ControllerList &output) +{ + + output.handles.clear(); + for(int i = 0; i < input.handles_size(); i++) + { + kortex_driver::ControllerHandle temp; + ToRosData(input.handles(i), temp); + output.handles.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerState input, kortex_driver::ControllerState &output) +{ + + ToRosData(input.handle(), output.handle); + output.event_type = input.event_type(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerElementState input, kortex_driver::ControllerElementState &output) +{ + + ToRosData(input.handle(), output.handle); + output.event_type = input.event_type(); + output.axis_value = input.axis_value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActionNotification input, kortex_driver::ActionNotification &output) +{ + + output.action_event = input.action_event(); + ToRosData(input.handle(), output.handle); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + output.abort_details = input.abort_details(); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActionExecutionState input, kortex_driver::ActionExecutionState &output) +{ + + output.action_event = input.action_event(); + ToRosData(input.handle(), output.handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::RobotEventNotification input, kortex_driver::RobotEventNotification &output) +{ + + output.event = input.event(); + ToRosData(input.handle(), output.handle); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::FactoryNotification input, kortex_driver::FactoryNotification &output) +{ + + output.event = input.event(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::NetworkNotification input, kortex_driver::NetworkNotification &output) +{ + + output.event = input.event(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConfigurationChangeNotificationList input, kortex_driver::ConfigurationChangeNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::ConfigurationChangeNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MappingInfoNotificationList input, kortex_driver::MappingInfoNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::MappingInfoNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControlModeNotificationList input, kortex_driver::ControlModeNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::ControlModeNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::OperatingModeNotificationList input, kortex_driver::OperatingModeNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::OperatingModeNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ServoingModeNotificationList input, kortex_driver::ServoingModeNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::ServoingModeNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SequenceInfoNotificationList input, kortex_driver::SequenceInfoNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::SequenceInfoNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ProtectionZoneNotificationList input, kortex_driver::ProtectionZoneNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::ProtectionZoneNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::UserNotificationList input, kortex_driver::UserNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::UserNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SafetyNotificationList input, kortex_driver::SafetyNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::SafetyNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerNotificationList input, kortex_driver::ControllerNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::ControllerNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActionNotificationList input, kortex_driver::ActionNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::ActionNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::RobotEventNotificationList input, kortex_driver::RobotEventNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::RobotEventNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::NetworkNotificationList input, kortex_driver::NetworkNotificationList &output) +{ + + output.notifications.clear(); + for(int i = 0; i < input.notifications_size(); i++) + { + kortex_driver::NetworkNotification temp; + ToRosData(input.notifications(i), temp); + output.notifications.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MappingHandle input, kortex_driver::MappingHandle &output) +{ + + output.identifier = input.identifier(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SafetyEvent input, kortex_driver::SafetyEvent &output) +{ + + ToRosData(input.safety_handle(), output.safety_handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerEvent input, kortex_driver::ControllerEvent &output) +{ + + output.input_type = input.input_type(); + output.behavior = input.behavior(); + output.input_identifier = input.input_identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::GpioEvent input, kortex_driver::GpioEvent &output) +{ + + output.input_type = input.input_type(); + output.behavior = input.behavior(); + output.input_identifier = input.input_identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MapEvent input, kortex_driver::MapEvent &output) +{ + + output.name = input.name(); + + + auto oneof_type_events = input.events_case(); + switch(oneof_type_events) + { + + case Kinova::Api::Base::MapEvent::kSafetyEvent: + { + decltype(output.oneof_events.safety_event)::value_type temp; + ToRosData(input.safety_event(), temp); + output.oneof_events.safety_event.push_back(temp); + break; + } + + case Kinova::Api::Base::MapEvent::kGpioEvent: + { + decltype(output.oneof_events.gpio_event)::value_type temp; + ToRosData(input.gpio_event(), temp); + output.oneof_events.gpio_event.push_back(temp); + break; + } + + case Kinova::Api::Base::MapEvent::kControllerEvent: + { + decltype(output.oneof_events.controller_event)::value_type temp; + ToRosData(input.controller_event(), temp); + output.oneof_events.controller_event.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::Base::MapElement input, kortex_driver::MapElement &output) +{ + + ToRosData(input.event(), output.event); + ToRosData(input.action(), output.action); + output.name = input.name(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActivateMapHandle input, kortex_driver::ActivateMapHandle &output) +{ + + ToRosData(input.mapping_handle(), output.mapping_handle); + ToRosData(input.map_group_handle(), output.map_group_handle); + ToRosData(input.map_handle(), output.map_handle); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Map input, kortex_driver::Map &output) +{ + + ToRosData(input.handle(), output.handle); + output.name = input.name(); + output.elements.clear(); + for(int i = 0; i < input.elements_size(); i++) + { + kortex_driver::MapElement temp; + ToRosData(input.elements(i), temp); + output.elements.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MapHandle input, kortex_driver::MapHandle &output) +{ + + output.identifier = input.identifier(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MapList input, kortex_driver::MapList &output) +{ + + output.map_list.clear(); + for(int i = 0; i < input.map_list_size(); i++) + { + kortex_driver::Map temp; + ToRosData(input.map_list(i), temp); + output.map_list.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MapGroupHandle input, kortex_driver::MapGroupHandle &output) +{ + + output.identifier = input.identifier(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MapGroup input, kortex_driver::MapGroup &output) +{ + + ToRosData(input.group_handle(), output.group_handle); + output.name = input.name(); + ToRosData(input.related_mapping_handle(), output.related_mapping_handle); + ToRosData(input.parent_group_handle(), output.parent_group_handle); + output.children_map_group_handles.clear(); + for(int i = 0; i < input.children_map_group_handles_size(); i++) + { + kortex_driver::MapGroupHandle temp; + ToRosData(input.children_map_group_handles(i), temp); + output.children_map_group_handles.push_back(temp); + } + output.map_handles.clear(); + for(int i = 0; i < input.map_handles_size(); i++) + { + kortex_driver::MapHandle temp; + ToRosData(input.map_handles(i), temp); + output.map_handles.push_back(temp); + } + output.application_data = input.application_data(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MapGroupList input, kortex_driver::MapGroupList &output) +{ + + output.map_groups.clear(); + for(int i = 0; i < input.map_groups_size(); i++) + { + kortex_driver::MapGroup temp; + ToRosData(input.map_groups(i), temp); + output.map_groups.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Mapping input, kortex_driver::Mapping &output) +{ + + ToRosData(input.handle(), output.handle); + output.name = input.name(); + output.controller_identifier = input.controller_identifier(); + ToRosData(input.active_map_group_handle(), output.active_map_group_handle); + output.map_group_handles.clear(); + for(int i = 0; i < input.map_group_handles_size(); i++) + { + kortex_driver::MapGroupHandle temp; + ToRosData(input.map_group_handles(i), temp); + output.map_group_handles.push_back(temp); + } + ToRosData(input.active_map_handle(), output.active_map_handle); + output.map_handles.clear(); + for(int i = 0; i < input.map_handles_size(); i++) + { + kortex_driver::MapHandle temp; + ToRosData(input.map_handles(i), temp); + output.map_handles.push_back(temp); + } + output.application_data = input.application_data(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::MappingList input, kortex_driver::MappingList &output) +{ + + output.mappings.clear(); + for(int i = 0; i < input.mappings_size(); i++) + { + kortex_driver::Mapping temp; + ToRosData(input.mappings(i), temp); + output.mappings.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::TransformationMatrix input, kortex_driver::TransformationMatrix &output) +{ + + ToRosData(input.r0(), output.r0); + ToRosData(input.r1(), output.r1); + ToRosData(input.r2(), output.r2); + ToRosData(input.r3(), output.r3); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::TransformationRow input, kortex_driver::TransformationRow &output) +{ + + output.c0 = input.c0(); + output.c1 = input.c1(); + output.c2 = input.c2(); + output.c3 = input.c3(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Pose input, kortex_driver::Pose &output) +{ + + output.x = input.x(); + output.y = input.y(); + output.z = input.z(); + output.theta_x = input.theta_x(); + output.theta_y = input.theta_y(); + output.theta_z = input.theta_z(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Position input, kortex_driver::Base_Position &output) +{ + + output.x = input.x(); + output.y = input.y(); + output.z = input.z(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Orientation input, kortex_driver::Orientation &output) +{ + + output.theta_x = input.theta_x(); + output.theta_y = input.theta_y(); + output.theta_z = input.theta_z(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::CartesianSpeed input, kortex_driver::CartesianSpeed &output) +{ + + output.translation = input.translation(); + output.orientation = input.orientation(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::CartesianTrajectoryConstraint input, kortex_driver::CartesianTrajectoryConstraint &output) +{ + + + + auto oneof_type_type = input.type_case(); + switch(oneof_type_type) + { + + case Kinova::Api::Base::CartesianTrajectoryConstraint::kSpeed: + { + decltype(output.oneof_type.speed)::value_type temp; + ToRosData(input.speed(), temp); + output.oneof_type.speed.push_back(temp); + break; + } + + case Kinova::Api::Base::CartesianTrajectoryConstraint::kDuration: + { + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::Base::JointTrajectoryConstraint input, kortex_driver::JointTrajectoryConstraint &output) +{ + + output.type = input.type(); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Wrench input, kortex_driver::Wrench &output) +{ + + output.force_x = input.force_x(); + output.force_y = input.force_y(); + output.force_z = input.force_z(); + output.torque_x = input.torque_x(); + output.torque_y = input.torque_y(); + output.torque_z = input.torque_z(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Twist input, kortex_driver::Twist &output) +{ + + output.linear_x = input.linear_x(); + output.linear_y = input.linear_y(); + output.linear_z = input.linear_z(); + output.angular_x = input.angular_x(); + output.angular_y = input.angular_y(); + output.angular_z = input.angular_z(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Admittance input, kortex_driver::Admittance &output) +{ + + output.admittance_mode = input.admittance_mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConstrainedPose input, kortex_driver::ConstrainedPose &output) +{ + + ToRosData(input.target_pose(), output.target_pose); + ToRosData(input.constraint(), output.constraint); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConstrainedPosition input, kortex_driver::ConstrainedPosition &output) +{ + + ToRosData(input.target_position(), output.target_position); + ToRosData(input.constraint(), output.constraint); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConstrainedOrientation input, kortex_driver::ConstrainedOrientation &output) +{ + + ToRosData(input.target_orientation(), output.target_orientation); + ToRosData(input.constraint(), output.constraint); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::WrenchCommand input, kortex_driver::WrenchCommand &output) +{ + + output.reference_frame = input.reference_frame(); + output.mode = input.mode(); + ToRosData(input.wrench(), output.wrench); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::TwistCommand input, kortex_driver::TwistCommand &output) +{ + + output.reference_frame = input.reference_frame(); + ToRosData(input.twist(), output.twist); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConstrainedJointAngles input, kortex_driver::ConstrainedJointAngles &output) +{ + + ToRosData(input.joint_angles(), output.joint_angles); + ToRosData(input.constraint(), output.constraint); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ConstrainedJointAngle input, kortex_driver::ConstrainedJointAngle &output) +{ + + output.joint_identifier = input.joint_identifier(); + output.value = input.value(); + ToRosData(input.constraint(), output.constraint); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointAngles input, kortex_driver::JointAngles &output) +{ + + output.joint_angles.clear(); + for(int i = 0; i < input.joint_angles_size(); i++) + { + kortex_driver::JointAngle temp; + ToRosData(input.joint_angles(i), temp); + output.joint_angles.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointAngle input, kortex_driver::JointAngle &output) +{ + + output.joint_identifier = input.joint_identifier(); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointSpeeds input, kortex_driver::Base_JointSpeeds &output) +{ + + output.joint_speeds.clear(); + for(int i = 0; i < input.joint_speeds_size(); i++) + { + kortex_driver::JointSpeed temp; + ToRosData(input.joint_speeds(i), temp); + output.joint_speeds.push_back(temp); + } + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointSpeed input, kortex_driver::JointSpeed &output) +{ + + output.joint_identifier = input.joint_identifier(); + output.value = input.value(); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointTorques input, kortex_driver::JointTorques &output) +{ + + output.joint_torques.clear(); + for(int i = 0; i < input.joint_torques_size(); i++) + { + kortex_driver::JointTorque temp; + ToRosData(input.joint_torques(i), temp); + output.joint_torques.push_back(temp); + } + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::JointTorque input, kortex_driver::JointTorque &output) +{ + + output.joint_identifier = input.joint_identifier(); + output.value = input.value(); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::GripperCommand input, kortex_driver::GripperCommand &output) +{ + + output.mode = input.mode(); + ToRosData(input.gripper(), output.gripper); + output.duration = input.duration(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::GripperRequest input, kortex_driver::GripperRequest &output) +{ + + output.mode = input.mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Gripper input, kortex_driver::Gripper &output) +{ + + output.finger.clear(); + for(int i = 0; i < input.finger_size(); i++) + { + kortex_driver::Finger temp; + ToRosData(input.finger(i), temp); + output.finger.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::Finger input, kortex_driver::Finger &output) +{ + + output.finger_identifier = input.finger_identifier(); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::SystemTime input, kortex_driver::SystemTime &output) +{ + + output.sec = input.sec(); + output.min = input.min(); + output.hour = input.hour(); + output.mday = input.mday(); + output.mon = input.mon(); + output.year = input.year(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerConfigurationMode input, kortex_driver::ControllerConfigurationMode &output) +{ + + output.enable = input.enable(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerConfiguration input, kortex_driver::ControllerConfiguration &output) +{ + + ToRosData(input.handle(), output.handle); + output.name = input.name(); + ToRosData(input.active_mapping_handle(), output.active_mapping_handle); + output.analog_input_identifier_enum = input.analog_input_identifier_enum(); + output.digital_input_identifier_enum = input.digital_input_identifier_enum(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ControllerConfigurationList input, kortex_driver::ControllerConfigurationList &output) +{ + + output.controller_configurations.clear(); + for(int i = 0; i < input.controller_configurations_size(); i++) + { + kortex_driver::ControllerConfiguration temp; + ToRosData(input.controller_configurations(i), temp); + output.controller_configurations.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ActuatorInformation input, kortex_driver::ActuatorInformation &output) +{ + + output.count = input.count(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ArmStateInformation input, kortex_driver::ArmStateInformation &output) +{ + + output.active_state = input.active_state(); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::ArmStateNotification input, kortex_driver::ArmStateNotification &output) +{ + + output.active_state = input.active_state(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::CapSenseConfig input, kortex_driver::Base_CapSenseConfig &output) +{ + + output.identifier = input.identifier(); + output.mode = input.mode(); + output.threshold_a = input.threshold_a(); + output.threshold_b = input.threshold_b(); + output.sensitivity_a = input.sensitivity_a(); + output.sensitivity_b = input.sensitivity_b(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::BridgeList input, kortex_driver::BridgeList &output) +{ + + output.bridgeConfig.clear(); + for(int i = 0; i < input.bridgeconfig_size(); i++) + { + kortex_driver::BridgeConfig temp; + ToRosData(input.bridgeconfig(i), temp); + output.bridgeConfig.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::BridgeResult input, kortex_driver::BridgeResult &output) +{ + + ToRosData(input.bridge_id(), output.bridge_id); + output.status = input.status(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::BridgeIdentifier input, kortex_driver::BridgeIdentifier &output) +{ + + output.bridge_id = input.bridge_id(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::BridgeConfig input, kortex_driver::BridgeConfig &output) +{ + + output.device_identifier = input.device_identifier(); + output.bridgetype = input.bridgetype(); + ToRosData(input.port_config(), output.port_config); + ToRosData(input.bridge_id(), output.bridge_id); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::BridgePortConfig input, kortex_driver::BridgePortConfig &output) +{ + + output.target_port = input.target_port(); + output.out_port = input.out_port(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::PreComputedJointTrajectory input, kortex_driver::PreComputedJointTrajectory &output) +{ + + output.mode = input.mode(); + output.trajectory_elements.clear(); + for(int i = 0; i < input.trajectory_elements_size(); i++) + { + kortex_driver::PreComputedJointTrajectoryElement temp; + ToRosData(input.trajectory_elements(i), temp); + output.trajectory_elements.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::PreComputedJointTrajectoryElement input, kortex_driver::PreComputedJointTrajectoryElement &output) +{ + + output.joint_angles.clear(); + for(int i = 0; i < input.joint_angles_size(); i++) + { + output.joint_angles.push_back(input.joint_angles(i)); + } + output.joint_speeds.clear(); + for(int i = 0; i < input.joint_speeds_size(); i++) + { + output.joint_speeds.push_back(input.joint_speeds(i)); + } + output.joint_accelerations.clear(); + for(int i = 0; i < input.joint_accelerations_size(); i++) + { + output.joint_accelerations.push_back(input.joint_accelerations(i)); + } + output.time_from_start = input.time_from_start(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::TrajectoryErrorElement input, kortex_driver::TrajectoryErrorElement &output) +{ + + output.error_type = input.error_type(); + output.error_identifier = input.error_identifier(); + output.error_value = input.error_value(); + output.min_value = input.min_value(); + output.max_value = input.max_value(); + output.index = input.index(); + output.message = input.message(); + + + + return 0; +} +int ToRosData(Kinova::Api::Base::TrajectoryErrorReport input, kortex_driver::TrajectoryErrorReport &output) +{ + + output.trajectory_error_elements.clear(); + for(int i = 0; i < input.trajectory_error_elements_size(); i++) + { + kortex_driver::TrajectoryErrorElement temp; + ToRosData(input.trajectory_error_elements(i), temp); + output.trajectory_error_elements.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::FirmwareBundleVersions input, kortex_driver::FirmwareBundleVersions &output) +{ + + output.main_bundle_version = input.main_bundle_version(); + output.components_versions.clear(); + for(int i = 0; i < input.components_versions_size(); i++) + { + kortex_driver::FirmwareComponentVersion temp; + ToRosData(input.components_versions(i), temp); + output.components_versions.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::Base::FirmwareComponentVersion input, kortex_driver::FirmwareComponentVersion &output) +{ + + output.name = input.name(); + output.version = input.version(); + output.device_id = input.device_id(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/base_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/base_services.cpp new file mode 100644 index 0000000..1a8a6dd --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/base_services.cpp @@ -0,0 +1,5150 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/base_services.h" + +BaseRobotServices::BaseRobotServices(ros::NodeHandle& node_handle, Kinova::Api::Base::BaseClient* base, uint32_t device_id, uint32_t timeout_ms): + IBaseServices(node_handle), + m_base(base), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_ConfigurationChangeTopic = m_node_handle.advertise("configuration_change_topic", 1000); + m_is_activated_ConfigurationChangeTopic = false; + m_pub_MappingInfoTopic = m_node_handle.advertise("mapping_info_topic", 1000); + m_is_activated_MappingInfoTopic = false; + m_pub_ControlModeTopic = m_node_handle.advertise("control_mode_topic", 1000); + m_is_activated_ControlModeTopic = false; + m_pub_OperatingModeTopic = m_node_handle.advertise("operating_mode_topic", 1000); + m_is_activated_OperatingModeTopic = false; + m_pub_SequenceInfoTopic = m_node_handle.advertise("sequence_info_topic", 1000); + m_is_activated_SequenceInfoTopic = false; + m_pub_ProtectionZoneTopic = m_node_handle.advertise("protection_zone_topic", 1000); + m_is_activated_ProtectionZoneTopic = false; + m_pub_UserTopic = m_node_handle.advertise("user_topic", 1000); + m_is_activated_UserTopic = false; + m_pub_ControllerTopic = m_node_handle.advertise("controller_topic", 1000); + m_is_activated_ControllerTopic = false; + m_pub_ActionTopic = m_node_handle.advertise("action_topic", 1000); + m_is_activated_ActionTopic = false; + m_pub_RobotEventTopic = m_node_handle.advertise("robot_event_topic", 1000); + m_is_activated_RobotEventTopic = false; + m_pub_ServoingModeTopic = m_node_handle.advertise("servoing_mode_topic", 1000); + m_is_activated_ServoingModeTopic = false; + m_pub_FactoryTopic = m_node_handle.advertise("factory_topic", 1000); + m_is_activated_FactoryTopic = false; + m_pub_NetworkTopic = m_node_handle.advertise("network_topic", 1000); + m_is_activated_NetworkTopic = false; + m_pub_ArmStateTopic = m_node_handle.advertise("arm_state_topic", 1000); + m_is_activated_ArmStateTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("base/set_device_id", &BaseRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("base/set_api_options", &BaseRobotServices::SetApiOptions, this); + + m_serviceCreateUserProfile = m_node_handle.advertiseService("base/create_user_profile", &BaseRobotServices::CreateUserProfile, this); + m_serviceUpdateUserProfile = m_node_handle.advertiseService("base/update_user_profile", &BaseRobotServices::UpdateUserProfile, this); + m_serviceReadUserProfile = m_node_handle.advertiseService("base/read_user_profile", &BaseRobotServices::ReadUserProfile, this); + m_serviceDeleteUserProfile = m_node_handle.advertiseService("base/delete_user_profile", &BaseRobotServices::DeleteUserProfile, this); + m_serviceReadAllUserProfiles = m_node_handle.advertiseService("base/read_all_user_profiles", &BaseRobotServices::ReadAllUserProfiles, this); + m_serviceReadAllUsers = m_node_handle.advertiseService("base/read_all_users", &BaseRobotServices::ReadAllUsers, this); + m_serviceChangePassword = m_node_handle.advertiseService("base/change_password", &BaseRobotServices::ChangePassword, this); + m_serviceCreateSequence = m_node_handle.advertiseService("base/create_sequence", &BaseRobotServices::CreateSequence, this); + m_serviceUpdateSequence = m_node_handle.advertiseService("base/update_sequence", &BaseRobotServices::UpdateSequence, this); + m_serviceReadSequence = m_node_handle.advertiseService("base/read_sequence", &BaseRobotServices::ReadSequence, this); + m_serviceDeleteSequence = m_node_handle.advertiseService("base/delete_sequence", &BaseRobotServices::DeleteSequence, this); + m_serviceReadAllSequences = m_node_handle.advertiseService("base/read_all_sequences", &BaseRobotServices::ReadAllSequences, this); + m_servicePlaySequence = m_node_handle.advertiseService("base/play_sequence", &BaseRobotServices::PlaySequence, this); + m_servicePlayAdvancedSequence = m_node_handle.advertiseService("base/play_advanced_sequence", &BaseRobotServices::PlayAdvancedSequence, this); + m_serviceStopSequence = m_node_handle.advertiseService("base/stop_sequence", &BaseRobotServices::StopSequence, this); + m_servicePauseSequence = m_node_handle.advertiseService("base/pause_sequence", &BaseRobotServices::PauseSequence, this); + m_serviceResumeSequence = m_node_handle.advertiseService("base/resume_sequence", &BaseRobotServices::ResumeSequence, this); + m_serviceCreateProtectionZone = m_node_handle.advertiseService("base/create_protection_zone", &BaseRobotServices::CreateProtectionZone, this); + m_serviceUpdateProtectionZone = m_node_handle.advertiseService("base/update_protection_zone", &BaseRobotServices::UpdateProtectionZone, this); + m_serviceReadProtectionZone = m_node_handle.advertiseService("base/read_protection_zone", &BaseRobotServices::ReadProtectionZone, this); + m_serviceDeleteProtectionZone = m_node_handle.advertiseService("base/delete_protection_zone", &BaseRobotServices::DeleteProtectionZone, this); + m_serviceReadAllProtectionZones = m_node_handle.advertiseService("base/read_all_protection_zones", &BaseRobotServices::ReadAllProtectionZones, this); + m_serviceCreateMapping = m_node_handle.advertiseService("base/create_mapping", &BaseRobotServices::CreateMapping, this); + m_serviceReadMapping = m_node_handle.advertiseService("base/read_mapping", &BaseRobotServices::ReadMapping, this); + m_serviceUpdateMapping = m_node_handle.advertiseService("base/update_mapping", &BaseRobotServices::UpdateMapping, this); + m_serviceDeleteMapping = m_node_handle.advertiseService("base/delete_mapping", &BaseRobotServices::DeleteMapping, this); + m_serviceReadAllMappings = m_node_handle.advertiseService("base/read_all_mappings", &BaseRobotServices::ReadAllMappings, this); + m_serviceCreateMap = m_node_handle.advertiseService("base/create_map", &BaseRobotServices::CreateMap, this); + m_serviceReadMap = m_node_handle.advertiseService("base/read_map", &BaseRobotServices::ReadMap, this); + m_serviceUpdateMap = m_node_handle.advertiseService("base/update_map", &BaseRobotServices::UpdateMap, this); + m_serviceDeleteMap = m_node_handle.advertiseService("base/delete_map", &BaseRobotServices::DeleteMap, this); + m_serviceReadAllMaps = m_node_handle.advertiseService("base/read_all_maps", &BaseRobotServices::ReadAllMaps, this); + m_serviceActivateMap = m_node_handle.advertiseService("base/activate_map", &BaseRobotServices::ActivateMap, this); + m_serviceCreateAction = m_node_handle.advertiseService("base/create_action", &BaseRobotServices::CreateAction, this); + m_serviceReadAction = m_node_handle.advertiseService("base/read_action", &BaseRobotServices::ReadAction, this); + m_serviceReadAllActions = m_node_handle.advertiseService("base/read_all_actions", &BaseRobotServices::ReadAllActions, this); + m_serviceDeleteAction = m_node_handle.advertiseService("base/delete_action", &BaseRobotServices::DeleteAction, this); + m_serviceUpdateAction = m_node_handle.advertiseService("base/update_action", &BaseRobotServices::UpdateAction, this); + m_serviceExecuteActionFromReference = m_node_handle.advertiseService("base/execute_action_from_reference", &BaseRobotServices::ExecuteActionFromReference, this); + m_serviceExecuteAction = m_node_handle.advertiseService("base/execute_action", &BaseRobotServices::ExecuteAction, this); + m_servicePauseAction = m_node_handle.advertiseService("base/pause_action", &BaseRobotServices::PauseAction, this); + m_serviceStopAction = m_node_handle.advertiseService("base/stop_action", &BaseRobotServices::StopAction, this); + m_serviceResumeAction = m_node_handle.advertiseService("base/resume_action", &BaseRobotServices::ResumeAction, this); + m_serviceGetIPv4Configuration = m_node_handle.advertiseService("base/get_i_pv4_configuration", &BaseRobotServices::GetIPv4Configuration, this); + m_serviceSetIPv4Configuration = m_node_handle.advertiseService("base/set_i_pv4_configuration", &BaseRobotServices::SetIPv4Configuration, this); + m_serviceSetCommunicationInterfaceEnable = m_node_handle.advertiseService("base/set_communication_interface_enable", &BaseRobotServices::SetCommunicationInterfaceEnable, this); + m_serviceIsCommunicationInterfaceEnable = m_node_handle.advertiseService("base/is_communication_interface_enable", &BaseRobotServices::IsCommunicationInterfaceEnable, this); + m_serviceGetAvailableWifi = m_node_handle.advertiseService("base/get_available_wifi", &BaseRobotServices::GetAvailableWifi, this); + m_serviceGetWifiInformation = m_node_handle.advertiseService("base/get_wifi_information", &BaseRobotServices::GetWifiInformation, this); + m_serviceAddWifiConfiguration = m_node_handle.advertiseService("base/add_wifi_configuration", &BaseRobotServices::AddWifiConfiguration, this); + m_serviceDeleteWifiConfiguration = m_node_handle.advertiseService("base/delete_wifi_configuration", &BaseRobotServices::DeleteWifiConfiguration, this); + m_serviceGetAllConfiguredWifis = m_node_handle.advertiseService("base/get_all_configured_wifis", &BaseRobotServices::GetAllConfiguredWifis, this); + m_serviceConnectWifi = m_node_handle.advertiseService("base/connect_wifi", &BaseRobotServices::ConnectWifi, this); + m_serviceDisconnectWifi = m_node_handle.advertiseService("base/disconnect_wifi", &BaseRobotServices::DisconnectWifi, this); + m_serviceGetConnectedWifiInformation = m_node_handle.advertiseService("base/get_connected_wifi_information", &BaseRobotServices::GetConnectedWifiInformation, this); + m_serviceBase_Unsubscribe = m_node_handle.advertiseService("base/unsubscribe", &BaseRobotServices::Base_Unsubscribe, this); + m_serviceOnNotificationConfigurationChangeTopic = m_node_handle.advertiseService("base/activate_publishing_of_configuration_change_topic", &BaseRobotServices::OnNotificationConfigurationChangeTopic, this); + m_serviceOnNotificationMappingInfoTopic = m_node_handle.advertiseService("base/activate_publishing_of_mapping_info_topic", &BaseRobotServices::OnNotificationMappingInfoTopic, this); + m_serviceOnNotificationControlModeTopic = m_node_handle.advertiseService("base/activate_publishing_of_control_mode_topic", &BaseRobotServices::OnNotificationControlModeTopic, this); + m_serviceOnNotificationOperatingModeTopic = m_node_handle.advertiseService("base/activate_publishing_of_operating_mode_topic", &BaseRobotServices::OnNotificationOperatingModeTopic, this); + m_serviceOnNotificationSequenceInfoTopic = m_node_handle.advertiseService("base/activate_publishing_of_sequence_info_topic", &BaseRobotServices::OnNotificationSequenceInfoTopic, this); + m_serviceOnNotificationProtectionZoneTopic = m_node_handle.advertiseService("base/activate_publishing_of_protection_zone_topic", &BaseRobotServices::OnNotificationProtectionZoneTopic, this); + m_serviceOnNotificationUserTopic = m_node_handle.advertiseService("base/activate_publishing_of_user_topic", &BaseRobotServices::OnNotificationUserTopic, this); + m_serviceOnNotificationControllerTopic = m_node_handle.advertiseService("base/activate_publishing_of_controller_topic", &BaseRobotServices::OnNotificationControllerTopic, this); + m_serviceOnNotificationActionTopic = m_node_handle.advertiseService("base/activate_publishing_of_action_topic", &BaseRobotServices::OnNotificationActionTopic, this); + m_serviceOnNotificationRobotEventTopic = m_node_handle.advertiseService("base/activate_publishing_of_robot_event_topic", &BaseRobotServices::OnNotificationRobotEventTopic, this); + m_servicePlayCartesianTrajectory = m_node_handle.advertiseService("base/play_cartesian_trajectory", &BaseRobotServices::PlayCartesianTrajectory, this); + m_servicePlayCartesianTrajectoryPosition = m_node_handle.advertiseService("base/play_cartesian_trajectory_position", &BaseRobotServices::PlayCartesianTrajectoryPosition, this); + m_servicePlayCartesianTrajectoryOrientation = m_node_handle.advertiseService("base/play_cartesian_trajectory_orientation", &BaseRobotServices::PlayCartesianTrajectoryOrientation, this); + m_serviceStop = m_node_handle.advertiseService("base/stop", &BaseRobotServices::Stop, this); + m_serviceGetMeasuredCartesianPose = m_node_handle.advertiseService("base/get_measured_cartesian_pose", &BaseRobotServices::GetMeasuredCartesianPose, this); + m_serviceSendWrenchCommand = m_node_handle.advertiseService("base/send_wrench_command", &BaseRobotServices::SendWrenchCommand, this); + m_serviceSendWrenchJoystickCommand = m_node_handle.advertiseService("base/send_wrench_joystick_command", &BaseRobotServices::SendWrenchJoystickCommand, this); + m_serviceSendTwistJoystickCommand = m_node_handle.advertiseService("base/send_twist_joystick_command", &BaseRobotServices::SendTwistJoystickCommand, this); + m_serviceSendTwistCommand = m_node_handle.advertiseService("base/send_twist_command", &BaseRobotServices::SendTwistCommand, this); + m_servicePlayJointTrajectory = m_node_handle.advertiseService("base/play_joint_trajectory", &BaseRobotServices::PlayJointTrajectory, this); + m_servicePlaySelectedJointTrajectory = m_node_handle.advertiseService("base/play_selected_joint_trajectory", &BaseRobotServices::PlaySelectedJointTrajectory, this); + m_serviceGetMeasuredJointAngles = m_node_handle.advertiseService("base/get_measured_joint_angles", &BaseRobotServices::GetMeasuredJointAngles, this); + m_serviceSendJointSpeedsCommand = m_node_handle.advertiseService("base/send_joint_speeds_command", &BaseRobotServices::SendJointSpeedsCommand, this); + m_serviceSendSelectedJointSpeedCommand = m_node_handle.advertiseService("base/send_selected_joint_speed_command", &BaseRobotServices::SendSelectedJointSpeedCommand, this); + m_serviceSendGripperCommand = m_node_handle.advertiseService("base/send_gripper_command", &BaseRobotServices::SendGripperCommand, this); + m_serviceGetMeasuredGripperMovement = m_node_handle.advertiseService("base/get_measured_gripper_movement", &BaseRobotServices::GetMeasuredGripperMovement, this); + m_serviceSetAdmittance = m_node_handle.advertiseService("base/set_admittance", &BaseRobotServices::SetAdmittance, this); + m_serviceSetOperatingMode = m_node_handle.advertiseService("base/set_operating_mode", &BaseRobotServices::SetOperatingMode, this); + m_serviceApplyEmergencyStop = m_node_handle.advertiseService("base/apply_emergency_stop", &BaseRobotServices::ApplyEmergencyStop, this); + m_serviceBase_ClearFaults = m_node_handle.advertiseService("base/clear_faults", &BaseRobotServices::Base_ClearFaults, this); + m_serviceBase_GetControlMode = m_node_handle.advertiseService("base/get_control_mode", &BaseRobotServices::Base_GetControlMode, this); + m_serviceGetOperatingMode = m_node_handle.advertiseService("base/get_operating_mode", &BaseRobotServices::GetOperatingMode, this); + m_serviceSetServoingMode = m_node_handle.advertiseService("base/set_servoing_mode", &BaseRobotServices::SetServoingMode, this); + m_serviceGetServoingMode = m_node_handle.advertiseService("base/get_servoing_mode", &BaseRobotServices::GetServoingMode, this); + m_serviceOnNotificationServoingModeTopic = m_node_handle.advertiseService("base/activate_publishing_of_servoing_mode_topic", &BaseRobotServices::OnNotificationServoingModeTopic, this); + m_serviceRestoreFactorySettings = m_node_handle.advertiseService("base/restore_factory_settings", &BaseRobotServices::RestoreFactorySettings, this); + m_serviceOnNotificationFactoryTopic = m_node_handle.advertiseService("base/activate_publishing_of_factory_topic", &BaseRobotServices::OnNotificationFactoryTopic, this); + m_serviceGetAllConnectedControllers = m_node_handle.advertiseService("base/get_all_connected_controllers", &BaseRobotServices::GetAllConnectedControllers, this); + m_serviceGetControllerState = m_node_handle.advertiseService("base/get_controller_state", &BaseRobotServices::GetControllerState, this); + m_serviceGetActuatorCount = m_node_handle.advertiseService("base/get_actuator_count", &BaseRobotServices::GetActuatorCount, this); + m_serviceStartWifiScan = m_node_handle.advertiseService("base/start_wifi_scan", &BaseRobotServices::StartWifiScan, this); + m_serviceGetConfiguredWifi = m_node_handle.advertiseService("base/get_configured_wifi", &BaseRobotServices::GetConfiguredWifi, this); + m_serviceOnNotificationNetworkTopic = m_node_handle.advertiseService("base/activate_publishing_of_network_topic", &BaseRobotServices::OnNotificationNetworkTopic, this); + m_serviceGetArmState = m_node_handle.advertiseService("base/get_arm_state", &BaseRobotServices::GetArmState, this); + m_serviceOnNotificationArmStateTopic = m_node_handle.advertiseService("base/activate_publishing_of_arm_state_topic", &BaseRobotServices::OnNotificationArmStateTopic, this); + m_serviceGetIPv4Information = m_node_handle.advertiseService("base/get_i_pv4_information", &BaseRobotServices::GetIPv4Information, this); + m_serviceSetWifiCountryCode = m_node_handle.advertiseService("base/set_wifi_country_code", &BaseRobotServices::SetWifiCountryCode, this); + m_serviceGetWifiCountryCode = m_node_handle.advertiseService("base/get_wifi_country_code", &BaseRobotServices::GetWifiCountryCode, this); + m_serviceBase_SetCapSenseConfig = m_node_handle.advertiseService("base/set_cap_sense_config", &BaseRobotServices::Base_SetCapSenseConfig, this); + m_serviceBase_GetCapSenseConfig = m_node_handle.advertiseService("base/get_cap_sense_config", &BaseRobotServices::Base_GetCapSenseConfig, this); + m_serviceGetAllJointsSpeedHardLimitation = m_node_handle.advertiseService("base/get_all_joints_speed_hard_limitation", &BaseRobotServices::GetAllJointsSpeedHardLimitation, this); + m_serviceGetAllJointsTorqueHardLimitation = m_node_handle.advertiseService("base/get_all_joints_torque_hard_limitation", &BaseRobotServices::GetAllJointsTorqueHardLimitation, this); + m_serviceGetTwistHardLimitation = m_node_handle.advertiseService("base/get_twist_hard_limitation", &BaseRobotServices::GetTwistHardLimitation, this); + m_serviceGetWrenchHardLimitation = m_node_handle.advertiseService("base/get_wrench_hard_limitation", &BaseRobotServices::GetWrenchHardLimitation, this); + m_serviceSendJointSpeedsJoystickCommand = m_node_handle.advertiseService("base/send_joint_speeds_joystick_command", &BaseRobotServices::SendJointSpeedsJoystickCommand, this); + m_serviceSendSelectedJointSpeedJoystickCommand = m_node_handle.advertiseService("base/send_selected_joint_speed_joystick_command", &BaseRobotServices::SendSelectedJointSpeedJoystickCommand, this); + m_serviceEnableBridge = m_node_handle.advertiseService("base/enable_bridge", &BaseRobotServices::EnableBridge, this); + m_serviceDisableBridge = m_node_handle.advertiseService("base/disable_bridge", &BaseRobotServices::DisableBridge, this); + m_serviceGetBridgeList = m_node_handle.advertiseService("base/get_bridge_list", &BaseRobotServices::GetBridgeList, this); + m_serviceGetBridgeConfig = m_node_handle.advertiseService("base/get_bridge_config", &BaseRobotServices::GetBridgeConfig, this); + m_servicePlayPreComputedJointTrajectory = m_node_handle.advertiseService("base/play_pre_computed_joint_trajectory", &BaseRobotServices::PlayPreComputedJointTrajectory, this); + m_serviceGetProductConfiguration = m_node_handle.advertiseService("base/get_product_configuration", &BaseRobotServices::GetProductConfiguration, this); + m_serviceUpdateEndEffectorTypeConfiguration = m_node_handle.advertiseService("base/update_end_effector_type_configuration", &BaseRobotServices::UpdateEndEffectorTypeConfiguration, this); + m_serviceRestoreFactoryProductConfiguration = m_node_handle.advertiseService("base/restore_factory_product_configuration", &BaseRobotServices::RestoreFactoryProductConfiguration, this); + m_serviceGetTrajectoryErrorReport = m_node_handle.advertiseService("base/get_trajectory_error_report", &BaseRobotServices::GetTrajectoryErrorReport, this); + m_serviceGetAllJointsSpeedSoftLimitation = m_node_handle.advertiseService("base/get_all_joints_speed_soft_limitation", &BaseRobotServices::GetAllJointsSpeedSoftLimitation, this); + m_serviceGetAllJointsTorqueSoftLimitation = m_node_handle.advertiseService("base/get_all_joints_torque_soft_limitation", &BaseRobotServices::GetAllJointsTorqueSoftLimitation, this); + m_serviceGetTwistSoftLimitation = m_node_handle.advertiseService("base/get_twist_soft_limitation", &BaseRobotServices::GetTwistSoftLimitation, this); + m_serviceGetWrenchSoftLimitation = m_node_handle.advertiseService("base/get_wrench_soft_limitation", &BaseRobotServices::GetWrenchSoftLimitation, this); + m_serviceSetControllerConfigurationMode = m_node_handle.advertiseService("base/set_controller_configuration_mode", &BaseRobotServices::SetControllerConfigurationMode, this); + m_serviceGetControllerConfigurationMode = m_node_handle.advertiseService("base/get_controller_configuration_mode", &BaseRobotServices::GetControllerConfigurationMode, this); + m_serviceStartTeaching = m_node_handle.advertiseService("base/start_teaching", &BaseRobotServices::StartTeaching, this); + m_serviceStopTeaching = m_node_handle.advertiseService("base/stop_teaching", &BaseRobotServices::StopTeaching, this); + m_serviceAddSequenceTasks = m_node_handle.advertiseService("base/add_sequence_tasks", &BaseRobotServices::AddSequenceTasks, this); + m_serviceUpdateSequenceTask = m_node_handle.advertiseService("base/update_sequence_task", &BaseRobotServices::UpdateSequenceTask, this); + m_serviceSwapSequenceTasks = m_node_handle.advertiseService("base/swap_sequence_tasks", &BaseRobotServices::SwapSequenceTasks, this); + m_serviceReadSequenceTask = m_node_handle.advertiseService("base/read_sequence_task", &BaseRobotServices::ReadSequenceTask, this); + m_serviceReadAllSequenceTasks = m_node_handle.advertiseService("base/read_all_sequence_tasks", &BaseRobotServices::ReadAllSequenceTasks, this); + m_serviceDeleteSequenceTask = m_node_handle.advertiseService("base/delete_sequence_task", &BaseRobotServices::DeleteSequenceTask, this); + m_serviceDeleteAllSequenceTasks = m_node_handle.advertiseService("base/delete_all_sequence_tasks", &BaseRobotServices::DeleteAllSequenceTasks, this); + m_serviceTakeSnapshot = m_node_handle.advertiseService("base/take_snapshot", &BaseRobotServices::TakeSnapshot, this); + m_serviceGetFirmwareBundleVersions = m_node_handle.advertiseService("base/get_firmware_bundle_versions", &BaseRobotServices::GetFirmwareBundleVersions, this); + m_serviceMoveSequenceTask = m_node_handle.advertiseService("base/move_sequence_task", &BaseRobotServices::MoveSequenceTask, this); + m_serviceDuplicateMapping = m_node_handle.advertiseService("base/duplicate_mapping", &BaseRobotServices::DuplicateMapping, this); + m_serviceDuplicateMap = m_node_handle.advertiseService("base/duplicate_map", &BaseRobotServices::DuplicateMap, this); + m_serviceSetControllerConfiguration = m_node_handle.advertiseService("base/set_controller_configuration", &BaseRobotServices::SetControllerConfiguration, this); + m_serviceGetControllerConfiguration = m_node_handle.advertiseService("base/get_controller_configuration", &BaseRobotServices::GetControllerConfiguration, this); + m_serviceGetAllControllerConfigurations = m_node_handle.advertiseService("base/get_all_controller_configurations", &BaseRobotServices::GetAllControllerConfigurations, this); +} + +bool BaseRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool BaseRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool BaseRobotServices::CreateUserProfile(kortex_driver::CreateUserProfile::Request &req, kortex_driver::CreateUserProfile::Response &res) +{ + + Kinova::Api::Base::FullUserProfile input; + ToProtoData(req.input, &input); + Kinova::Api::Common::UserProfileHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->CreateUserProfile(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateUserProfile(kortex_driver::UpdateUserProfile::Request &req, kortex_driver::UpdateUserProfile::Response &res) +{ + + Kinova::Api::Base::UserProfile input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateUserProfile(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadUserProfile(kortex_driver::ReadUserProfile::Request &req, kortex_driver::ReadUserProfile::Response &res) +{ + + Kinova::Api::Common::UserProfileHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::UserProfile output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadUserProfile(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DeleteUserProfile(kortex_driver::DeleteUserProfile::Request &req, kortex_driver::DeleteUserProfile::Response &res) +{ + + Kinova::Api::Common::UserProfileHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteUserProfile(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadAllUserProfiles(kortex_driver::ReadAllUserProfiles::Request &req, kortex_driver::ReadAllUserProfiles::Response &res) +{ + + Kinova::Api::Base::UserProfileList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllUserProfiles(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ReadAllUsers(kortex_driver::ReadAllUsers::Request &req, kortex_driver::ReadAllUsers::Response &res) +{ + + Kinova::Api::Base::UserList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllUsers(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ChangePassword(kortex_driver::ChangePassword::Request &req, kortex_driver::ChangePassword::Response &res) +{ + + Kinova::Api::Base::PasswordChange input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->ChangePassword(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::CreateSequence(kortex_driver::CreateSequence::Request &req, kortex_driver::CreateSequence::Response &res) +{ + + Kinova::Api::Base::Sequence input; + ToProtoData(req.input, &input); + Kinova::Api::Base::SequenceHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->CreateSequence(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateSequence(kortex_driver::UpdateSequence::Request &req, kortex_driver::UpdateSequence::Response &res) +{ + + Kinova::Api::Base::Sequence input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateSequence(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadSequence(kortex_driver::ReadSequence::Request &req, kortex_driver::ReadSequence::Response &res) +{ + + Kinova::Api::Base::SequenceHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::Sequence output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadSequence(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DeleteSequence(kortex_driver::DeleteSequence::Request &req, kortex_driver::DeleteSequence::Response &res) +{ + + Kinova::Api::Base::SequenceHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteSequence(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadAllSequences(kortex_driver::ReadAllSequences::Request &req, kortex_driver::ReadAllSequences::Response &res) +{ + + Kinova::Api::Base::SequenceList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllSequences(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::PlaySequence(kortex_driver::PlaySequence::Request &req, kortex_driver::PlaySequence::Response &res) +{ + + Kinova::Api::Base::SequenceHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlaySequence(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PlayAdvancedSequence(kortex_driver::PlayAdvancedSequence::Request &req, kortex_driver::PlayAdvancedSequence::Response &res) +{ + + Kinova::Api::Base::AdvancedSequenceHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlayAdvancedSequence(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::StopSequence(kortex_driver::StopSequence::Request &req, kortex_driver::StopSequence::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->StopSequence(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PauseSequence(kortex_driver::PauseSequence::Request &req, kortex_driver::PauseSequence::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->PauseSequence(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ResumeSequence(kortex_driver::ResumeSequence::Request &req, kortex_driver::ResumeSequence::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->ResumeSequence(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::CreateProtectionZone(kortex_driver::CreateProtectionZone::Request &req, kortex_driver::CreateProtectionZone::Response &res) +{ + + Kinova::Api::Base::ProtectionZone input; + ToProtoData(req.input, &input); + Kinova::Api::Base::ProtectionZoneHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->CreateProtectionZone(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateProtectionZone(kortex_driver::UpdateProtectionZone::Request &req, kortex_driver::UpdateProtectionZone::Response &res) +{ + + Kinova::Api::Base::ProtectionZone input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateProtectionZone(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadProtectionZone(kortex_driver::ReadProtectionZone::Request &req, kortex_driver::ReadProtectionZone::Response &res) +{ + + Kinova::Api::Base::ProtectionZoneHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::ProtectionZone output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadProtectionZone(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DeleteProtectionZone(kortex_driver::DeleteProtectionZone::Request &req, kortex_driver::DeleteProtectionZone::Response &res) +{ + + Kinova::Api::Base::ProtectionZoneHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteProtectionZone(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadAllProtectionZones(kortex_driver::ReadAllProtectionZones::Request &req, kortex_driver::ReadAllProtectionZones::Response &res) +{ + + Kinova::Api::Base::ProtectionZoneList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllProtectionZones(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::CreateMapping(kortex_driver::CreateMapping::Request &req, kortex_driver::CreateMapping::Response &res) +{ + + Kinova::Api::Base::Mapping input; + ToProtoData(req.input, &input); + Kinova::Api::Base::MappingHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->CreateMapping(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ReadMapping(kortex_driver::ReadMapping::Request &req, kortex_driver::ReadMapping::Response &res) +{ + + Kinova::Api::Base::MappingHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::Mapping output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadMapping(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateMapping(kortex_driver::UpdateMapping::Request &req, kortex_driver::UpdateMapping::Response &res) +{ + + Kinova::Api::Base::Mapping input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateMapping(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::DeleteMapping(kortex_driver::DeleteMapping::Request &req, kortex_driver::DeleteMapping::Response &res) +{ + + Kinova::Api::Base::MappingHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteMapping(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadAllMappings(kortex_driver::ReadAllMappings::Request &req, kortex_driver::ReadAllMappings::Response &res) +{ + + Kinova::Api::Base::MappingList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllMappings(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::CreateMap(kortex_driver::CreateMap::Request &req, kortex_driver::CreateMap::Response &res) +{ + + Kinova::Api::Base::Map input; + ToProtoData(req.input, &input); + Kinova::Api::Base::MapHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->CreateMap(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ReadMap(kortex_driver::ReadMap::Request &req, kortex_driver::ReadMap::Response &res) +{ + + Kinova::Api::Base::MapHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::Map output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadMap(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateMap(kortex_driver::UpdateMap::Request &req, kortex_driver::UpdateMap::Response &res) +{ + + Kinova::Api::Base::Map input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateMap(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::DeleteMap(kortex_driver::DeleteMap::Request &req, kortex_driver::DeleteMap::Response &res) +{ + + Kinova::Api::Base::MapHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteMap(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadAllMaps(kortex_driver::ReadAllMaps::Request &req, kortex_driver::ReadAllMaps::Response &res) +{ + + Kinova::Api::Base::MappingHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::MapList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllMaps(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ActivateMap(kortex_driver::ActivateMap::Request &req, kortex_driver::ActivateMap::Response &res) +{ + + Kinova::Api::Base::ActivateMapHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->ActivateMap(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::CreateAction(kortex_driver::CreateAction::Request &req, kortex_driver::CreateAction::Response &res) +{ + + Kinova::Api::Base::Action input; + ToProtoData(req.input, &input); + Kinova::Api::Base::ActionHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->CreateAction(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ReadAction(kortex_driver::ReadAction::Request &req, kortex_driver::ReadAction::Response &res) +{ + + Kinova::Api::Base::ActionHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::Action output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAction(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ReadAllActions(kortex_driver::ReadAllActions::Request &req, kortex_driver::ReadAllActions::Response &res) +{ + + Kinova::Api::Base::RequestedActionType input; + ToProtoData(req.input, &input); + Kinova::Api::Base::ActionList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllActions(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DeleteAction(kortex_driver::DeleteAction::Request &req, kortex_driver::DeleteAction::Response &res) +{ + + Kinova::Api::Base::ActionHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteAction(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::UpdateAction(kortex_driver::UpdateAction::Request &req, kortex_driver::UpdateAction::Response &res) +{ + + Kinova::Api::Base::Action input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateAction(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ExecuteActionFromReference(kortex_driver::ExecuteActionFromReference::Request &req, kortex_driver::ExecuteActionFromReference::Response &res) +{ + + Kinova::Api::Base::ActionHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->ExecuteActionFromReference(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ExecuteAction(kortex_driver::ExecuteAction::Request &req, kortex_driver::ExecuteAction::Response &res) +{ + + Kinova::Api::Base::Action input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->ExecuteAction(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PauseAction(kortex_driver::PauseAction::Request &req, kortex_driver::PauseAction::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->PauseAction(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::StopAction(kortex_driver::StopAction::Request &req, kortex_driver::StopAction::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->StopAction(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ResumeAction(kortex_driver::ResumeAction::Request &req, kortex_driver::ResumeAction::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->ResumeAction(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetIPv4Configuration(kortex_driver::GetIPv4Configuration::Request &req, kortex_driver::GetIPv4Configuration::Response &res) +{ + + Kinova::Api::Base::NetworkHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::IPv4Configuration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetIPv4Configuration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SetIPv4Configuration(kortex_driver::SetIPv4Configuration::Request &req, kortex_driver::SetIPv4Configuration::Response &res) +{ + + Kinova::Api::Base::FullIPv4Configuration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetIPv4Configuration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SetCommunicationInterfaceEnable(kortex_driver::SetCommunicationInterfaceEnable::Request &req, kortex_driver::SetCommunicationInterfaceEnable::Response &res) +{ + + Kinova::Api::Base::CommunicationInterfaceConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetCommunicationInterfaceEnable(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::IsCommunicationInterfaceEnable(kortex_driver::IsCommunicationInterfaceEnable::Request &req, kortex_driver::IsCommunicationInterfaceEnable::Response &res) +{ + + Kinova::Api::Base::NetworkHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::CommunicationInterfaceConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->IsCommunicationInterfaceEnable(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetAvailableWifi(kortex_driver::GetAvailableWifi::Request &req, kortex_driver::GetAvailableWifi::Response &res) +{ + + Kinova::Api::Base::WifiInformationList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAvailableWifi(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetWifiInformation(kortex_driver::GetWifiInformation::Request &req, kortex_driver::GetWifiInformation::Response &res) +{ + + Kinova::Api::Base::Ssid input; + ToProtoData(req.input, &input); + Kinova::Api::Base::WifiInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetWifiInformation(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::AddWifiConfiguration(kortex_driver::AddWifiConfiguration::Request &req, kortex_driver::AddWifiConfiguration::Response &res) +{ + + Kinova::Api::Base::WifiConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->AddWifiConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::DeleteWifiConfiguration(kortex_driver::DeleteWifiConfiguration::Request &req, kortex_driver::DeleteWifiConfiguration::Response &res) +{ + + Kinova::Api::Base::Ssid input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteWifiConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetAllConfiguredWifis(kortex_driver::GetAllConfiguredWifis::Request &req, kortex_driver::GetAllConfiguredWifis::Response &res) +{ + + Kinova::Api::Base::WifiConfigurationList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllConfiguredWifis(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ConnectWifi(kortex_driver::ConnectWifi::Request &req, kortex_driver::ConnectWifi::Response &res) +{ + + Kinova::Api::Base::Ssid input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->ConnectWifi(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::DisconnectWifi(kortex_driver::DisconnectWifi::Request &req, kortex_driver::DisconnectWifi::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->DisconnectWifi(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetConnectedWifiInformation(kortex_driver::GetConnectedWifiInformation::Request &req, kortex_driver::GetConnectedWifiInformation::Response &res) +{ + + Kinova::Api::Base::WifiInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetConnectedWifiInformation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::Base_Unsubscribe(kortex_driver::Base_Unsubscribe::Request &req, kortex_driver::Base_Unsubscribe::Response &res) +{ + + Kinova::Api::Common::NotificationHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->Unsubscribe(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::OnNotificationConfigurationChangeTopic(kortex_driver::OnNotificationConfigurationChangeTopic::Request &req, kortex_driver::OnNotificationConfigurationChangeTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ConfigurationChangeTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ConfigurationChangeNotification) > callback = std::bind(&BaseRobotServices::cb_ConfigurationChangeTopic, this, std::placeholders::_1); + output = m_base->OnNotificationConfigurationChangeTopic(callback, input, m_current_device_id); + m_is_activated_ConfigurationChangeTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ConfigurationChangeTopic(Kinova::Api::Base::ConfigurationChangeNotification notif) +{ + kortex_driver::ConfigurationChangeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ConfigurationChangeTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationMappingInfoTopic(kortex_driver::OnNotificationMappingInfoTopic::Request &req, kortex_driver::OnNotificationMappingInfoTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_MappingInfoTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::MappingInfoNotification) > callback = std::bind(&BaseRobotServices::cb_MappingInfoTopic, this, std::placeholders::_1); + output = m_base->OnNotificationMappingInfoTopic(callback, input, m_current_device_id); + m_is_activated_MappingInfoTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_MappingInfoTopic(Kinova::Api::Base::MappingInfoNotification notif) +{ + kortex_driver::MappingInfoNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_MappingInfoTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationControlModeTopic(kortex_driver::OnNotificationControlModeTopic::Request &req, kortex_driver::OnNotificationControlModeTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ControlModeTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ControlModeNotification) > callback = std::bind(&BaseRobotServices::cb_ControlModeTopic, this, std::placeholders::_1); + output = m_base->OnNotificationControlModeTopic(callback, input, m_current_device_id); + m_is_activated_ControlModeTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ControlModeTopic(Kinova::Api::Base::ControlModeNotification notif) +{ + kortex_driver::ControlModeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ControlModeTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationOperatingModeTopic(kortex_driver::OnNotificationOperatingModeTopic::Request &req, kortex_driver::OnNotificationOperatingModeTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_OperatingModeTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::OperatingModeNotification) > callback = std::bind(&BaseRobotServices::cb_OperatingModeTopic, this, std::placeholders::_1); + output = m_base->OnNotificationOperatingModeTopic(callback, input, m_current_device_id); + m_is_activated_OperatingModeTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_OperatingModeTopic(Kinova::Api::Base::OperatingModeNotification notif) +{ + kortex_driver::OperatingModeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_OperatingModeTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationSequenceInfoTopic(kortex_driver::OnNotificationSequenceInfoTopic::Request &req, kortex_driver::OnNotificationSequenceInfoTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_SequenceInfoTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::SequenceInfoNotification) > callback = std::bind(&BaseRobotServices::cb_SequenceInfoTopic, this, std::placeholders::_1); + output = m_base->OnNotificationSequenceInfoTopic(callback, input, m_current_device_id); + m_is_activated_SequenceInfoTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_SequenceInfoTopic(Kinova::Api::Base::SequenceInfoNotification notif) +{ + kortex_driver::SequenceInfoNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_SequenceInfoTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationProtectionZoneTopic(kortex_driver::OnNotificationProtectionZoneTopic::Request &req, kortex_driver::OnNotificationProtectionZoneTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ProtectionZoneTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ProtectionZoneNotification) > callback = std::bind(&BaseRobotServices::cb_ProtectionZoneTopic, this, std::placeholders::_1); + output = m_base->OnNotificationProtectionZoneTopic(callback, input, m_current_device_id); + m_is_activated_ProtectionZoneTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ProtectionZoneTopic(Kinova::Api::Base::ProtectionZoneNotification notif) +{ + kortex_driver::ProtectionZoneNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ProtectionZoneTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationUserTopic(kortex_driver::OnNotificationUserTopic::Request &req, kortex_driver::OnNotificationUserTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_UserTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::UserNotification) > callback = std::bind(&BaseRobotServices::cb_UserTopic, this, std::placeholders::_1); + output = m_base->OnNotificationUserTopic(callback, input, m_current_device_id); + m_is_activated_UserTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_UserTopic(Kinova::Api::Base::UserNotification notif) +{ + kortex_driver::UserNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_UserTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationControllerTopic(kortex_driver::OnNotificationControllerTopic::Request &req, kortex_driver::OnNotificationControllerTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ControllerTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ControllerNotification) > callback = std::bind(&BaseRobotServices::cb_ControllerTopic, this, std::placeholders::_1); + output = m_base->OnNotificationControllerTopic(callback, input, m_current_device_id); + m_is_activated_ControllerTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ControllerTopic(Kinova::Api::Base::ControllerNotification notif) +{ + kortex_driver::ControllerNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ControllerTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationActionTopic(kortex_driver::OnNotificationActionTopic::Request &req, kortex_driver::OnNotificationActionTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ActionTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ActionNotification) > callback = std::bind(&BaseRobotServices::cb_ActionTopic, this, std::placeholders::_1); + output = m_base->OnNotificationActionTopic(callback, input, m_current_device_id); + m_is_activated_ActionTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ActionTopic(Kinova::Api::Base::ActionNotification notif) +{ + kortex_driver::ActionNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ActionTopic.publish(ros_msg); +} + +bool BaseRobotServices::OnNotificationRobotEventTopic(kortex_driver::OnNotificationRobotEventTopic::Request &req, kortex_driver::OnNotificationRobotEventTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_RobotEventTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::RobotEventNotification) > callback = std::bind(&BaseRobotServices::cb_RobotEventTopic, this, std::placeholders::_1); + output = m_base->OnNotificationRobotEventTopic(callback, input, m_current_device_id); + m_is_activated_RobotEventTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_RobotEventTopic(Kinova::Api::Base::RobotEventNotification notif) +{ + kortex_driver::RobotEventNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_RobotEventTopic.publish(ros_msg); +} + +bool BaseRobotServices::PlayCartesianTrajectory(kortex_driver::PlayCartesianTrajectory::Request &req, kortex_driver::PlayCartesianTrajectory::Response &res) +{ + + Kinova::Api::Base::ConstrainedPose input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlayCartesianTrajectory(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PlayCartesianTrajectoryPosition(kortex_driver::PlayCartesianTrajectoryPosition::Request &req, kortex_driver::PlayCartesianTrajectoryPosition::Response &res) +{ + + Kinova::Api::Base::ConstrainedPosition input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlayCartesianTrajectoryPosition(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PlayCartesianTrajectoryOrientation(kortex_driver::PlayCartesianTrajectoryOrientation::Request &req, kortex_driver::PlayCartesianTrajectoryOrientation::Response &res) +{ + + Kinova::Api::Base::ConstrainedOrientation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlayCartesianTrajectoryOrientation(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::Stop(kortex_driver::Stop::Request &req, kortex_driver::Stop::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->Stop(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetMeasuredCartesianPose(kortex_driver::GetMeasuredCartesianPose::Request &req, kortex_driver::GetMeasuredCartesianPose::Response &res) +{ + + Kinova::Api::Base::Pose output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetMeasuredCartesianPose(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SendWrenchCommand(kortex_driver::SendWrenchCommand::Request &req, kortex_driver::SendWrenchCommand::Response &res) +{ + + Kinova::Api::Base::WrenchCommand input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendWrenchCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SendWrenchJoystickCommand(kortex_driver::SendWrenchJoystickCommand::Request &req, kortex_driver::SendWrenchJoystickCommand::Response &res) +{ + + Kinova::Api::Base::WrenchCommand input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendWrenchJoystickCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SendTwistJoystickCommand(kortex_driver::SendTwistJoystickCommand::Request &req, kortex_driver::SendTwistJoystickCommand::Response &res) +{ + + Kinova::Api::Base::TwistCommand input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendTwistJoystickCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SendTwistCommand(kortex_driver::SendTwistCommand::Request &req, kortex_driver::SendTwistCommand::Response &res) +{ + + Kinova::Api::Base::TwistCommand input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendTwistCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PlayJointTrajectory(kortex_driver::PlayJointTrajectory::Request &req, kortex_driver::PlayJointTrajectory::Response &res) +{ + + Kinova::Api::Base::ConstrainedJointAngles input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlayJointTrajectory(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::PlaySelectedJointTrajectory(kortex_driver::PlaySelectedJointTrajectory::Request &req, kortex_driver::PlaySelectedJointTrajectory::Response &res) +{ + + Kinova::Api::Base::ConstrainedJointAngle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlaySelectedJointTrajectory(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetMeasuredJointAngles(kortex_driver::GetMeasuredJointAngles::Request &req, kortex_driver::GetMeasuredJointAngles::Response &res) +{ + + Kinova::Api::Base::JointAngles output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetMeasuredJointAngles(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SendJointSpeedsCommand(kortex_driver::SendJointSpeedsCommand::Request &req, kortex_driver::SendJointSpeedsCommand::Response &res) +{ + + Kinova::Api::Base::JointSpeeds input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendJointSpeedsCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SendSelectedJointSpeedCommand(kortex_driver::SendSelectedJointSpeedCommand::Request &req, kortex_driver::SendSelectedJointSpeedCommand::Response &res) +{ + + Kinova::Api::Base::JointSpeed input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendSelectedJointSpeedCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SendGripperCommand(kortex_driver::SendGripperCommand::Request &req, kortex_driver::SendGripperCommand::Response &res) +{ + + Kinova::Api::Base::GripperCommand input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendGripperCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetMeasuredGripperMovement(kortex_driver::GetMeasuredGripperMovement::Request &req, kortex_driver::GetMeasuredGripperMovement::Response &res) +{ + + Kinova::Api::Base::GripperRequest input; + ToProtoData(req.input, &input); + Kinova::Api::Base::Gripper output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetMeasuredGripperMovement(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SetAdmittance(kortex_driver::SetAdmittance::Request &req, kortex_driver::SetAdmittance::Response &res) +{ + + Kinova::Api::Base::Admittance input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetAdmittance(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SetOperatingMode(kortex_driver::SetOperatingMode::Request &req, kortex_driver::SetOperatingMode::Response &res) +{ + + Kinova::Api::Base::OperatingModeInformation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetOperatingMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ApplyEmergencyStop(kortex_driver::ApplyEmergencyStop::Request &req, kortex_driver::ApplyEmergencyStop::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->ApplyEmergencyStop(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::Base_ClearFaults(kortex_driver::Base_ClearFaults::Request &req, kortex_driver::Base_ClearFaults::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->ClearFaults(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::Base_GetControlMode(kortex_driver::Base_GetControlMode::Request &req, kortex_driver::Base_GetControlMode::Response &res) +{ + + Kinova::Api::Base::ControlModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetControlMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetOperatingMode(kortex_driver::GetOperatingMode::Request &req, kortex_driver::GetOperatingMode::Response &res) +{ + + Kinova::Api::Base::OperatingModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetOperatingMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SetServoingMode(kortex_driver::SetServoingMode::Request &req, kortex_driver::SetServoingMode::Response &res) +{ + + Kinova::Api::Base::ServoingModeInformation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetServoingMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetServoingMode(kortex_driver::GetServoingMode::Request &req, kortex_driver::GetServoingMode::Response &res) +{ + + Kinova::Api::Base::ServoingModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetServoingMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::OnNotificationServoingModeTopic(kortex_driver::OnNotificationServoingModeTopic::Request &req, kortex_driver::OnNotificationServoingModeTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ServoingModeTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ServoingModeNotification) > callback = std::bind(&BaseRobotServices::cb_ServoingModeTopic, this, std::placeholders::_1); + output = m_base->OnNotificationServoingModeTopic(callback, input, m_current_device_id); + m_is_activated_ServoingModeTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ServoingModeTopic(Kinova::Api::Base::ServoingModeNotification notif) +{ + kortex_driver::ServoingModeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ServoingModeTopic.publish(ros_msg); +} + +bool BaseRobotServices::RestoreFactorySettings(kortex_driver::RestoreFactorySettings::Request &req, kortex_driver::RestoreFactorySettings::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->RestoreFactorySettings(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::OnNotificationFactoryTopic(kortex_driver::OnNotificationFactoryTopic::Request &req, kortex_driver::OnNotificationFactoryTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_FactoryTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::FactoryNotification) > callback = std::bind(&BaseRobotServices::cb_FactoryTopic, this, std::placeholders::_1); + output = m_base->OnNotificationFactoryTopic(callback, input, m_current_device_id); + m_is_activated_FactoryTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_FactoryTopic(Kinova::Api::Base::FactoryNotification notif) +{ + kortex_driver::FactoryNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_FactoryTopic.publish(ros_msg); +} + +bool BaseRobotServices::GetAllConnectedControllers(kortex_driver::GetAllConnectedControllers::Request &req, kortex_driver::GetAllConnectedControllers::Response &res) +{ + + Kinova::Api::Base::ControllerList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllConnectedControllers(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetControllerState(kortex_driver::GetControllerState::Request &req, kortex_driver::GetControllerState::Response &res) +{ + + Kinova::Api::Base::ControllerHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::ControllerState output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetControllerState(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetActuatorCount(kortex_driver::GetActuatorCount::Request &req, kortex_driver::GetActuatorCount::Response &res) +{ + + Kinova::Api::Base::ActuatorInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetActuatorCount(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::StartWifiScan(kortex_driver::StartWifiScan::Request &req, kortex_driver::StartWifiScan::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->StartWifiScan(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetConfiguredWifi(kortex_driver::GetConfiguredWifi::Request &req, kortex_driver::GetConfiguredWifi::Response &res) +{ + + Kinova::Api::Base::Ssid input; + ToProtoData(req.input, &input); + Kinova::Api::Base::WifiConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetConfiguredWifi(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::OnNotificationNetworkTopic(kortex_driver::OnNotificationNetworkTopic::Request &req, kortex_driver::OnNotificationNetworkTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_NetworkTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::NetworkNotification) > callback = std::bind(&BaseRobotServices::cb_NetworkTopic, this, std::placeholders::_1); + output = m_base->OnNotificationNetworkTopic(callback, input, m_current_device_id); + m_is_activated_NetworkTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_NetworkTopic(Kinova::Api::Base::NetworkNotification notif) +{ + kortex_driver::NetworkNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_NetworkTopic.publish(ros_msg); +} + +bool BaseRobotServices::GetArmState(kortex_driver::GetArmState::Request &req, kortex_driver::GetArmState::Response &res) +{ + + Kinova::Api::Base::ArmStateInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetArmState(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::OnNotificationArmStateTopic(kortex_driver::OnNotificationArmStateTopic::Request &req, kortex_driver::OnNotificationArmStateTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ArmStateTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Base::ArmStateNotification) > callback = std::bind(&BaseRobotServices::cb_ArmStateTopic, this, std::placeholders::_1); + output = m_base->OnNotificationArmStateTopic(callback, input, m_current_device_id); + m_is_activated_ArmStateTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void BaseRobotServices::cb_ArmStateTopic(Kinova::Api::Base::ArmStateNotification notif) +{ + kortex_driver::ArmStateNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ArmStateTopic.publish(ros_msg); +} + +bool BaseRobotServices::GetIPv4Information(kortex_driver::GetIPv4Information::Request &req, kortex_driver::GetIPv4Information::Response &res) +{ + + Kinova::Api::Base::NetworkHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::IPv4Information output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetIPv4Information(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SetWifiCountryCode(kortex_driver::SetWifiCountryCode::Request &req, kortex_driver::SetWifiCountryCode::Response &res) +{ + + Kinova::Api::Common::CountryCode input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetWifiCountryCode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetWifiCountryCode(kortex_driver::GetWifiCountryCode::Request &req, kortex_driver::GetWifiCountryCode::Response &res) +{ + + Kinova::Api::Common::CountryCode output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetWifiCountryCode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::Base_SetCapSenseConfig(kortex_driver::Base_SetCapSenseConfig::Request &req, kortex_driver::Base_SetCapSenseConfig::Response &res) +{ + + Kinova::Api::Base::CapSenseConfig input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetCapSenseConfig(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::Base_GetCapSenseConfig(kortex_driver::Base_GetCapSenseConfig::Request &req, kortex_driver::Base_GetCapSenseConfig::Response &res) +{ + + Kinova::Api::Base::CapSenseConfig output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetCapSenseConfig(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetAllJointsSpeedHardLimitation(kortex_driver::GetAllJointsSpeedHardLimitation::Request &req, kortex_driver::GetAllJointsSpeedHardLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_speed_hard_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::JointsLimitationsList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllJointsSpeedHardLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetAllJointsTorqueHardLimitation(kortex_driver::GetAllJointsTorqueHardLimitation::Request &req, kortex_driver::GetAllJointsTorqueHardLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_torque_hard_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::JointsLimitationsList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllJointsTorqueHardLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetTwistHardLimitation(kortex_driver::GetTwistHardLimitation::Request &req, kortex_driver::GetTwistHardLimitation::Response &res) +{ + ROS_WARN("The base/get_twist_hard_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::TwistLimitation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetTwistHardLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetWrenchHardLimitation(kortex_driver::GetWrenchHardLimitation::Request &req, kortex_driver::GetWrenchHardLimitation::Response &res) +{ + ROS_WARN("The base/get_wrench_hard_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::WrenchLimitation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetWrenchHardLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SendJointSpeedsJoystickCommand(kortex_driver::SendJointSpeedsJoystickCommand::Request &req, kortex_driver::SendJointSpeedsJoystickCommand::Response &res) +{ + + Kinova::Api::Base::JointSpeeds input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendJointSpeedsJoystickCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SendSelectedJointSpeedJoystickCommand(kortex_driver::SendSelectedJointSpeedJoystickCommand::Request &req, kortex_driver::SendSelectedJointSpeedJoystickCommand::Response &res) +{ + + Kinova::Api::Base::JointSpeed input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SendSelectedJointSpeedJoystickCommand(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::EnableBridge(kortex_driver::EnableBridge::Request &req, kortex_driver::EnableBridge::Response &res) +{ + + Kinova::Api::Base::BridgeConfig input; + ToProtoData(req.input, &input); + Kinova::Api::Base::BridgeResult output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->EnableBridge(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DisableBridge(kortex_driver::DisableBridge::Request &req, kortex_driver::DisableBridge::Response &res) +{ + + Kinova::Api::Base::BridgeIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::Base::BridgeResult output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->DisableBridge(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetBridgeList(kortex_driver::GetBridgeList::Request &req, kortex_driver::GetBridgeList::Response &res) +{ + + Kinova::Api::Base::BridgeList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetBridgeList(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetBridgeConfig(kortex_driver::GetBridgeConfig::Request &req, kortex_driver::GetBridgeConfig::Response &res) +{ + + Kinova::Api::Base::BridgeIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::Base::BridgeConfig output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetBridgeConfig(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::PlayPreComputedJointTrajectory(kortex_driver::PlayPreComputedJointTrajectory::Request &req, kortex_driver::PlayPreComputedJointTrajectory::Response &res) +{ + + Kinova::Api::Base::PreComputedJointTrajectory input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->PlayPreComputedJointTrajectory(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetProductConfiguration(kortex_driver::GetProductConfiguration::Request &req, kortex_driver::GetProductConfiguration::Response &res) +{ + + Kinova::Api::ProductConfiguration::CompleteProductConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetProductConfiguration(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateEndEffectorTypeConfiguration(kortex_driver::UpdateEndEffectorTypeConfiguration::Request &req, kortex_driver::UpdateEndEffectorTypeConfiguration::Response &res) +{ + + Kinova::Api::ProductConfiguration::ProductConfigurationEndEffectorType input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateEndEffectorTypeConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::RestoreFactoryProductConfiguration(kortex_driver::RestoreFactoryProductConfiguration::Request &req, kortex_driver::RestoreFactoryProductConfiguration::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->RestoreFactoryProductConfiguration(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetTrajectoryErrorReport(kortex_driver::GetTrajectoryErrorReport::Request &req, kortex_driver::GetTrajectoryErrorReport::Response &res) +{ + + Kinova::Api::Base::TrajectoryErrorReport output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetTrajectoryErrorReport(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetAllJointsSpeedSoftLimitation(kortex_driver::GetAllJointsSpeedSoftLimitation::Request &req, kortex_driver::GetAllJointsSpeedSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_speed_soft_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::JointsLimitationsList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllJointsSpeedSoftLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetAllJointsTorqueSoftLimitation(kortex_driver::GetAllJointsTorqueSoftLimitation::Request &req, kortex_driver::GetAllJointsTorqueSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_torque_soft_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::JointsLimitationsList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllJointsTorqueSoftLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetTwistSoftLimitation(kortex_driver::GetTwistSoftLimitation::Request &req, kortex_driver::GetTwistSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_twist_soft_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::TwistLimitation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetTwistSoftLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetWrenchSoftLimitation(kortex_driver::GetWrenchSoftLimitation::Request &req, kortex_driver::GetWrenchSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_wrench_soft_limitation service is now deprecated and will be removed in a future release."); + + Kinova::Api::Base::WrenchLimitation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetWrenchSoftLimitation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SetControllerConfigurationMode(kortex_driver::SetControllerConfigurationMode::Request &req, kortex_driver::SetControllerConfigurationMode::Response &res) +{ + + Kinova::Api::Base::ControllerConfigurationMode input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetControllerConfigurationMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetControllerConfigurationMode(kortex_driver::GetControllerConfigurationMode::Request &req, kortex_driver::GetControllerConfigurationMode::Response &res) +{ + + Kinova::Api::Base::ControllerConfigurationMode output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetControllerConfigurationMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::StartTeaching(kortex_driver::StartTeaching::Request &req, kortex_driver::StartTeaching::Response &res) +{ + + Kinova::Api::Base::SequenceTaskHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->StartTeaching(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::StopTeaching(kortex_driver::StopTeaching::Request &req, kortex_driver::StopTeaching::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_base->StopTeaching(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::AddSequenceTasks(kortex_driver::AddSequenceTasks::Request &req, kortex_driver::AddSequenceTasks::Response &res) +{ + + Kinova::Api::Base::SequenceTasksConfiguration input; + ToProtoData(req.input, &input); + Kinova::Api::Base::SequenceTasksRange output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->AddSequenceTasks(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::UpdateSequenceTask(kortex_driver::UpdateSequenceTask::Request &req, kortex_driver::UpdateSequenceTask::Response &res) +{ + + Kinova::Api::Base::SequenceTaskConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->UpdateSequenceTask(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::SwapSequenceTasks(kortex_driver::SwapSequenceTasks::Request &req, kortex_driver::SwapSequenceTasks::Response &res) +{ + + Kinova::Api::Base::SequenceTasksPair input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SwapSequenceTasks(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::ReadSequenceTask(kortex_driver::ReadSequenceTask::Request &req, kortex_driver::ReadSequenceTask::Response &res) +{ + + Kinova::Api::Base::SequenceTaskHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::SequenceTask output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadSequenceTask(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::ReadAllSequenceTasks(kortex_driver::ReadAllSequenceTasks::Request &req, kortex_driver::ReadAllSequenceTasks::Response &res) +{ + + Kinova::Api::Base::SequenceHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::SequenceTasks output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->ReadAllSequenceTasks(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DeleteSequenceTask(kortex_driver::DeleteSequenceTask::Request &req, kortex_driver::DeleteSequenceTask::Response &res) +{ + + Kinova::Api::Base::SequenceTaskHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteSequenceTask(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::DeleteAllSequenceTasks(kortex_driver::DeleteAllSequenceTasks::Request &req, kortex_driver::DeleteAllSequenceTasks::Response &res) +{ + + Kinova::Api::Base::SequenceHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->DeleteAllSequenceTasks(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::TakeSnapshot(kortex_driver::TakeSnapshot::Request &req, kortex_driver::TakeSnapshot::Response &res) +{ + + Kinova::Api::Base::Snapshot input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->TakeSnapshot(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetFirmwareBundleVersions(kortex_driver::GetFirmwareBundleVersions::Request &req, kortex_driver::GetFirmwareBundleVersions::Response &res) +{ + + Kinova::Api::Base::FirmwareBundleVersions output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetFirmwareBundleVersions(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::MoveSequenceTask(kortex_driver::MoveSequenceTask::Request &req, kortex_driver::MoveSequenceTask::Response &res) +{ + + Kinova::Api::Base::SequenceTasksPair input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->MoveSequenceTask(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::DuplicateMapping(kortex_driver::DuplicateMapping::Request &req, kortex_driver::DuplicateMapping::Response &res) +{ + + Kinova::Api::Base::MappingHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::MappingHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->DuplicateMapping(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::DuplicateMap(kortex_driver::DuplicateMap::Request &req, kortex_driver::DuplicateMap::Response &res) +{ + + Kinova::Api::Base::MapHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::MapHandle output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->DuplicateMap(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::SetControllerConfiguration(kortex_driver::SetControllerConfiguration::Request &req, kortex_driver::SetControllerConfiguration::Response &res) +{ + + Kinova::Api::Base::ControllerConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_base->SetControllerConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool BaseRobotServices::GetControllerConfiguration(kortex_driver::GetControllerConfiguration::Request &req, kortex_driver::GetControllerConfiguration::Response &res) +{ + + Kinova::Api::Base::ControllerHandle input; + ToProtoData(req.input, &input); + Kinova::Api::Base::ControllerConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetControllerConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool BaseRobotServices::GetAllControllerConfigurations(kortex_driver::GetAllControllerConfigurations::Request &req, kortex_driver::GetAllControllerConfigurations::Response &res) +{ + + Kinova::Api::Base::ControllerConfigurationList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_base->GetAllControllerConfigurations(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/basecyclic_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/basecyclic_proto_converter.cpp new file mode 100644 index 0000000..30f9bc4 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/basecyclic_proto_converter.cpp @@ -0,0 +1,167 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" + +int ToProtoData(kortex_driver::ActuatorCommand input, Kinova::Api::BaseCyclic::ActuatorCommand *output) +{ + + output->set_command_id(input.command_id); + output->set_flags(input.flags); + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_torque_joint(input.torque_joint); + output->set_current_motor(input.current_motor); + + return 0; +} +int ToProtoData(kortex_driver::ActuatorFeedback input, Kinova::Api::BaseCyclic::ActuatorFeedback *output) +{ + + output->set_command_id(input.command_id); + output->set_status_flags(input.status_flags); + output->set_jitter_comm(input.jitter_comm); + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_torque(input.torque); + output->set_current_motor(input.current_motor); + output->set_voltage(input.voltage); + output->set_temperature_motor(input.temperature_motor); + output->set_temperature_core(input.temperature_core); + output->set_fault_bank_a(input.fault_bank_a); + output->set_fault_bank_b(input.fault_bank_b); + output->set_warning_bank_a(input.warning_bank_a); + output->set_warning_bank_b(input.warning_bank_b); + + return 0; +} +int ToProtoData(kortex_driver::ActuatorCustomData input, Kinova::Api::BaseCyclic::ActuatorCustomData *output) +{ + + output->set_command_id(input.command_id); + output->set_custom_data_0(input.custom_data_0); + output->set_custom_data_1(input.custom_data_1); + output->set_custom_data_2(input.custom_data_2); + output->set_custom_data_3(input.custom_data_3); + output->set_custom_data_4(input.custom_data_4); + output->set_custom_data_5(input.custom_data_5); + output->set_custom_data_6(input.custom_data_6); + output->set_custom_data_7(input.custom_data_7); + output->set_custom_data_8(input.custom_data_8); + output->set_custom_data_9(input.custom_data_9); + output->set_custom_data_10(input.custom_data_10); + output->set_custom_data_11(input.custom_data_11); + output->set_custom_data_12(input.custom_data_12); + output->set_custom_data_13(input.custom_data_13); + output->set_custom_data_14(input.custom_data_14); + output->set_custom_data_15(input.custom_data_15); + + return 0; +} +int ToProtoData(kortex_driver::BaseFeedback input, Kinova::Api::BaseCyclic::BaseFeedback *output) +{ + + output->set_active_state_connection_identifier(input.active_state_connection_identifier); + output->set_active_state((Kinova::Api::Common::ArmState)input.active_state); + output->set_arm_voltage(input.arm_voltage); + output->set_arm_current(input.arm_current); + output->set_temperature_cpu(input.temperature_cpu); + output->set_temperature_ambient(input.temperature_ambient); + output->set_imu_acceleration_x(input.imu_acceleration_x); + output->set_imu_acceleration_y(input.imu_acceleration_y); + output->set_imu_acceleration_z(input.imu_acceleration_z); + output->set_imu_angular_velocity_x(input.imu_angular_velocity_x); + output->set_imu_angular_velocity_y(input.imu_angular_velocity_y); + output->set_imu_angular_velocity_z(input.imu_angular_velocity_z); + output->set_tool_pose_x(input.tool_pose_x); + output->set_tool_pose_y(input.tool_pose_y); + output->set_tool_pose_z(input.tool_pose_z); + output->set_tool_pose_theta_x(input.tool_pose_theta_x); + output->set_tool_pose_theta_y(input.tool_pose_theta_y); + output->set_tool_pose_theta_z(input.tool_pose_theta_z); + output->set_tool_twist_linear_x(input.tool_twist_linear_x); + output->set_tool_twist_linear_y(input.tool_twist_linear_y); + output->set_tool_twist_linear_z(input.tool_twist_linear_z); + output->set_tool_twist_angular_x(input.tool_twist_angular_x); + output->set_tool_twist_angular_y(input.tool_twist_angular_y); + output->set_tool_twist_angular_z(input.tool_twist_angular_z); + output->set_tool_external_wrench_force_x(input.tool_external_wrench_force_x); + output->set_tool_external_wrench_force_y(input.tool_external_wrench_force_y); + output->set_tool_external_wrench_force_z(input.tool_external_wrench_force_z); + output->set_tool_external_wrench_torque_x(input.tool_external_wrench_torque_x); + output->set_tool_external_wrench_torque_y(input.tool_external_wrench_torque_y); + output->set_tool_external_wrench_torque_z(input.tool_external_wrench_torque_z); + output->set_fault_bank_a(input.fault_bank_a); + output->set_fault_bank_b(input.fault_bank_b); + output->set_warning_bank_a(input.warning_bank_a); + output->set_warning_bank_b(input.warning_bank_b); + output->set_commanded_tool_pose_x(input.commanded_tool_pose_x); + output->set_commanded_tool_pose_y(input.commanded_tool_pose_y); + output->set_commanded_tool_pose_z(input.commanded_tool_pose_z); + output->set_commanded_tool_pose_theta_x(input.commanded_tool_pose_theta_x); + output->set_commanded_tool_pose_theta_y(input.commanded_tool_pose_theta_y); + output->set_commanded_tool_pose_theta_z(input.commanded_tool_pose_theta_z); + + return 0; +} +int ToProtoData(kortex_driver::BaseCyclic_CustomData input, Kinova::Api::BaseCyclic::CustomData *output) +{ + + output->set_frame_id(input.frame_id); + output->set_custom_data_0(input.custom_data_0); + output->set_custom_data_1(input.custom_data_1); + output->set_custom_data_2(input.custom_data_2); + output->set_custom_data_3(input.custom_data_3); + output->set_custom_data_4(input.custom_data_4); + output->set_custom_data_5(input.custom_data_5); + output->set_custom_data_6(input.custom_data_6); + output->set_custom_data_7(input.custom_data_7); + output->clear_actuators_custom_data(); + for(int i = 0; i < input.actuators_custom_data.size(); i++) + { + ToProtoData(input.actuators_custom_data[i], output->add_actuators_custom_data()); + } + ToProtoData(input.interconnect_custom_data, output->mutable_interconnect_custom_data()); + + return 0; +} +int ToProtoData(kortex_driver::BaseCyclic_Command input, Kinova::Api::BaseCyclic::Command *output) +{ + + output->set_frame_id(input.frame_id); + output->clear_actuators(); + for(int i = 0; i < input.actuators.size(); i++) + { + ToProtoData(input.actuators[i], output->add_actuators()); + } + ToProtoData(input.interconnect, output->mutable_interconnect()); + + return 0; +} +int ToProtoData(kortex_driver::BaseCyclic_Feedback input, Kinova::Api::BaseCyclic::Feedback *output) +{ + + output->set_frame_id(input.frame_id); + ToProtoData(input.base, output->mutable_base()); + output->clear_actuators(); + for(int i = 0; i < input.actuators.size(); i++) + { + ToProtoData(input.actuators[i], output->add_actuators()); + } + ToProtoData(input.interconnect, output->mutable_interconnect()); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/basecyclic_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/basecyclic_ros_converter.cpp new file mode 100644 index 0000000..e064758 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/basecyclic_ros_converter.cpp @@ -0,0 +1,187 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" + +int ToRosData(Kinova::Api::BaseCyclic::ActuatorCommand input, kortex_driver::ActuatorCommand &output) +{ + + output.command_id = input.command_id(); + output.flags = input.flags(); + output.position = input.position(); + output.velocity = input.velocity(); + output.torque_joint = input.torque_joint(); + output.current_motor = input.current_motor(); + + + + return 0; +} +int ToRosData(Kinova::Api::BaseCyclic::ActuatorFeedback input, kortex_driver::ActuatorFeedback &output) +{ + + output.command_id = input.command_id(); + output.status_flags = input.status_flags(); + output.jitter_comm = input.jitter_comm(); + output.position = input.position(); + output.velocity = input.velocity(); + output.torque = input.torque(); + output.current_motor = input.current_motor(); + output.voltage = input.voltage(); + output.temperature_motor = input.temperature_motor(); + output.temperature_core = input.temperature_core(); + output.fault_bank_a = input.fault_bank_a(); + output.fault_bank_b = input.fault_bank_b(); + output.warning_bank_a = input.warning_bank_a(); + output.warning_bank_b = input.warning_bank_b(); + + + + return 0; +} +int ToRosData(Kinova::Api::BaseCyclic::ActuatorCustomData input, kortex_driver::ActuatorCustomData &output) +{ + + output.command_id = input.command_id(); + output.custom_data_0 = input.custom_data_0(); + output.custom_data_1 = input.custom_data_1(); + output.custom_data_2 = input.custom_data_2(); + output.custom_data_3 = input.custom_data_3(); + output.custom_data_4 = input.custom_data_4(); + output.custom_data_5 = input.custom_data_5(); + output.custom_data_6 = input.custom_data_6(); + output.custom_data_7 = input.custom_data_7(); + output.custom_data_8 = input.custom_data_8(); + output.custom_data_9 = input.custom_data_9(); + output.custom_data_10 = input.custom_data_10(); + output.custom_data_11 = input.custom_data_11(); + output.custom_data_12 = input.custom_data_12(); + output.custom_data_13 = input.custom_data_13(); + output.custom_data_14 = input.custom_data_14(); + output.custom_data_15 = input.custom_data_15(); + + + + return 0; +} +int ToRosData(Kinova::Api::BaseCyclic::BaseFeedback input, kortex_driver::BaseFeedback &output) +{ + + output.active_state_connection_identifier = input.active_state_connection_identifier(); + output.active_state = input.active_state(); + output.arm_voltage = input.arm_voltage(); + output.arm_current = input.arm_current(); + output.temperature_cpu = input.temperature_cpu(); + output.temperature_ambient = input.temperature_ambient(); + output.imu_acceleration_x = input.imu_acceleration_x(); + output.imu_acceleration_y = input.imu_acceleration_y(); + output.imu_acceleration_z = input.imu_acceleration_z(); + output.imu_angular_velocity_x = input.imu_angular_velocity_x(); + output.imu_angular_velocity_y = input.imu_angular_velocity_y(); + output.imu_angular_velocity_z = input.imu_angular_velocity_z(); + output.tool_pose_x = input.tool_pose_x(); + output.tool_pose_y = input.tool_pose_y(); + output.tool_pose_z = input.tool_pose_z(); + output.tool_pose_theta_x = input.tool_pose_theta_x(); + output.tool_pose_theta_y = input.tool_pose_theta_y(); + output.tool_pose_theta_z = input.tool_pose_theta_z(); + output.tool_twist_linear_x = input.tool_twist_linear_x(); + output.tool_twist_linear_y = input.tool_twist_linear_y(); + output.tool_twist_linear_z = input.tool_twist_linear_z(); + output.tool_twist_angular_x = input.tool_twist_angular_x(); + output.tool_twist_angular_y = input.tool_twist_angular_y(); + output.tool_twist_angular_z = input.tool_twist_angular_z(); + output.tool_external_wrench_force_x = input.tool_external_wrench_force_x(); + output.tool_external_wrench_force_y = input.tool_external_wrench_force_y(); + output.tool_external_wrench_force_z = input.tool_external_wrench_force_z(); + output.tool_external_wrench_torque_x = input.tool_external_wrench_torque_x(); + output.tool_external_wrench_torque_y = input.tool_external_wrench_torque_y(); + output.tool_external_wrench_torque_z = input.tool_external_wrench_torque_z(); + output.fault_bank_a = input.fault_bank_a(); + output.fault_bank_b = input.fault_bank_b(); + output.warning_bank_a = input.warning_bank_a(); + output.warning_bank_b = input.warning_bank_b(); + output.commanded_tool_pose_x = input.commanded_tool_pose_x(); + output.commanded_tool_pose_y = input.commanded_tool_pose_y(); + output.commanded_tool_pose_z = input.commanded_tool_pose_z(); + output.commanded_tool_pose_theta_x = input.commanded_tool_pose_theta_x(); + output.commanded_tool_pose_theta_y = input.commanded_tool_pose_theta_y(); + output.commanded_tool_pose_theta_z = input.commanded_tool_pose_theta_z(); + + + + return 0; +} +int ToRosData(Kinova::Api::BaseCyclic::CustomData input, kortex_driver::BaseCyclic_CustomData &output) +{ + + output.frame_id = input.frame_id(); + output.custom_data_0 = input.custom_data_0(); + output.custom_data_1 = input.custom_data_1(); + output.custom_data_2 = input.custom_data_2(); + output.custom_data_3 = input.custom_data_3(); + output.custom_data_4 = input.custom_data_4(); + output.custom_data_5 = input.custom_data_5(); + output.custom_data_6 = input.custom_data_6(); + output.custom_data_7 = input.custom_data_7(); + output.actuators_custom_data.clear(); + for(int i = 0; i < input.actuators_custom_data_size(); i++) + { + kortex_driver::ActuatorCustomData temp; + ToRosData(input.actuators_custom_data(i), temp); + output.actuators_custom_data.push_back(temp); + } + ToRosData(input.interconnect_custom_data(), output.interconnect_custom_data); + + + + return 0; +} +int ToRosData(Kinova::Api::BaseCyclic::Command input, kortex_driver::BaseCyclic_Command &output) +{ + + output.frame_id = input.frame_id(); + output.actuators.clear(); + for(int i = 0; i < input.actuators_size(); i++) + { + kortex_driver::ActuatorCommand temp; + ToRosData(input.actuators(i), temp); + output.actuators.push_back(temp); + } + ToRosData(input.interconnect(), output.interconnect); + + + + return 0; +} +int ToRosData(Kinova::Api::BaseCyclic::Feedback input, kortex_driver::BaseCyclic_Feedback &output) +{ + + output.frame_id = input.frame_id(); + ToRosData(input.base(), output.base); + output.actuators.clear(); + for(int i = 0; i < input.actuators_size(); i++) + { + kortex_driver::ActuatorFeedback temp; + ToRosData(input.actuators(i), temp); + output.actuators.push_back(temp); + } + ToRosData(input.interconnect(), output.interconnect); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/common_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/common_proto_converter.cpp new file mode 100644 index 0000000..d135787 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/common_proto_converter.cpp @@ -0,0 +1,118 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" + +int ToProtoData(kortex_driver::DeviceHandle input, Kinova::Api::Common::DeviceHandle *output) +{ + + output->set_device_type((Kinova::Api::Common::DeviceTypes)input.device_type); + output->set_device_identifier(input.device_identifier); + output->set_order(input.order); + + return 0; +} +int ToProtoData(kortex_driver::Empty input, Kinova::Api::Common::Empty *output) +{ + + + return 0; +} +int ToProtoData(kortex_driver::NotificationOptions input, Kinova::Api::Common::NotificationOptions *output) +{ + + output->set_type((Kinova::Api::Common::NotificationType)input.type); + output->set_rate_m_sec(input.rate_m_sec); + output->set_threshold_value(input.threshold_value); + + return 0; +} +int ToProtoData(kortex_driver::SafetyHandle input, Kinova::Api::Common::SafetyHandle *output) +{ + + output->set_identifier(input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::NotificationHandle input, Kinova::Api::Common::NotificationHandle *output) +{ + + output->set_identifier(input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::SafetyNotification input, Kinova::Api::Common::SafetyNotification *output) +{ + + ToProtoData(input.safety_handle, output->mutable_safety_handle()); + output->set_value((Kinova::Api::Common::SafetyStatusValue)input.value); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::Timestamp input, Kinova::Api::Common::Timestamp *output) +{ + + output->set_sec(input.sec); + output->set_usec(input.usec); + + return 0; +} +int ToProtoData(kortex_driver::UserProfileHandle input, Kinova::Api::Common::UserProfileHandle *output) +{ + + output->set_identifier(input.identifier); + output->set_permission(input.permission); + + return 0; +} +int ToProtoData(kortex_driver::Connection input, Kinova::Api::Common::Connection *output) +{ + + ToProtoData(input.user_handle, output->mutable_user_handle()); + output->set_connection_information(input.connection_information); + output->set_connection_identifier(input.connection_identifier); + + return 0; +} +int ToProtoData(kortex_driver::UARTConfiguration input, Kinova::Api::Common::UARTConfiguration *output) +{ + + output->set_port_id(input.port_id); + output->set_enabled(input.enabled); + output->set_speed((Kinova::Api::Common::UARTSpeed)input.speed); + output->set_word_length((Kinova::Api::Common::UARTWordLength)input.word_length); + output->set_stop_bits((Kinova::Api::Common::UARTStopBits)input.stop_bits); + output->set_parity((Kinova::Api::Common::UARTParity)input.parity); + + return 0; +} +int ToProtoData(kortex_driver::UARTDeviceIdentification input, Kinova::Api::Common::UARTDeviceIdentification *output) +{ + + output->set_port_id(input.port_id); + + return 0; +} +int ToProtoData(kortex_driver::CountryCode input, Kinova::Api::Common::CountryCode *output) +{ + + output->set_identifier((Kinova::Api::Common::CountryCodeIdentifier)input.identifier); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/common_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/common_ros_converter.cpp new file mode 100644 index 0000000..df98ecb --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/common_ros_converter.cpp @@ -0,0 +1,142 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_ros_converter.h" + +int ToRosData(Kinova::Api::Common::DeviceHandle input, kortex_driver::DeviceHandle &output) +{ + + output.device_type = input.device_type(); + output.device_identifier = input.device_identifier(); + output.order = input.order(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::Empty input, kortex_driver::Empty &output) +{ + + + + + return 0; +} +int ToRosData(Kinova::Api::Common::NotificationOptions input, kortex_driver::NotificationOptions &output) +{ + + output.type = input.type(); + output.rate_m_sec = input.rate_m_sec(); + output.threshold_value = input.threshold_value(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::SafetyHandle input, kortex_driver::SafetyHandle &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::NotificationHandle input, kortex_driver::NotificationHandle &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::SafetyNotification input, kortex_driver::SafetyNotification &output) +{ + + ToRosData(input.safety_handle(), output.safety_handle); + output.value = input.value(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::Timestamp input, kortex_driver::Timestamp &output) +{ + + output.sec = input.sec(); + output.usec = input.usec(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::UserProfileHandle input, kortex_driver::UserProfileHandle &output) +{ + + output.identifier = input.identifier(); + output.permission = input.permission(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::Connection input, kortex_driver::Connection &output) +{ + + ToRosData(input.user_handle(), output.user_handle); + output.connection_information = input.connection_information(); + output.connection_identifier = input.connection_identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::UARTConfiguration input, kortex_driver::UARTConfiguration &output) +{ + + output.port_id = input.port_id(); + output.enabled = input.enabled(); + output.speed = input.speed(); + output.word_length = input.word_length(); + output.stop_bits = input.stop_bits(); + output.parity = input.parity(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::UARTDeviceIdentification input, kortex_driver::UARTDeviceIdentification &output) +{ + + output.port_id = input.port_id(); + + + + return 0; +} +int ToRosData(Kinova::Api::Common::CountryCode input, kortex_driver::CountryCode &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/controlconfig_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/controlconfig_proto_converter.cpp new file mode 100644 index 0000000..844f103 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/controlconfig_proto_converter.cpp @@ -0,0 +1,197 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" + +int ToProtoData(kortex_driver::GravityVector input, Kinova::Api::ControlConfig::GravityVector *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + output->set_z(input.z); + + return 0; +} +int ToProtoData(kortex_driver::ControlConfig_Position input, Kinova::Api::ControlConfig::Position *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + output->set_z(input.z); + + return 0; +} +int ToProtoData(kortex_driver::PayloadInformation input, Kinova::Api::ControlConfig::PayloadInformation *output) +{ + + output->set_payload_mass(input.payload_mass); + ToProtoData(input.payload_mass_center, output->mutable_payload_mass_center()); + + return 0; +} +int ToProtoData(kortex_driver::CartesianTransform input, Kinova::Api::ControlConfig::CartesianTransform *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + output->set_z(input.z); + output->set_theta_x(input.theta_x); + output->set_theta_y(input.theta_y); + output->set_theta_z(input.theta_z); + + return 0; +} +int ToProtoData(kortex_driver::ToolConfiguration input, Kinova::Api::ControlConfig::ToolConfiguration *output) +{ + + ToProtoData(input.tool_transform, output->mutable_tool_transform()); + output->set_tool_mass(input.tool_mass); + ToProtoData(input.tool_mass_center, output->mutable_tool_mass_center()); + + return 0; +} +int ToProtoData(kortex_driver::ControlConfigurationNotification input, Kinova::Api::ControlConfig::ControlConfigurationNotification *output) +{ + + output->set_event((Kinova::Api::ControlConfig::ControlConfigurationEvent)input.event); + ToProtoData(input.timestamp, output->mutable_timestamp()); + ToProtoData(input.user_handle, output->mutable_user_handle()); + ToProtoData(input.connection, output->mutable_connection()); + + return 0; +} +int ToProtoData(kortex_driver::CartesianReferenceFrameInfo input, Kinova::Api::ControlConfig::CartesianReferenceFrameInfo *output) +{ + + output->set_reference_frame((Kinova::Api::Common::CartesianReferenceFrame)input.reference_frame); + + return 0; +} +int ToProtoData(kortex_driver::TwistLinearSoftLimit input, Kinova::Api::ControlConfig::TwistLinearSoftLimit *output) +{ + + output->set_control_mode((Kinova::Api::ControlConfig::ControlMode)input.control_mode); + output->set_twist_linear_soft_limit(input.twist_linear_soft_limit); + + return 0; +} +int ToProtoData(kortex_driver::TwistAngularSoftLimit input, Kinova::Api::ControlConfig::TwistAngularSoftLimit *output) +{ + + output->set_control_mode((Kinova::Api::ControlConfig::ControlMode)input.control_mode); + output->set_twist_angular_soft_limit(input.twist_angular_soft_limit); + + return 0; +} +int ToProtoData(kortex_driver::JointSpeedSoftLimits input, Kinova::Api::ControlConfig::JointSpeedSoftLimits *output) +{ + + output->set_control_mode((Kinova::Api::ControlConfig::ControlMode)input.control_mode); + output->clear_joint_speed_soft_limits(); + for(int i = 0; i < input.joint_speed_soft_limits.size(); i++) + { + output->add_joint_speed_soft_limits(input.joint_speed_soft_limits[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::JointAccelerationSoftLimits input, Kinova::Api::ControlConfig::JointAccelerationSoftLimits *output) +{ + + output->set_control_mode((Kinova::Api::ControlConfig::ControlMode)input.control_mode); + output->clear_joint_acceleration_soft_limits(); + for(int i = 0; i < input.joint_acceleration_soft_limits.size(); i++) + { + output->add_joint_acceleration_soft_limits(input.joint_acceleration_soft_limits[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::KinematicLimits input, Kinova::Api::ControlConfig::KinematicLimits *output) +{ + + output->set_control_mode((Kinova::Api::ControlConfig::ControlMode)input.control_mode); + output->set_twist_linear(input.twist_linear); + output->set_twist_angular(input.twist_angular); + output->clear_joint_speed_limits(); + for(int i = 0; i < input.joint_speed_limits.size(); i++) + { + output->add_joint_speed_limits(input.joint_speed_limits[i]); + } + output->clear_joint_acceleration_limits(); + for(int i = 0; i < input.joint_acceleration_limits.size(); i++) + { + output->add_joint_acceleration_limits(input.joint_acceleration_limits[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::KinematicLimitsList input, Kinova::Api::ControlConfig::KinematicLimitsList *output) +{ + + output->clear_kinematic_limits_list(); + for(int i = 0; i < input.kinematic_limits_list.size(); i++) + { + ToProtoData(input.kinematic_limits_list[i], output->add_kinematic_limits_list()); + } + + return 0; +} +int ToProtoData(kortex_driver::DesiredSpeeds input, Kinova::Api::ControlConfig::DesiredSpeeds *output) +{ + + output->set_linear(input.linear); + output->set_angular(input.angular); + output->clear_joint_speed(); + for(int i = 0; i < input.joint_speed.size(); i++) + { + output->add_joint_speed(input.joint_speed[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::LinearTwist input, Kinova::Api::ControlConfig::LinearTwist *output) +{ + + output->set_linear(input.linear); + + return 0; +} +int ToProtoData(kortex_driver::AngularTwist input, Kinova::Api::ControlConfig::AngularTwist *output) +{ + + output->set_angular(input.angular); + + return 0; +} +int ToProtoData(kortex_driver::ControlConfig_JointSpeeds input, Kinova::Api::ControlConfig::JointSpeeds *output) +{ + + output->clear_joint_speed(); + for(int i = 0; i < input.joint_speed.size(); i++) + { + output->add_joint_speed(input.joint_speed[i]); + } + + return 0; +} +int ToProtoData(kortex_driver::ControlConfig_ControlModeInformation input, Kinova::Api::ControlConfig::ControlModeInformation *output) +{ + + output->set_control_mode((Kinova::Api::ControlConfig::ControlMode)input.control_mode); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/controlconfig_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/controlconfig_ros_converter.cpp new file mode 100644 index 0000000..5032d46 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/controlconfig_ros_converter.cpp @@ -0,0 +1,235 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" + +int ToRosData(Kinova::Api::ControlConfig::GravityVector input, kortex_driver::GravityVector &output) +{ + + output.x = input.x(); + output.y = input.y(); + output.z = input.z(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::Position input, kortex_driver::ControlConfig_Position &output) +{ + + output.x = input.x(); + output.y = input.y(); + output.z = input.z(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::PayloadInformation input, kortex_driver::PayloadInformation &output) +{ + + output.payload_mass = input.payload_mass(); + ToRosData(input.payload_mass_center(), output.payload_mass_center); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::CartesianTransform input, kortex_driver::CartesianTransform &output) +{ + + output.x = input.x(); + output.y = input.y(); + output.z = input.z(); + output.theta_x = input.theta_x(); + output.theta_y = input.theta_y(); + output.theta_z = input.theta_z(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::ToolConfiguration input, kortex_driver::ToolConfiguration &output) +{ + + ToRosData(input.tool_transform(), output.tool_transform); + output.tool_mass = input.tool_mass(); + ToRosData(input.tool_mass_center(), output.tool_mass_center); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::ControlConfigurationNotification input, kortex_driver::ControlConfigurationNotification &output) +{ + + output.event = input.event(); + ToRosData(input.timestamp(), output.timestamp); + ToRosData(input.user_handle(), output.user_handle); + ToRosData(input.connection(), output.connection); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::CartesianReferenceFrameInfo input, kortex_driver::CartesianReferenceFrameInfo &output) +{ + + output.reference_frame = input.reference_frame(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::TwistLinearSoftLimit input, kortex_driver::TwistLinearSoftLimit &output) +{ + + output.control_mode = input.control_mode(); + output.twist_linear_soft_limit = input.twist_linear_soft_limit(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::TwistAngularSoftLimit input, kortex_driver::TwistAngularSoftLimit &output) +{ + + output.control_mode = input.control_mode(); + output.twist_angular_soft_limit = input.twist_angular_soft_limit(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::JointSpeedSoftLimits input, kortex_driver::JointSpeedSoftLimits &output) +{ + + output.control_mode = input.control_mode(); + output.joint_speed_soft_limits.clear(); + for(int i = 0; i < input.joint_speed_soft_limits_size(); i++) + { + output.joint_speed_soft_limits.push_back(input.joint_speed_soft_limits(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::JointAccelerationSoftLimits input, kortex_driver::JointAccelerationSoftLimits &output) +{ + + output.control_mode = input.control_mode(); + output.joint_acceleration_soft_limits.clear(); + for(int i = 0; i < input.joint_acceleration_soft_limits_size(); i++) + { + output.joint_acceleration_soft_limits.push_back(input.joint_acceleration_soft_limits(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::KinematicLimits input, kortex_driver::KinematicLimits &output) +{ + + output.control_mode = input.control_mode(); + output.twist_linear = input.twist_linear(); + output.twist_angular = input.twist_angular(); + output.joint_speed_limits.clear(); + for(int i = 0; i < input.joint_speed_limits_size(); i++) + { + output.joint_speed_limits.push_back(input.joint_speed_limits(i)); + } + output.joint_acceleration_limits.clear(); + for(int i = 0; i < input.joint_acceleration_limits_size(); i++) + { + output.joint_acceleration_limits.push_back(input.joint_acceleration_limits(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::KinematicLimitsList input, kortex_driver::KinematicLimitsList &output) +{ + + output.kinematic_limits_list.clear(); + for(int i = 0; i < input.kinematic_limits_list_size(); i++) + { + kortex_driver::KinematicLimits temp; + ToRosData(input.kinematic_limits_list(i), temp); + output.kinematic_limits_list.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::DesiredSpeeds input, kortex_driver::DesiredSpeeds &output) +{ + + output.linear = input.linear(); + output.angular = input.angular(); + output.joint_speed.clear(); + for(int i = 0; i < input.joint_speed_size(); i++) + { + output.joint_speed.push_back(input.joint_speed(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::LinearTwist input, kortex_driver::LinearTwist &output) +{ + + output.linear = input.linear(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::AngularTwist input, kortex_driver::AngularTwist &output) +{ + + output.angular = input.angular(); + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::JointSpeeds input, kortex_driver::ControlConfig_JointSpeeds &output) +{ + + output.joint_speed.clear(); + for(int i = 0; i < input.joint_speed_size(); i++) + { + output.joint_speed.push_back(input.joint_speed(i)); + } + + + + return 0; +} +int ToRosData(Kinova::Api::ControlConfig::ControlModeInformation input, kortex_driver::ControlConfig_ControlModeInformation &output) +{ + + output.control_mode = input.control_mode(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/controlconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/controlconfig_services.cpp new file mode 100644 index 0000000..0e75bf8 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/controlconfig_services.cpp @@ -0,0 +1,1071 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_services.h" + +ControlConfigRobotServices::ControlConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::ControlConfig::ControlConfigClient* controlconfig, uint32_t device_id, uint32_t timeout_ms): + IControlConfigServices(node_handle), + m_controlconfig(controlconfig), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_ControlConfigurationTopic = m_node_handle.advertise("control_configuration_topic", 1000); + m_is_activated_ControlConfigurationTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("control_config/set_device_id", &ControlConfigRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("control_config/set_api_options", &ControlConfigRobotServices::SetApiOptions, this); + + m_serviceSetGravityVector = m_node_handle.advertiseService("control_config/set_gravity_vector", &ControlConfigRobotServices::SetGravityVector, this); + m_serviceGetGravityVector = m_node_handle.advertiseService("control_config/get_gravity_vector", &ControlConfigRobotServices::GetGravityVector, this); + m_serviceSetPayloadInformation = m_node_handle.advertiseService("control_config/set_payload_information", &ControlConfigRobotServices::SetPayloadInformation, this); + m_serviceGetPayloadInformation = m_node_handle.advertiseService("control_config/get_payload_information", &ControlConfigRobotServices::GetPayloadInformation, this); + m_serviceSetToolConfiguration = m_node_handle.advertiseService("control_config/set_tool_configuration", &ControlConfigRobotServices::SetToolConfiguration, this); + m_serviceGetToolConfiguration = m_node_handle.advertiseService("control_config/get_tool_configuration", &ControlConfigRobotServices::GetToolConfiguration, this); + m_serviceOnNotificationControlConfigurationTopic = m_node_handle.advertiseService("control_config/activate_publishing_of_control_configuration_topic", &ControlConfigRobotServices::OnNotificationControlConfigurationTopic, this); + m_serviceControlConfig_Unsubscribe = m_node_handle.advertiseService("control_config/unsubscribe", &ControlConfigRobotServices::ControlConfig_Unsubscribe, this); + m_serviceSetCartesianReferenceFrame = m_node_handle.advertiseService("control_config/set_cartesian_reference_frame", &ControlConfigRobotServices::SetCartesianReferenceFrame, this); + m_serviceGetCartesianReferenceFrame = m_node_handle.advertiseService("control_config/get_cartesian_reference_frame", &ControlConfigRobotServices::GetCartesianReferenceFrame, this); + m_serviceControlConfig_GetControlMode = m_node_handle.advertiseService("control_config/get_control_mode", &ControlConfigRobotServices::ControlConfig_GetControlMode, this); + m_serviceSetJointSpeedSoftLimits = m_node_handle.advertiseService("control_config/set_joint_speed_soft_limits", &ControlConfigRobotServices::SetJointSpeedSoftLimits, this); + m_serviceSetTwistLinearSoftLimit = m_node_handle.advertiseService("control_config/set_twist_linear_soft_limit", &ControlConfigRobotServices::SetTwistLinearSoftLimit, this); + m_serviceSetTwistAngularSoftLimit = m_node_handle.advertiseService("control_config/set_twist_angular_soft_limit", &ControlConfigRobotServices::SetTwistAngularSoftLimit, this); + m_serviceSetJointAccelerationSoftLimits = m_node_handle.advertiseService("control_config/set_joint_acceleration_soft_limits", &ControlConfigRobotServices::SetJointAccelerationSoftLimits, this); + m_serviceGetKinematicHardLimits = m_node_handle.advertiseService("control_config/get_kinematic_hard_limits", &ControlConfigRobotServices::GetKinematicHardLimits, this); + m_serviceGetKinematicSoftLimits = m_node_handle.advertiseService("control_config/get_kinematic_soft_limits", &ControlConfigRobotServices::GetKinematicSoftLimits, this); + m_serviceGetAllKinematicSoftLimits = m_node_handle.advertiseService("control_config/get_all_kinematic_soft_limits", &ControlConfigRobotServices::GetAllKinematicSoftLimits, this); + m_serviceSetDesiredLinearTwist = m_node_handle.advertiseService("control_config/set_desired_linear_twist", &ControlConfigRobotServices::SetDesiredLinearTwist, this); + m_serviceSetDesiredAngularTwist = m_node_handle.advertiseService("control_config/set_desired_angular_twist", &ControlConfigRobotServices::SetDesiredAngularTwist, this); + m_serviceSetDesiredJointSpeeds = m_node_handle.advertiseService("control_config/set_desired_joint_speeds", &ControlConfigRobotServices::SetDesiredJointSpeeds, this); + m_serviceGetDesiredSpeeds = m_node_handle.advertiseService("control_config/get_desired_speeds", &ControlConfigRobotServices::GetDesiredSpeeds, this); + m_serviceResetGravityVector = m_node_handle.advertiseService("control_config/reset_gravity_vector", &ControlConfigRobotServices::ResetGravityVector, this); + m_serviceResetPayloadInformation = m_node_handle.advertiseService("control_config/reset_payload_information", &ControlConfigRobotServices::ResetPayloadInformation, this); + m_serviceResetToolConfiguration = m_node_handle.advertiseService("control_config/reset_tool_configuration", &ControlConfigRobotServices::ResetToolConfiguration, this); + m_serviceResetJointSpeedSoftLimits = m_node_handle.advertiseService("control_config/reset_joint_speed_soft_limits", &ControlConfigRobotServices::ResetJointSpeedSoftLimits, this); + m_serviceResetTwistLinearSoftLimit = m_node_handle.advertiseService("control_config/reset_twist_linear_soft_limit", &ControlConfigRobotServices::ResetTwistLinearSoftLimit, this); + m_serviceResetTwistAngularSoftLimit = m_node_handle.advertiseService("control_config/reset_twist_angular_soft_limit", &ControlConfigRobotServices::ResetTwistAngularSoftLimit, this); + m_serviceResetJointAccelerationSoftLimits = m_node_handle.advertiseService("control_config/reset_joint_acceleration_soft_limits", &ControlConfigRobotServices::ResetJointAccelerationSoftLimits, this); +} + +bool ControlConfigRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool ControlConfigRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool ControlConfigRobotServices::SetGravityVector(kortex_driver::SetGravityVector::Request &req, kortex_driver::SetGravityVector::Response &res) +{ + + Kinova::Api::ControlConfig::GravityVector input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetGravityVector(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::GetGravityVector(kortex_driver::GetGravityVector::Request &req, kortex_driver::GetGravityVector::Response &res) +{ + + Kinova::Api::ControlConfig::GravityVector output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetGravityVector(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::SetPayloadInformation(kortex_driver::SetPayloadInformation::Request &req, kortex_driver::SetPayloadInformation::Response &res) +{ + + Kinova::Api::ControlConfig::PayloadInformation input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetPayloadInformation(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::GetPayloadInformation(kortex_driver::GetPayloadInformation::Request &req, kortex_driver::GetPayloadInformation::Response &res) +{ + + Kinova::Api::ControlConfig::PayloadInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetPayloadInformation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::SetToolConfiguration(kortex_driver::SetToolConfiguration::Request &req, kortex_driver::SetToolConfiguration::Response &res) +{ + + Kinova::Api::ControlConfig::ToolConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetToolConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::GetToolConfiguration(kortex_driver::GetToolConfiguration::Request &req, kortex_driver::GetToolConfiguration::Response &res) +{ + + Kinova::Api::ControlConfig::ToolConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetToolConfiguration(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::OnNotificationControlConfigurationTopic(kortex_driver::OnNotificationControlConfigurationTopic::Request &req, kortex_driver::OnNotificationControlConfigurationTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_ControlConfigurationTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::ControlConfig::ControlConfigurationNotification) > callback = std::bind(&ControlConfigRobotServices::cb_ControlConfigurationTopic, this, std::placeholders::_1); + output = m_controlconfig->OnNotificationControlConfigurationTopic(callback, input, m_current_device_id); + m_is_activated_ControlConfigurationTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void ControlConfigRobotServices::cb_ControlConfigurationTopic(Kinova::Api::ControlConfig::ControlConfigurationNotification notif) +{ + kortex_driver::ControlConfigurationNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ControlConfigurationTopic.publish(ros_msg); +} + +bool ControlConfigRobotServices::ControlConfig_Unsubscribe(kortex_driver::ControlConfig_Unsubscribe::Request &req, kortex_driver::ControlConfig_Unsubscribe::Response &res) +{ + + Kinova::Api::Common::NotificationHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->Unsubscribe(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::SetCartesianReferenceFrame(kortex_driver::SetCartesianReferenceFrame::Request &req, kortex_driver::SetCartesianReferenceFrame::Response &res) +{ + + Kinova::Api::ControlConfig::CartesianReferenceFrameInfo input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetCartesianReferenceFrame(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::GetCartesianReferenceFrame(kortex_driver::GetCartesianReferenceFrame::Request &req, kortex_driver::GetCartesianReferenceFrame::Response &res) +{ + + Kinova::Api::ControlConfig::CartesianReferenceFrameInfo output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetCartesianReferenceFrame(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ControlConfig_GetControlMode(kortex_driver::ControlConfig_GetControlMode::Request &req, kortex_driver::ControlConfig_GetControlMode::Response &res) +{ + + Kinova::Api::ControlConfig::ControlModeInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetControlMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::SetJointSpeedSoftLimits(kortex_driver::SetJointSpeedSoftLimits::Request &req, kortex_driver::SetJointSpeedSoftLimits::Response &res) +{ + + Kinova::Api::ControlConfig::JointSpeedSoftLimits input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetJointSpeedSoftLimits(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::SetTwistLinearSoftLimit(kortex_driver::SetTwistLinearSoftLimit::Request &req, kortex_driver::SetTwistLinearSoftLimit::Response &res) +{ + + Kinova::Api::ControlConfig::TwistLinearSoftLimit input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetTwistLinearSoftLimit(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::SetTwistAngularSoftLimit(kortex_driver::SetTwistAngularSoftLimit::Request &req, kortex_driver::SetTwistAngularSoftLimit::Response &res) +{ + + Kinova::Api::ControlConfig::TwistAngularSoftLimit input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetTwistAngularSoftLimit(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::SetJointAccelerationSoftLimits(kortex_driver::SetJointAccelerationSoftLimits::Request &req, kortex_driver::SetJointAccelerationSoftLimits::Response &res) +{ + + Kinova::Api::ControlConfig::JointAccelerationSoftLimits input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetJointAccelerationSoftLimits(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::GetKinematicHardLimits(kortex_driver::GetKinematicHardLimits::Request &req, kortex_driver::GetKinematicHardLimits::Response &res) +{ + + Kinova::Api::ControlConfig::KinematicLimits output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetKinematicHardLimits(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::GetKinematicSoftLimits(kortex_driver::GetKinematicSoftLimits::Request &req, kortex_driver::GetKinematicSoftLimits::Response &res) +{ + + Kinova::Api::ControlConfig::ControlModeInformation input; + ToProtoData(req.input, &input); + Kinova::Api::ControlConfig::KinematicLimits output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetKinematicSoftLimits(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::GetAllKinematicSoftLimits(kortex_driver::GetAllKinematicSoftLimits::Request &req, kortex_driver::GetAllKinematicSoftLimits::Response &res) +{ + + Kinova::Api::ControlConfig::KinematicLimitsList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetAllKinematicSoftLimits(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::SetDesiredLinearTwist(kortex_driver::SetDesiredLinearTwist::Request &req, kortex_driver::SetDesiredLinearTwist::Response &res) +{ + + Kinova::Api::ControlConfig::LinearTwist input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetDesiredLinearTwist(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::SetDesiredAngularTwist(kortex_driver::SetDesiredAngularTwist::Request &req, kortex_driver::SetDesiredAngularTwist::Response &res) +{ + + Kinova::Api::ControlConfig::AngularTwist input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetDesiredAngularTwist(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::SetDesiredJointSpeeds(kortex_driver::SetDesiredJointSpeeds::Request &req, kortex_driver::SetDesiredJointSpeeds::Response &res) +{ + + Kinova::Api::ControlConfig::JointSpeeds input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_controlconfig->SetDesiredJointSpeeds(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool ControlConfigRobotServices::GetDesiredSpeeds(kortex_driver::GetDesiredSpeeds::Request &req, kortex_driver::GetDesiredSpeeds::Response &res) +{ + + Kinova::Api::ControlConfig::DesiredSpeeds output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->GetDesiredSpeeds(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetGravityVector(kortex_driver::ResetGravityVector::Request &req, kortex_driver::ResetGravityVector::Response &res) +{ + + Kinova::Api::ControlConfig::GravityVector output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetGravityVector(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetPayloadInformation(kortex_driver::ResetPayloadInformation::Request &req, kortex_driver::ResetPayloadInformation::Response &res) +{ + + Kinova::Api::ControlConfig::PayloadInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetPayloadInformation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetToolConfiguration(kortex_driver::ResetToolConfiguration::Request &req, kortex_driver::ResetToolConfiguration::Response &res) +{ + + Kinova::Api::ControlConfig::ToolConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetToolConfiguration(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetJointSpeedSoftLimits(kortex_driver::ResetJointSpeedSoftLimits::Request &req, kortex_driver::ResetJointSpeedSoftLimits::Response &res) +{ + + Kinova::Api::ControlConfig::ControlModeInformation input; + ToProtoData(req.input, &input); + Kinova::Api::ControlConfig::JointSpeedSoftLimits output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetJointSpeedSoftLimits(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetTwistLinearSoftLimit(kortex_driver::ResetTwistLinearSoftLimit::Request &req, kortex_driver::ResetTwistLinearSoftLimit::Response &res) +{ + + Kinova::Api::ControlConfig::ControlModeInformation input; + ToProtoData(req.input, &input); + Kinova::Api::ControlConfig::TwistLinearSoftLimit output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetTwistLinearSoftLimit(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetTwistAngularSoftLimit(kortex_driver::ResetTwistAngularSoftLimit::Request &req, kortex_driver::ResetTwistAngularSoftLimit::Response &res) +{ + + Kinova::Api::ControlConfig::ControlModeInformation input; + ToProtoData(req.input, &input); + Kinova::Api::ControlConfig::TwistAngularSoftLimit output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetTwistAngularSoftLimit(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool ControlConfigRobotServices::ResetJointAccelerationSoftLimits(kortex_driver::ResetJointAccelerationSoftLimits::Request &req, kortex_driver::ResetJointAccelerationSoftLimits::Response &res) +{ + + Kinova::Api::ControlConfig::ControlModeInformation input; + ToProtoData(req.input, &input); + Kinova::Api::ControlConfig::JointAccelerationSoftLimits output; + + kortex_driver::KortexError result_error; + + try + { + output = m_controlconfig->ResetJointAccelerationSoftLimits(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_proto_converter.cpp new file mode 100644 index 0000000..143b590 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_proto_converter.cpp @@ -0,0 +1,239 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" + +int ToProtoData(kortex_driver::DeviceType input, Kinova::Api::DeviceConfig::DeviceType *output) +{ + + output->set_device_type((Kinova::Api::Common::DeviceTypes)input.device_type); + + return 0; +} +int ToProtoData(kortex_driver::RunMode input, Kinova::Api::DeviceConfig::RunMode *output) +{ + + output->set_run_mode((Kinova::Api::DeviceConfig::RunModes)input.run_mode); + + return 0; +} +int ToProtoData(kortex_driver::FirmwareVersion input, Kinova::Api::DeviceConfig::FirmwareVersion *output) +{ + + output->set_firmware_version(input.firmware_version); + + return 0; +} +int ToProtoData(kortex_driver::BootloaderVersion input, Kinova::Api::DeviceConfig::BootloaderVersion *output) +{ + + output->set_bootloader_version(input.bootloader_version); + + return 0; +} +int ToProtoData(kortex_driver::ModelNumber input, Kinova::Api::DeviceConfig::ModelNumber *output) +{ + + output->set_model_number(input.model_number); + + return 0; +} +int ToProtoData(kortex_driver::PartNumber input, Kinova::Api::DeviceConfig::PartNumber *output) +{ + + output->set_part_number(input.part_number); + + return 0; +} +int ToProtoData(kortex_driver::SerialNumber input, Kinova::Api::DeviceConfig::SerialNumber *output) +{ + + output->set_serial_number(input.serial_number); + + return 0; +} +int ToProtoData(kortex_driver::MACAddress input, Kinova::Api::DeviceConfig::MACAddress *output) +{ + + output->set_mac_address(std::string(input.mac_address.begin(), input.mac_address.end())); + + return 0; +} +int ToProtoData(kortex_driver::IPv4Settings input, Kinova::Api::DeviceConfig::IPv4Settings *output) +{ + + output->set_ipv4_address(input.ipv4_address); + output->set_ipv4_subnet_mask(input.ipv4_subnet_mask); + output->set_ipv4_default_gateway(input.ipv4_default_gateway); + + return 0; +} +int ToProtoData(kortex_driver::PartNumberRevision input, Kinova::Api::DeviceConfig::PartNumberRevision *output) +{ + + output->set_part_number_revision(input.part_number_revision); + + return 0; +} +int ToProtoData(kortex_driver::PowerOnSelfTestResult input, Kinova::Api::DeviceConfig::PowerOnSelfTestResult *output) +{ + + output->set_power_on_self_test_result(input.power_on_self_test_result); + + return 0; +} +int ToProtoData(kortex_driver::RebootRqst input, Kinova::Api::DeviceConfig::RebootRqst *output) +{ + + output->set_delay(input.delay); + + return 0; +} +int ToProtoData(kortex_driver::SafetyInformation input, Kinova::Api::DeviceConfig::SafetyInformation *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_can_change_safety_state(input.can_change_safety_state); + output->set_has_warning_threshold(input.has_warning_threshold); + output->set_has_error_threshold(input.has_error_threshold); + output->set_limit_type((Kinova::Api::DeviceConfig::SafetyLimitType)input.limit_type); + output->set_default_warning_threshold(input.default_warning_threshold); + output->set_default_error_threshold(input.default_error_threshold); + output->set_upper_hard_limit(input.upper_hard_limit); + output->set_lower_hard_limit(input.lower_hard_limit); + output->set_status((Kinova::Api::Common::SafetyStatusValue)input.status); + output->set_unit((Kinova::Api::Common::Unit)input.unit); + + return 0; +} +int ToProtoData(kortex_driver::SafetyInformationList input, Kinova::Api::DeviceConfig::SafetyInformationList *output) +{ + + output->clear_information(); + for(int i = 0; i < input.information.size(); i++) + { + ToProtoData(input.information[i], output->add_information()); + } + + return 0; +} +int ToProtoData(kortex_driver::SafetyEnable input, Kinova::Api::DeviceConfig::SafetyEnable *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_enable(input.enable); + + return 0; +} +int ToProtoData(kortex_driver::SafetyThreshold input, Kinova::Api::DeviceConfig::SafetyThreshold *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::SafetyConfiguration input, Kinova::Api::DeviceConfig::SafetyConfiguration *output) +{ + + ToProtoData(input.handle, output->mutable_handle()); + output->set_error_threshold(input.error_threshold); + output->set_warning_threshold(input.warning_threshold); + ToProtoData(input.enable, output->mutable_enable()); + + return 0; +} +int ToProtoData(kortex_driver::SafetyConfigurationList input, Kinova::Api::DeviceConfig::SafetyConfigurationList *output) +{ + + output->clear_configuration(); + for(int i = 0; i < input.configuration.size(); i++) + { + ToProtoData(input.configuration[i], output->add_configuration()); + } + + return 0; +} +int ToProtoData(kortex_driver::SafetyStatus input, Kinova::Api::DeviceConfig::SafetyStatus *output) +{ + + output->set_value((Kinova::Api::Common::SafetyStatusValue)input.value); + + return 0; +} +int ToProtoData(kortex_driver::CalibrationParameter input, Kinova::Api::DeviceConfig::CalibrationParameter *output) +{ + + output->set_calibration_parameter_identifier(input.calibration_parameter_identifier); + if(input.oneof_value.signedIntValue.size() > 0) + { + output->set_signedintvalue(input.oneof_value.signedIntValue[0]); + } + if(input.oneof_value.unsignedIntValue.size() > 0) + { + output->set_unsignedintvalue(input.oneof_value.unsignedIntValue[0]); + } + if(input.oneof_value.floatValue.size() > 0) + { + output->set_floatvalue(input.oneof_value.floatValue[0]); + } + + return 0; +} +int ToProtoData(kortex_driver::Calibration input, Kinova::Api::DeviceConfig::Calibration *output) +{ + + output->set_calibration_item((Kinova::Api::DeviceConfig::CalibrationItem)input.calibration_item); + output->clear_calibration_parameter(); + for(int i = 0; i < input.calibration_parameter.size(); i++) + { + ToProtoData(input.calibration_parameter[i], output->add_calibration_parameter()); + } + + return 0; +} +int ToProtoData(kortex_driver::CalibrationElement input, Kinova::Api::DeviceConfig::CalibrationElement *output) +{ + + output->set_calibration_item((Kinova::Api::DeviceConfig::CalibrationItem)input.calibration_item); + + return 0; +} +int ToProtoData(kortex_driver::CalibrationResult input, Kinova::Api::DeviceConfig::CalibrationResult *output) +{ + + output->set_calibration_status((Kinova::Api::DeviceConfig::CalibrationStatus)input.calibration_status); + output->set_calibration_details(input.calibration_details); + + return 0; +} +int ToProtoData(kortex_driver::DeviceConfig_CapSenseConfig input, Kinova::Api::DeviceConfig::CapSenseConfig *output) +{ + + output->set_mode((Kinova::Api::DeviceConfig::CapSenseMode)input.mode); + output->set_threshold_a(input.threshold_a); + output->set_threshold_b(input.threshold_b); + + return 0; +} +int ToProtoData(kortex_driver::CapSenseRegister input, Kinova::Api::DeviceConfig::CapSenseRegister *output) +{ + + output->set_address(input.address); + output->set_value(input.value); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_ros_converter.cpp new file mode 100644 index 0000000..15e0ef1 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_ros_converter.cpp @@ -0,0 +1,301 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" + +int ToRosData(Kinova::Api::DeviceConfig::DeviceType input, kortex_driver::DeviceType &output) +{ + + output.device_type = input.device_type(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::RunMode input, kortex_driver::RunMode &output) +{ + + output.run_mode = input.run_mode(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::FirmwareVersion input, kortex_driver::FirmwareVersion &output) +{ + + output.firmware_version = input.firmware_version(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::BootloaderVersion input, kortex_driver::BootloaderVersion &output) +{ + + output.bootloader_version = input.bootloader_version(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::ModelNumber input, kortex_driver::ModelNumber &output) +{ + + output.model_number = input.model_number(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::PartNumber input, kortex_driver::PartNumber &output) +{ + + output.part_number = input.part_number(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SerialNumber input, kortex_driver::SerialNumber &output) +{ + + output.serial_number = input.serial_number(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::MACAddress input, kortex_driver::MACAddress &output) +{ + + output.mac_address = std::vector(input.mac_address().begin(), input.mac_address().end()); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::IPv4Settings input, kortex_driver::IPv4Settings &output) +{ + + output.ipv4_address = input.ipv4_address(); + output.ipv4_subnet_mask = input.ipv4_subnet_mask(); + output.ipv4_default_gateway = input.ipv4_default_gateway(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::PartNumberRevision input, kortex_driver::PartNumberRevision &output) +{ + + output.part_number_revision = input.part_number_revision(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::PowerOnSelfTestResult input, kortex_driver::PowerOnSelfTestResult &output) +{ + + output.power_on_self_test_result = input.power_on_self_test_result(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::RebootRqst input, kortex_driver::RebootRqst &output) +{ + + output.delay = input.delay(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyInformation input, kortex_driver::SafetyInformation &output) +{ + + ToRosData(input.handle(), output.handle); + output.can_change_safety_state = input.can_change_safety_state(); + output.has_warning_threshold = input.has_warning_threshold(); + output.has_error_threshold = input.has_error_threshold(); + output.limit_type = input.limit_type(); + output.default_warning_threshold = input.default_warning_threshold(); + output.default_error_threshold = input.default_error_threshold(); + output.upper_hard_limit = input.upper_hard_limit(); + output.lower_hard_limit = input.lower_hard_limit(); + output.status = input.status(); + output.unit = input.unit(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyInformationList input, kortex_driver::SafetyInformationList &output) +{ + + output.information.clear(); + for(int i = 0; i < input.information_size(); i++) + { + kortex_driver::SafetyInformation temp; + ToRosData(input.information(i), temp); + output.information.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyEnable input, kortex_driver::SafetyEnable &output) +{ + + ToRosData(input.handle(), output.handle); + output.enable = input.enable(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyThreshold input, kortex_driver::SafetyThreshold &output) +{ + + ToRosData(input.handle(), output.handle); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyConfiguration input, kortex_driver::SafetyConfiguration &output) +{ + + ToRosData(input.handle(), output.handle); + output.error_threshold = input.error_threshold(); + output.warning_threshold = input.warning_threshold(); + ToRosData(input.enable(), output.enable); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyConfigurationList input, kortex_driver::SafetyConfigurationList &output) +{ + + output.configuration.clear(); + for(int i = 0; i < input.configuration_size(); i++) + { + kortex_driver::SafetyConfiguration temp; + ToRosData(input.configuration(i), temp); + output.configuration.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::SafetyStatus input, kortex_driver::SafetyStatus &output) +{ + + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::CalibrationParameter input, kortex_driver::CalibrationParameter &output) +{ + + output.calibration_parameter_identifier = input.calibration_parameter_identifier(); + + + auto oneof_type_value = input.value_case(); + switch(oneof_type_value) + { + + case Kinova::Api::DeviceConfig::CalibrationParameter::kSignedIntValue: + { + break; + } + + case Kinova::Api::DeviceConfig::CalibrationParameter::kUnsignedIntValue: + { + break; + } + + case Kinova::Api::DeviceConfig::CalibrationParameter::kFloatValue: + { + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::Calibration input, kortex_driver::Calibration &output) +{ + + output.calibration_item = input.calibration_item(); + output.calibration_parameter.clear(); + for(int i = 0; i < input.calibration_parameter_size(); i++) + { + kortex_driver::CalibrationParameter temp; + ToRosData(input.calibration_parameter(i), temp); + output.calibration_parameter.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::CalibrationElement input, kortex_driver::CalibrationElement &output) +{ + + output.calibration_item = input.calibration_item(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::CalibrationResult input, kortex_driver::CalibrationResult &output) +{ + + output.calibration_status = input.calibration_status(); + output.calibration_details = input.calibration_details(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::CapSenseConfig input, kortex_driver::DeviceConfig_CapSenseConfig &output) +{ + + output.mode = input.mode(); + output.threshold_a = input.threshold_a(); + output.threshold_b = input.threshold_b(); + + + + return 0; +} +int ToRosData(Kinova::Api::DeviceConfig::CapSenseRegister input, kortex_driver::CapSenseRegister &output) +{ + + output.address = input.address(); + output.value = input.value(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_services.cpp new file mode 100644 index 0000000..8476cff --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/deviceconfig_services.cpp @@ -0,0 +1,1171 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_services.h" + +DeviceConfigRobotServices::DeviceConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::DeviceConfig::DeviceConfigClient* deviceconfig, uint32_t device_id, uint32_t timeout_ms): + IDeviceConfigServices(node_handle), + m_deviceconfig(deviceconfig), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_SafetyTopic = m_node_handle.advertise("safety_topic", 1000); + m_is_activated_SafetyTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("device_config/set_device_id", &DeviceConfigRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("device_config/set_api_options", &DeviceConfigRobotServices::SetApiOptions, this); + + m_serviceGetRunMode = m_node_handle.advertiseService("device_config/get_run_mode", &DeviceConfigRobotServices::GetRunMode, this); + m_serviceSetRunMode = m_node_handle.advertiseService("device_config/set_run_mode", &DeviceConfigRobotServices::SetRunMode, this); + m_serviceGetDeviceType = m_node_handle.advertiseService("device_config/get_device_type", &DeviceConfigRobotServices::GetDeviceType, this); + m_serviceGetFirmwareVersion = m_node_handle.advertiseService("device_config/get_firmware_version", &DeviceConfigRobotServices::GetFirmwareVersion, this); + m_serviceGetBootloaderVersion = m_node_handle.advertiseService("device_config/get_bootloader_version", &DeviceConfigRobotServices::GetBootloaderVersion, this); + m_serviceGetModelNumber = m_node_handle.advertiseService("device_config/get_model_number", &DeviceConfigRobotServices::GetModelNumber, this); + m_serviceGetPartNumber = m_node_handle.advertiseService("device_config/get_part_number", &DeviceConfigRobotServices::GetPartNumber, this); + m_serviceGetSerialNumber = m_node_handle.advertiseService("device_config/get_serial_number", &DeviceConfigRobotServices::GetSerialNumber, this); + m_serviceGetMACAddress = m_node_handle.advertiseService("device_config/get_m_a_c_address", &DeviceConfigRobotServices::GetMACAddress, this); + m_serviceGetIPv4Settings = m_node_handle.advertiseService("device_config/get_i_pv4_settings", &DeviceConfigRobotServices::GetIPv4Settings, this); + m_serviceSetIPv4Settings = m_node_handle.advertiseService("device_config/set_i_pv4_settings", &DeviceConfigRobotServices::SetIPv4Settings, this); + m_serviceGetPartNumberRevision = m_node_handle.advertiseService("device_config/get_part_number_revision", &DeviceConfigRobotServices::GetPartNumberRevision, this); + m_serviceRebootRequest = m_node_handle.advertiseService("device_config/reboot_request", &DeviceConfigRobotServices::RebootRequest, this); + m_serviceSetSafetyEnable = m_node_handle.advertiseService("device_config/set_safety_enable", &DeviceConfigRobotServices::SetSafetyEnable, this); + m_serviceSetSafetyErrorThreshold = m_node_handle.advertiseService("device_config/set_safety_error_threshold", &DeviceConfigRobotServices::SetSafetyErrorThreshold, this); + m_serviceSetSafetyWarningThreshold = m_node_handle.advertiseService("device_config/set_safety_warning_threshold", &DeviceConfigRobotServices::SetSafetyWarningThreshold, this); + m_serviceSetSafetyConfiguration = m_node_handle.advertiseService("device_config/set_safety_configuration", &DeviceConfigRobotServices::SetSafetyConfiguration, this); + m_serviceGetSafetyConfiguration = m_node_handle.advertiseService("device_config/get_safety_configuration", &DeviceConfigRobotServices::GetSafetyConfiguration, this); + m_serviceGetSafetyInformation = m_node_handle.advertiseService("device_config/get_safety_information", &DeviceConfigRobotServices::GetSafetyInformation, this); + m_serviceGetSafetyEnable = m_node_handle.advertiseService("device_config/get_safety_enable", &DeviceConfigRobotServices::GetSafetyEnable, this); + m_serviceGetSafetyStatus = m_node_handle.advertiseService("device_config/get_safety_status", &DeviceConfigRobotServices::GetSafetyStatus, this); + m_serviceClearAllSafetyStatus = m_node_handle.advertiseService("device_config/clear_all_safety_status", &DeviceConfigRobotServices::ClearAllSafetyStatus, this); + m_serviceClearSafetyStatus = m_node_handle.advertiseService("device_config/clear_safety_status", &DeviceConfigRobotServices::ClearSafetyStatus, this); + m_serviceGetAllSafetyConfiguration = m_node_handle.advertiseService("device_config/get_all_safety_configuration", &DeviceConfigRobotServices::GetAllSafetyConfiguration, this); + m_serviceGetAllSafetyInformation = m_node_handle.advertiseService("device_config/get_all_safety_information", &DeviceConfigRobotServices::GetAllSafetyInformation, this); + m_serviceResetSafetyDefaults = m_node_handle.advertiseService("device_config/reset_safety_defaults", &DeviceConfigRobotServices::ResetSafetyDefaults, this); + m_serviceOnNotificationSafetyTopic = m_node_handle.advertiseService("device_config/activate_publishing_of_safety_topic", &DeviceConfigRobotServices::OnNotificationSafetyTopic, this); + m_serviceExecuteCalibration = m_node_handle.advertiseService("device_config/execute_calibration", &DeviceConfigRobotServices::ExecuteCalibration, this); + m_serviceGetCalibrationResult = m_node_handle.advertiseService("device_config/get_calibration_result", &DeviceConfigRobotServices::GetCalibrationResult, this); + m_serviceStopCalibration = m_node_handle.advertiseService("device_config/stop_calibration", &DeviceConfigRobotServices::StopCalibration, this); + m_serviceDeviceConfig_SetCapSenseConfig = m_node_handle.advertiseService("device_config/set_cap_sense_config", &DeviceConfigRobotServices::DeviceConfig_SetCapSenseConfig, this); + m_serviceDeviceConfig_GetCapSenseConfig = m_node_handle.advertiseService("device_config/get_cap_sense_config", &DeviceConfigRobotServices::DeviceConfig_GetCapSenseConfig, this); +} + +bool DeviceConfigRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool DeviceConfigRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool DeviceConfigRobotServices::GetRunMode(kortex_driver::GetRunMode::Request &req, kortex_driver::GetRunMode::Response &res) +{ + + Kinova::Api::DeviceConfig::RunMode output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetRunMode(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::SetRunMode(kortex_driver::SetRunMode::Request &req, kortex_driver::SetRunMode::Response &res) +{ + + Kinova::Api::DeviceConfig::RunMode input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetRunMode(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::GetDeviceType(kortex_driver::GetDeviceType::Request &req, kortex_driver::GetDeviceType::Response &res) +{ + + Kinova::Api::DeviceConfig::DeviceType output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetDeviceType(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetFirmwareVersion(kortex_driver::GetFirmwareVersion::Request &req, kortex_driver::GetFirmwareVersion::Response &res) +{ + + Kinova::Api::DeviceConfig::FirmwareVersion output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetFirmwareVersion(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetBootloaderVersion(kortex_driver::GetBootloaderVersion::Request &req, kortex_driver::GetBootloaderVersion::Response &res) +{ + + Kinova::Api::DeviceConfig::BootloaderVersion output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetBootloaderVersion(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetModelNumber(kortex_driver::GetModelNumber::Request &req, kortex_driver::GetModelNumber::Response &res) +{ + + Kinova::Api::DeviceConfig::ModelNumber output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetModelNumber(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetPartNumber(kortex_driver::GetPartNumber::Request &req, kortex_driver::GetPartNumber::Response &res) +{ + + Kinova::Api::DeviceConfig::PartNumber output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetPartNumber(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetSerialNumber(kortex_driver::GetSerialNumber::Request &req, kortex_driver::GetSerialNumber::Response &res) +{ + + Kinova::Api::DeviceConfig::SerialNumber output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetSerialNumber(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetMACAddress(kortex_driver::GetMACAddress::Request &req, kortex_driver::GetMACAddress::Response &res) +{ + + Kinova::Api::DeviceConfig::MACAddress output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetMACAddress(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetIPv4Settings(kortex_driver::GetIPv4Settings::Request &req, kortex_driver::GetIPv4Settings::Response &res) +{ + + Kinova::Api::DeviceConfig::IPv4Settings output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetIPv4Settings(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::SetIPv4Settings(kortex_driver::SetIPv4Settings::Request &req, kortex_driver::SetIPv4Settings::Response &res) +{ + + Kinova::Api::DeviceConfig::IPv4Settings input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetIPv4Settings(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::GetPartNumberRevision(kortex_driver::GetPartNumberRevision::Request &req, kortex_driver::GetPartNumberRevision::Response &res) +{ + + Kinova::Api::DeviceConfig::PartNumberRevision output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetPartNumberRevision(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::RebootRequest(kortex_driver::RebootRequest::Request &req, kortex_driver::RebootRequest::Response &res) +{ + + Kinova::Api::DeviceConfig::RebootRqst input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->RebootRequest(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::SetSafetyEnable(kortex_driver::SetSafetyEnable::Request &req, kortex_driver::SetSafetyEnable::Response &res) +{ + + Kinova::Api::DeviceConfig::SafetyEnable input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetSafetyEnable(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::SetSafetyErrorThreshold(kortex_driver::SetSafetyErrorThreshold::Request &req, kortex_driver::SetSafetyErrorThreshold::Response &res) +{ + + Kinova::Api::DeviceConfig::SafetyThreshold input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetSafetyErrorThreshold(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::SetSafetyWarningThreshold(kortex_driver::SetSafetyWarningThreshold::Request &req, kortex_driver::SetSafetyWarningThreshold::Response &res) +{ + + Kinova::Api::DeviceConfig::SafetyThreshold input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetSafetyWarningThreshold(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::SetSafetyConfiguration(kortex_driver::SetSafetyConfiguration::Request &req, kortex_driver::SetSafetyConfiguration::Response &res) +{ + + Kinova::Api::DeviceConfig::SafetyConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetSafetyConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::GetSafetyConfiguration(kortex_driver::GetSafetyConfiguration::Request &req, kortex_driver::GetSafetyConfiguration::Response &res) +{ + + Kinova::Api::Common::SafetyHandle input; + ToProtoData(req.input, &input); + Kinova::Api::DeviceConfig::SafetyConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetSafetyConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetSafetyInformation(kortex_driver::GetSafetyInformation::Request &req, kortex_driver::GetSafetyInformation::Response &res) +{ + + Kinova::Api::Common::SafetyHandle input; + ToProtoData(req.input, &input); + Kinova::Api::DeviceConfig::SafetyInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetSafetyInformation(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetSafetyEnable(kortex_driver::GetSafetyEnable::Request &req, kortex_driver::GetSafetyEnable::Response &res) +{ + + Kinova::Api::Common::SafetyHandle input; + ToProtoData(req.input, &input); + Kinova::Api::DeviceConfig::SafetyEnable output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetSafetyEnable(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetSafetyStatus(kortex_driver::GetSafetyStatus::Request &req, kortex_driver::GetSafetyStatus::Response &res) +{ + + Kinova::Api::Common::SafetyHandle input; + ToProtoData(req.input, &input); + Kinova::Api::DeviceConfig::SafetyStatus output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetSafetyStatus(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::ClearAllSafetyStatus(kortex_driver::ClearAllSafetyStatus::Request &req, kortex_driver::ClearAllSafetyStatus::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->ClearAllSafetyStatus(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::ClearSafetyStatus(kortex_driver::ClearSafetyStatus::Request &req, kortex_driver::ClearSafetyStatus::Response &res) +{ + + Kinova::Api::Common::SafetyHandle input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->ClearSafetyStatus(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::GetAllSafetyConfiguration(kortex_driver::GetAllSafetyConfiguration::Request &req, kortex_driver::GetAllSafetyConfiguration::Response &res) +{ + + Kinova::Api::DeviceConfig::SafetyConfigurationList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetAllSafetyConfiguration(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::GetAllSafetyInformation(kortex_driver::GetAllSafetyInformation::Request &req, kortex_driver::GetAllSafetyInformation::Response &res) +{ + + Kinova::Api::DeviceConfig::SafetyInformationList output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetAllSafetyInformation(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::ResetSafetyDefaults(kortex_driver::ResetSafetyDefaults::Request &req, kortex_driver::ResetSafetyDefaults::Response &res) +{ + + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->ResetSafetyDefaults(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::OnNotificationSafetyTopic(kortex_driver::OnNotificationSafetyTopic::Request &req, kortex_driver::OnNotificationSafetyTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_SafetyTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::Common::SafetyNotification) > callback = std::bind(&DeviceConfigRobotServices::cb_SafetyTopic, this, std::placeholders::_1); + output = m_deviceconfig->OnNotificationSafetyTopic(callback, input, m_current_device_id); + m_is_activated_SafetyTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void DeviceConfigRobotServices::cb_SafetyTopic(Kinova::Api::Common::SafetyNotification notif) +{ + kortex_driver::SafetyNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_SafetyTopic.publish(ros_msg); +} + +bool DeviceConfigRobotServices::ExecuteCalibration(kortex_driver::ExecuteCalibration::Request &req, kortex_driver::ExecuteCalibration::Response &res) +{ + + Kinova::Api::DeviceConfig::Calibration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->ExecuteCalibration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::GetCalibrationResult(kortex_driver::GetCalibrationResult::Request &req, kortex_driver::GetCalibrationResult::Response &res) +{ + + Kinova::Api::DeviceConfig::CalibrationElement input; + ToProtoData(req.input, &input); + Kinova::Api::DeviceConfig::CalibrationResult output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetCalibrationResult(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::StopCalibration(kortex_driver::StopCalibration::Request &req, kortex_driver::StopCalibration::Response &res) +{ + + Kinova::Api::DeviceConfig::Calibration input; + ToProtoData(req.input, &input); + Kinova::Api::DeviceConfig::CalibrationResult output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->StopCalibration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool DeviceConfigRobotServices::DeviceConfig_SetCapSenseConfig(kortex_driver::DeviceConfig_SetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_SetCapSenseConfig::Response &res) +{ + + Kinova::Api::DeviceConfig::CapSenseConfig input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_deviceconfig->SetCapSenseConfig(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool DeviceConfigRobotServices::DeviceConfig_GetCapSenseConfig(kortex_driver::DeviceConfig_GetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_GetCapSenseConfig::Response &res) +{ + + Kinova::Api::DeviceConfig::CapSenseConfig output; + + kortex_driver::KortexError result_error; + + try + { + output = m_deviceconfig->GetCapSenseConfig(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/devicemanager_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/devicemanager_proto_converter.cpp new file mode 100644 index 0000000..22cda42 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/devicemanager_proto_converter.cpp @@ -0,0 +1,29 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" + +int ToProtoData(kortex_driver::DeviceHandles input, Kinova::Api::DeviceManager::DeviceHandles *output) +{ + + output->clear_device_handle(); + for(int i = 0; i < input.device_handle.size(); i++) + { + ToProtoData(input.device_handle[i], output->add_device_handle()); + } + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/devicemanager_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/devicemanager_ros_converter.cpp new file mode 100644 index 0000000..3b5e95f --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/devicemanager_ros_converter.cpp @@ -0,0 +1,33 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" + +int ToRosData(Kinova::Api::DeviceManager::DeviceHandles input, kortex_driver::DeviceHandles &output) +{ + + output.device_handle.clear(); + for(int i = 0; i < input.device_handle_size(); i++) + { + kortex_driver::DeviceHandle temp; + ToRosData(input.device_handle(i), temp); + output.device_handle.push_back(temp); + } + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/devicemanager_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/devicemanager_services.cpp new file mode 100644 index 0000000..b649cf2 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/devicemanager_services.cpp @@ -0,0 +1,106 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_services.h" + +DeviceManagerRobotServices::DeviceManagerRobotServices(ros::NodeHandle& node_handle, Kinova::Api::DeviceManager::DeviceManagerClient* devicemanager, uint32_t device_id, uint32_t timeout_ms): + IDeviceManagerServices(node_handle), + m_devicemanager(devicemanager), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + + m_serviceSetDeviceID = m_node_handle.advertiseService("device_manager/set_device_id", &DeviceManagerRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("device_manager/set_api_options", &DeviceManagerRobotServices::SetApiOptions, this); + + m_serviceReadAllDevices = m_node_handle.advertiseService("device_manager/read_all_devices", &DeviceManagerRobotServices::ReadAllDevices, this); +} + +bool DeviceManagerRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool DeviceManagerRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool DeviceManagerRobotServices::ReadAllDevices(kortex_driver::ReadAllDevices::Request &req, kortex_driver::ReadAllDevices::Response &res) +{ + + Kinova::Api::DeviceManager::DeviceHandles output; + + kortex_driver::KortexError result_error; + + try + { + output = m_devicemanager->ReadAllDevices(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/grippercyclic_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/grippercyclic_proto_converter.cpp new file mode 100644 index 0000000..fe1962d --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/grippercyclic_proto_converter.cpp @@ -0,0 +1,112 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" + +int ToProtoData(kortex_driver::GripperCyclic_MessageId input, Kinova::Api::GripperCyclic::MessageId *output) +{ + + output->set_identifier(input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::MotorCommand input, Kinova::Api::GripperCyclic::MotorCommand *output) +{ + + output->set_motor_id(input.motor_id); + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_force(input.force); + + return 0; +} +int ToProtoData(kortex_driver::GripperCyclic_Command input, Kinova::Api::GripperCyclic::Command *output) +{ + + ToProtoData(input.command_id, output->mutable_command_id()); + output->set_flags(input.flags); + output->clear_motor_cmd(); + for(int i = 0; i < input.motor_cmd.size(); i++) + { + ToProtoData(input.motor_cmd[i], output->add_motor_cmd()); + } + + return 0; +} +int ToProtoData(kortex_driver::MotorFeedback input, Kinova::Api::GripperCyclic::MotorFeedback *output) +{ + + output->set_motor_id(input.motor_id); + output->set_position(input.position); + output->set_velocity(input.velocity); + output->set_current_motor(input.current_motor); + output->set_voltage(input.voltage); + output->set_temperature_motor(input.temperature_motor); + + return 0; +} +int ToProtoData(kortex_driver::GripperCyclic_Feedback input, Kinova::Api::GripperCyclic::Feedback *output) +{ + + ToProtoData(input.feedback_id, output->mutable_feedback_id()); + output->set_status_flags(input.status_flags); + output->set_fault_bank_a(input.fault_bank_a); + output->set_fault_bank_b(input.fault_bank_b); + output->set_warning_bank_a(input.warning_bank_a); + output->set_warning_bank_b(input.warning_bank_b); + output->clear_motor(); + for(int i = 0; i < input.motor.size(); i++) + { + ToProtoData(input.motor[i], output->add_motor()); + } + + return 0; +} +int ToProtoData(kortex_driver::CustomDataUnit input, Kinova::Api::GripperCyclic::CustomDataUnit *output) +{ + + output->set_custom_data_0(input.custom_data_0); + output->set_custom_data_1(input.custom_data_1); + output->set_custom_data_2(input.custom_data_2); + output->set_custom_data_3(input.custom_data_3); + output->set_custom_data_4(input.custom_data_4); + output->set_custom_data_5(input.custom_data_5); + output->set_custom_data_6(input.custom_data_6); + output->set_custom_data_7(input.custom_data_7); + output->set_custom_data_8(input.custom_data_8); + output->set_custom_data_9(input.custom_data_9); + output->set_custom_data_10(input.custom_data_10); + output->set_custom_data_11(input.custom_data_11); + output->set_custom_data_12(input.custom_data_12); + output->set_custom_data_13(input.custom_data_13); + output->set_custom_data_14(input.custom_data_14); + output->set_custom_data_15(input.custom_data_15); + + return 0; +} +int ToProtoData(kortex_driver::GripperCyclic_CustomData input, Kinova::Api::GripperCyclic::CustomData *output) +{ + + ToProtoData(input.custom_data_id, output->mutable_custom_data_id()); + ToProtoData(input.gripper_custom_data, output->mutable_gripper_custom_data()); + output->clear_motor_custom_data(); + for(int i = 0; i < input.motor_custom_data.size(); i++) + { + ToProtoData(input.motor_custom_data[i], output->add_motor_custom_data()); + } + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/grippercyclic_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/grippercyclic_ros_converter.cpp new file mode 100644 index 0000000..0952304 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/grippercyclic_ros_converter.cpp @@ -0,0 +1,132 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" + +int ToRosData(Kinova::Api::GripperCyclic::MessageId input, kortex_driver::GripperCyclic_MessageId &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::GripperCyclic::MotorCommand input, kortex_driver::MotorCommand &output) +{ + + output.motor_id = input.motor_id(); + output.position = input.position(); + output.velocity = input.velocity(); + output.force = input.force(); + + + + return 0; +} +int ToRosData(Kinova::Api::GripperCyclic::Command input, kortex_driver::GripperCyclic_Command &output) +{ + + ToRosData(input.command_id(), output.command_id); + output.flags = input.flags(); + output.motor_cmd.clear(); + for(int i = 0; i < input.motor_cmd_size(); i++) + { + kortex_driver::MotorCommand temp; + ToRosData(input.motor_cmd(i), temp); + output.motor_cmd.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::GripperCyclic::MotorFeedback input, kortex_driver::MotorFeedback &output) +{ + + output.motor_id = input.motor_id(); + output.position = input.position(); + output.velocity = input.velocity(); + output.current_motor = input.current_motor(); + output.voltage = input.voltage(); + output.temperature_motor = input.temperature_motor(); + + + + return 0; +} +int ToRosData(Kinova::Api::GripperCyclic::Feedback input, kortex_driver::GripperCyclic_Feedback &output) +{ + + ToRosData(input.feedback_id(), output.feedback_id); + output.status_flags = input.status_flags(); + output.fault_bank_a = input.fault_bank_a(); + output.fault_bank_b = input.fault_bank_b(); + output.warning_bank_a = input.warning_bank_a(); + output.warning_bank_b = input.warning_bank_b(); + output.motor.clear(); + for(int i = 0; i < input.motor_size(); i++) + { + kortex_driver::MotorFeedback temp; + ToRosData(input.motor(i), temp); + output.motor.push_back(temp); + } + + + + return 0; +} +int ToRosData(Kinova::Api::GripperCyclic::CustomDataUnit input, kortex_driver::CustomDataUnit &output) +{ + + output.custom_data_0 = input.custom_data_0(); + output.custom_data_1 = input.custom_data_1(); + output.custom_data_2 = input.custom_data_2(); + output.custom_data_3 = input.custom_data_3(); + output.custom_data_4 = input.custom_data_4(); + output.custom_data_5 = input.custom_data_5(); + output.custom_data_6 = input.custom_data_6(); + output.custom_data_7 = input.custom_data_7(); + output.custom_data_8 = input.custom_data_8(); + output.custom_data_9 = input.custom_data_9(); + output.custom_data_10 = input.custom_data_10(); + output.custom_data_11 = input.custom_data_11(); + output.custom_data_12 = input.custom_data_12(); + output.custom_data_13 = input.custom_data_13(); + output.custom_data_14 = input.custom_data_14(); + output.custom_data_15 = input.custom_data_15(); + + + + return 0; +} +int ToRosData(Kinova::Api::GripperCyclic::CustomData input, kortex_driver::GripperCyclic_CustomData &output) +{ + + ToRosData(input.custom_data_id(), output.custom_data_id); + ToRosData(input.gripper_custom_data(), output.gripper_custom_data); + output.motor_custom_data.clear(); + for(int i = 0; i < input.motor_custom_data_size(); i++) + { + kortex_driver::CustomDataUnit temp; + ToRosData(input.motor_custom_data(i), temp); + output.motor_custom_data.push_back(temp); + } + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_proto_converter.cpp new file mode 100644 index 0000000..1c0bc73 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_proto_converter.cpp @@ -0,0 +1,129 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" + +int ToProtoData(kortex_driver::EthernetDeviceIdentification input, Kinova::Api::InterconnectConfig::EthernetDeviceIdentification *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::EthernetDevice)input.device); + + return 0; +} +int ToProtoData(kortex_driver::EthernetConfiguration input, Kinova::Api::InterconnectConfig::EthernetConfiguration *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::EthernetDevice)input.device); + output->set_enabled(input.enabled); + output->set_speed((Kinova::Api::InterconnectConfig::EthernetSpeed)input.speed); + output->set_duplex((Kinova::Api::InterconnectConfig::EthernetDuplex)input.duplex); + + return 0; +} +int ToProtoData(kortex_driver::GPIOIdentification input, Kinova::Api::InterconnectConfig::GPIOIdentification *output) +{ + + output->set_identifier((Kinova::Api::InterconnectConfig::GPIOIdentifier)input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::GPIOConfiguration input, Kinova::Api::InterconnectConfig::GPIOConfiguration *output) +{ + + output->set_identifier((Kinova::Api::InterconnectConfig::GPIOIdentifier)input.identifier); + output->set_mode((Kinova::Api::InterconnectConfig::GPIOMode)input.mode); + output->set_pull((Kinova::Api::InterconnectConfig::GPIOPull)input.pull); + output->set_default_value((Kinova::Api::InterconnectConfig::GPIOValue)input.default_value); + + return 0; +} +int ToProtoData(kortex_driver::GPIOState input, Kinova::Api::InterconnectConfig::GPIOState *output) +{ + + output->set_identifier((Kinova::Api::InterconnectConfig::GPIOIdentifier)input.identifier); + output->set_value((Kinova::Api::InterconnectConfig::GPIOValue)input.value); + + return 0; +} +int ToProtoData(kortex_driver::I2CDeviceIdentification input, Kinova::Api::InterconnectConfig::I2CDeviceIdentification *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::I2CDevice)input.device); + + return 0; +} +int ToProtoData(kortex_driver::I2CConfiguration input, Kinova::Api::InterconnectConfig::I2CConfiguration *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::I2CDevice)input.device); + output->set_enabled(input.enabled); + output->set_mode((Kinova::Api::InterconnectConfig::I2CMode)input.mode); + output->set_addressing((Kinova::Api::InterconnectConfig::I2CDeviceAddressing)input.addressing); + + return 0; +} +int ToProtoData(kortex_driver::I2CReadParameter input, Kinova::Api::InterconnectConfig::I2CReadParameter *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::I2CDevice)input.device); + output->set_device_address(input.device_address); + output->set_size(input.size); + output->set_timeout(input.timeout); + + return 0; +} +int ToProtoData(kortex_driver::I2CReadRegisterParameter input, Kinova::Api::InterconnectConfig::I2CReadRegisterParameter *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::I2CDevice)input.device); + output->set_device_address(input.device_address); + output->set_register_address(input.register_address); + output->set_register_address_size((Kinova::Api::InterconnectConfig::I2CRegisterAddressSize)input.register_address_size); + output->set_size(input.size); + output->set_timeout(input.timeout); + + return 0; +} +int ToProtoData(kortex_driver::I2CWriteParameter input, Kinova::Api::InterconnectConfig::I2CWriteParameter *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::I2CDevice)input.device); + output->set_device_address(input.device_address); + output->set_timeout(input.timeout); + ToProtoData(input.data, output->mutable_data()); + + return 0; +} +int ToProtoData(kortex_driver::I2CWriteRegisterParameter input, Kinova::Api::InterconnectConfig::I2CWriteRegisterParameter *output) +{ + + output->set_device((Kinova::Api::InterconnectConfig::I2CDevice)input.device); + output->set_device_address(input.device_address); + output->set_register_address(input.register_address); + output->set_register_address_size((Kinova::Api::InterconnectConfig::I2CRegisterAddressSize)input.register_address_size); + output->set_timeout(input.timeout); + ToProtoData(input.data, output->mutable_data()); + + return 0; +} +int ToProtoData(kortex_driver::I2CData input, Kinova::Api::InterconnectConfig::I2CData *output) +{ + + output->set_data(std::string(input.data.begin(), input.data.end())); + output->set_size(input.size); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_ros_converter.cpp new file mode 100644 index 0000000..bc2f660 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_ros_converter.cpp @@ -0,0 +1,153 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" + +int ToRosData(Kinova::Api::InterconnectConfig::EthernetDeviceIdentification input, kortex_driver::EthernetDeviceIdentification &output) +{ + + output.device = input.device(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::EthernetConfiguration input, kortex_driver::EthernetConfiguration &output) +{ + + output.device = input.device(); + output.enabled = input.enabled(); + output.speed = input.speed(); + output.duplex = input.duplex(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::GPIOIdentification input, kortex_driver::GPIOIdentification &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::GPIOConfiguration input, kortex_driver::GPIOConfiguration &output) +{ + + output.identifier = input.identifier(); + output.mode = input.mode(); + output.pull = input.pull(); + output.default_value = input.default_value(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::GPIOState input, kortex_driver::GPIOState &output) +{ + + output.identifier = input.identifier(); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CDeviceIdentification input, kortex_driver::I2CDeviceIdentification &output) +{ + + output.device = input.device(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CConfiguration input, kortex_driver::I2CConfiguration &output) +{ + + output.device = input.device(); + output.enabled = input.enabled(); + output.mode = input.mode(); + output.addressing = input.addressing(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CReadParameter input, kortex_driver::I2CReadParameter &output) +{ + + output.device = input.device(); + output.device_address = input.device_address(); + output.size = input.size(); + output.timeout = input.timeout(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CReadRegisterParameter input, kortex_driver::I2CReadRegisterParameter &output) +{ + + output.device = input.device(); + output.device_address = input.device_address(); + output.register_address = input.register_address(); + output.register_address_size = input.register_address_size(); + output.size = input.size(); + output.timeout = input.timeout(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CWriteParameter input, kortex_driver::I2CWriteParameter &output) +{ + + output.device = input.device(); + output.device_address = input.device_address(); + output.timeout = input.timeout(); + ToRosData(input.data(), output.data); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CWriteRegisterParameter input, kortex_driver::I2CWriteRegisterParameter &output) +{ + + output.device = input.device(); + output.device_address = input.device_address(); + output.register_address = input.register_address(); + output.register_address_size = input.register_address_size(); + output.timeout = input.timeout(); + ToRosData(input.data(), output.data); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectConfig::I2CData input, kortex_driver::I2CData &output) +{ + + output.data = std::vector(input.data().begin(), input.data().end()); + output.size = input.size(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_services.cpp new file mode 100644 index 0000000..bd696c4 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/interconnectconfig_services.cpp @@ -0,0 +1,555 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_services.h" + +InterconnectConfigRobotServices::InterconnectConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::InterconnectConfig::InterconnectConfigClient* interconnectconfig, uint32_t device_id, uint32_t timeout_ms): + IInterconnectConfigServices(node_handle), + m_interconnectconfig(interconnectconfig), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + + m_serviceSetDeviceID = m_node_handle.advertiseService("interconnect_config/set_device_id", &InterconnectConfigRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("interconnect_config/set_api_options", &InterconnectConfigRobotServices::SetApiOptions, this); + + m_serviceGetUARTConfiguration = m_node_handle.advertiseService("interconnect_config/get_u_a_r_t_configuration", &InterconnectConfigRobotServices::GetUARTConfiguration, this); + m_serviceSetUARTConfiguration = m_node_handle.advertiseService("interconnect_config/set_u_a_r_t_configuration", &InterconnectConfigRobotServices::SetUARTConfiguration, this); + m_serviceGetEthernetConfiguration = m_node_handle.advertiseService("interconnect_config/get_ethernet_configuration", &InterconnectConfigRobotServices::GetEthernetConfiguration, this); + m_serviceSetEthernetConfiguration = m_node_handle.advertiseService("interconnect_config/set_ethernet_configuration", &InterconnectConfigRobotServices::SetEthernetConfiguration, this); + m_serviceGetGPIOConfiguration = m_node_handle.advertiseService("interconnect_config/get_g_p_i_o_configuration", &InterconnectConfigRobotServices::GetGPIOConfiguration, this); + m_serviceSetGPIOConfiguration = m_node_handle.advertiseService("interconnect_config/set_g_p_i_o_configuration", &InterconnectConfigRobotServices::SetGPIOConfiguration, this); + m_serviceGetGPIOState = m_node_handle.advertiseService("interconnect_config/get_g_p_i_o_state", &InterconnectConfigRobotServices::GetGPIOState, this); + m_serviceSetGPIOState = m_node_handle.advertiseService("interconnect_config/set_g_p_i_o_state", &InterconnectConfigRobotServices::SetGPIOState, this); + m_serviceGetI2CConfiguration = m_node_handle.advertiseService("interconnect_config/get_i2_c_configuration", &InterconnectConfigRobotServices::GetI2CConfiguration, this); + m_serviceSetI2CConfiguration = m_node_handle.advertiseService("interconnect_config/set_i2_c_configuration", &InterconnectConfigRobotServices::SetI2CConfiguration, this); + m_serviceI2CRead = m_node_handle.advertiseService("interconnect_config/i2_c_read", &InterconnectConfigRobotServices::I2CRead, this); + m_serviceI2CReadRegister = m_node_handle.advertiseService("interconnect_config/i2_c_read_register", &InterconnectConfigRobotServices::I2CReadRegister, this); + m_serviceI2CWrite = m_node_handle.advertiseService("interconnect_config/i2_c_write", &InterconnectConfigRobotServices::I2CWrite, this); + m_serviceI2CWriteRegister = m_node_handle.advertiseService("interconnect_config/i2_c_write_register", &InterconnectConfigRobotServices::I2CWriteRegister, this); +} + +bool InterconnectConfigRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool InterconnectConfigRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool InterconnectConfigRobotServices::GetUARTConfiguration(kortex_driver::GetUARTConfiguration::Request &req, kortex_driver::GetUARTConfiguration::Response &res) +{ + + Kinova::Api::Common::UARTDeviceIdentification input; + ToProtoData(req.input, &input); + Kinova::Api::Common::UARTConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->GetUARTConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::SetUARTConfiguration(kortex_driver::SetUARTConfiguration::Request &req, kortex_driver::SetUARTConfiguration::Response &res) +{ + + Kinova::Api::Common::UARTConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->SetUARTConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool InterconnectConfigRobotServices::GetEthernetConfiguration(kortex_driver::GetEthernetConfiguration::Request &req, kortex_driver::GetEthernetConfiguration::Response &res) +{ + + Kinova::Api::InterconnectConfig::EthernetDeviceIdentification input; + ToProtoData(req.input, &input); + Kinova::Api::InterconnectConfig::EthernetConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->GetEthernetConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::SetEthernetConfiguration(kortex_driver::SetEthernetConfiguration::Request &req, kortex_driver::SetEthernetConfiguration::Response &res) +{ + + Kinova::Api::InterconnectConfig::EthernetConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->SetEthernetConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool InterconnectConfigRobotServices::GetGPIOConfiguration(kortex_driver::GetGPIOConfiguration::Request &req, kortex_driver::GetGPIOConfiguration::Response &res) +{ + + Kinova::Api::InterconnectConfig::GPIOIdentification input; + ToProtoData(req.input, &input); + Kinova::Api::InterconnectConfig::GPIOConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->GetGPIOConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::SetGPIOConfiguration(kortex_driver::SetGPIOConfiguration::Request &req, kortex_driver::SetGPIOConfiguration::Response &res) +{ + + Kinova::Api::InterconnectConfig::GPIOConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->SetGPIOConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool InterconnectConfigRobotServices::GetGPIOState(kortex_driver::GetGPIOState::Request &req, kortex_driver::GetGPIOState::Response &res) +{ + + Kinova::Api::InterconnectConfig::GPIOIdentification input; + ToProtoData(req.input, &input); + Kinova::Api::InterconnectConfig::GPIOState output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->GetGPIOState(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::SetGPIOState(kortex_driver::SetGPIOState::Request &req, kortex_driver::SetGPIOState::Response &res) +{ + + Kinova::Api::InterconnectConfig::GPIOState input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->SetGPIOState(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool InterconnectConfigRobotServices::GetI2CConfiguration(kortex_driver::GetI2CConfiguration::Request &req, kortex_driver::GetI2CConfiguration::Response &res) +{ + + Kinova::Api::InterconnectConfig::I2CDeviceIdentification input; + ToProtoData(req.input, &input); + Kinova::Api::InterconnectConfig::I2CConfiguration output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->GetI2CConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::SetI2CConfiguration(kortex_driver::SetI2CConfiguration::Request &req, kortex_driver::SetI2CConfiguration::Response &res) +{ + + Kinova::Api::InterconnectConfig::I2CConfiguration input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->SetI2CConfiguration(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool InterconnectConfigRobotServices::I2CRead(kortex_driver::I2CRead::Request &req, kortex_driver::I2CRead::Response &res) +{ + + Kinova::Api::InterconnectConfig::I2CReadParameter input; + ToProtoData(req.input, &input); + Kinova::Api::InterconnectConfig::I2CData output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->I2CRead(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::I2CReadRegister(kortex_driver::I2CReadRegister::Request &req, kortex_driver::I2CReadRegister::Response &res) +{ + + Kinova::Api::InterconnectConfig::I2CReadRegisterParameter input; + ToProtoData(req.input, &input); + Kinova::Api::InterconnectConfig::I2CData output; + + kortex_driver::KortexError result_error; + + try + { + output = m_interconnectconfig->I2CReadRegister(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool InterconnectConfigRobotServices::I2CWrite(kortex_driver::I2CWrite::Request &req, kortex_driver::I2CWrite::Response &res) +{ + + Kinova::Api::InterconnectConfig::I2CWriteParameter input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->I2CWrite(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool InterconnectConfigRobotServices::I2CWriteRegister(kortex_driver::I2CWriteRegister::Request &req, kortex_driver::I2CWriteRegister::Response &res) +{ + + Kinova::Api::InterconnectConfig::I2CWriteRegisterParameter input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_interconnectconfig->I2CWriteRegister(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/interconnectcyclic_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/interconnectcyclic_proto_converter.cpp new file mode 100644 index 0000000..a2aef97 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/interconnectcyclic_proto_converter.cpp @@ -0,0 +1,89 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" + +int ToProtoData(kortex_driver::InterconnectCyclic_MessageId input, Kinova::Api::InterconnectCyclic::MessageId *output) +{ + + output->set_identifier(input.identifier); + + return 0; +} +int ToProtoData(kortex_driver::InterconnectCyclic_Command input, Kinova::Api::InterconnectCyclic::Command *output) +{ + + ToProtoData(input.command_id, output->mutable_command_id()); + output->set_flags(input.flags); + if(input.oneof_tool_command.gripper_command.size() > 0) + { + ToProtoData(input.oneof_tool_command.gripper_command[0], output->mutable_gripper_command()); + } + + return 0; +} +int ToProtoData(kortex_driver::InterconnectCyclic_Feedback input, Kinova::Api::InterconnectCyclic::Feedback *output) +{ + + ToProtoData(input.feedback_id, output->mutable_feedback_id()); + output->set_status_flags(input.status_flags); + output->set_jitter_comm(input.jitter_comm); + output->set_imu_acceleration_x(input.imu_acceleration_x); + output->set_imu_acceleration_y(input.imu_acceleration_y); + output->set_imu_acceleration_z(input.imu_acceleration_z); + output->set_imu_angular_velocity_x(input.imu_angular_velocity_x); + output->set_imu_angular_velocity_y(input.imu_angular_velocity_y); + output->set_imu_angular_velocity_z(input.imu_angular_velocity_z); + output->set_voltage(input.voltage); + output->set_temperature_core(input.temperature_core); + output->set_fault_bank_a(input.fault_bank_a); + output->set_fault_bank_b(input.fault_bank_b); + output->set_warning_bank_a(input.warning_bank_a); + output->set_warning_bank_b(input.warning_bank_b); + if(input.oneof_tool_feedback.gripper_feedback.size() > 0) + { + ToProtoData(input.oneof_tool_feedback.gripper_feedback[0], output->mutable_gripper_feedback()); + } + + return 0; +} +int ToProtoData(kortex_driver::InterconnectCyclic_CustomData input, Kinova::Api::InterconnectCyclic::CustomData *output) +{ + + ToProtoData(input.custom_data_id, output->mutable_custom_data_id()); + output->set_custom_data_0(input.custom_data_0); + output->set_custom_data_1(input.custom_data_1); + output->set_custom_data_2(input.custom_data_2); + output->set_custom_data_3(input.custom_data_3); + output->set_custom_data_4(input.custom_data_4); + output->set_custom_data_5(input.custom_data_5); + output->set_custom_data_6(input.custom_data_6); + output->set_custom_data_7(input.custom_data_7); + output->set_custom_data_8(input.custom_data_8); + output->set_custom_data_9(input.custom_data_9); + output->set_custom_data_10(input.custom_data_10); + output->set_custom_data_11(input.custom_data_11); + output->set_custom_data_12(input.custom_data_12); + output->set_custom_data_13(input.custom_data_13); + output->set_custom_data_14(input.custom_data_14); + output->set_custom_data_15(input.custom_data_15); + if(input.oneof_tool_customData.gripper_custom_data.size() > 0) + { + ToProtoData(input.oneof_tool_customData.gripper_custom_data[0], output->mutable_gripper_custom_data()); + } + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/interconnectcyclic_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/interconnectcyclic_ros_converter.cpp new file mode 100644 index 0000000..bdda1db --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/interconnectcyclic_ros_converter.cpp @@ -0,0 +1,118 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" + +int ToRosData(Kinova::Api::InterconnectCyclic::MessageId input, kortex_driver::InterconnectCyclic_MessageId &output) +{ + + output.identifier = input.identifier(); + + + + return 0; +} +int ToRosData(Kinova::Api::InterconnectCyclic::Command input, kortex_driver::InterconnectCyclic_Command &output) +{ + + ToRosData(input.command_id(), output.command_id); + output.flags = input.flags(); + + + auto oneof_type_tool_command = input.tool_command_case(); + switch(oneof_type_tool_command) + { + + case Kinova::Api::InterconnectCyclic::Command::kGripperCommand: + { + decltype(output.oneof_tool_command.gripper_command)::value_type temp; + ToRosData(input.gripper_command(), temp); + output.oneof_tool_command.gripper_command.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::InterconnectCyclic::Feedback input, kortex_driver::InterconnectCyclic_Feedback &output) +{ + + ToRosData(input.feedback_id(), output.feedback_id); + output.status_flags = input.status_flags(); + output.jitter_comm = input.jitter_comm(); + output.imu_acceleration_x = input.imu_acceleration_x(); + output.imu_acceleration_y = input.imu_acceleration_y(); + output.imu_acceleration_z = input.imu_acceleration_z(); + output.imu_angular_velocity_x = input.imu_angular_velocity_x(); + output.imu_angular_velocity_y = input.imu_angular_velocity_y(); + output.imu_angular_velocity_z = input.imu_angular_velocity_z(); + output.voltage = input.voltage(); + output.temperature_core = input.temperature_core(); + output.fault_bank_a = input.fault_bank_a(); + output.fault_bank_b = input.fault_bank_b(); + output.warning_bank_a = input.warning_bank_a(); + output.warning_bank_b = input.warning_bank_b(); + + + auto oneof_type_tool_feedback = input.tool_feedback_case(); + switch(oneof_type_tool_feedback) + { + + case Kinova::Api::InterconnectCyclic::Feedback::kGripperFeedback: + { + decltype(output.oneof_tool_feedback.gripper_feedback)::value_type temp; + ToRosData(input.gripper_feedback(), temp); + output.oneof_tool_feedback.gripper_feedback.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::InterconnectCyclic::CustomData input, kortex_driver::InterconnectCyclic_CustomData &output) +{ + + ToRosData(input.custom_data_id(), output.custom_data_id); + output.custom_data_0 = input.custom_data_0(); + output.custom_data_1 = input.custom_data_1(); + output.custom_data_2 = input.custom_data_2(); + output.custom_data_3 = input.custom_data_3(); + output.custom_data_4 = input.custom_data_4(); + output.custom_data_5 = input.custom_data_5(); + output.custom_data_6 = input.custom_data_6(); + output.custom_data_7 = input.custom_data_7(); + output.custom_data_8 = input.custom_data_8(); + output.custom_data_9 = input.custom_data_9(); + output.custom_data_10 = input.custom_data_10(); + output.custom_data_11 = input.custom_data_11(); + output.custom_data_12 = input.custom_data_12(); + output.custom_data_13 = input.custom_data_13(); + output.custom_data_14 = input.custom_data_14(); + output.custom_data_15 = input.custom_data_15(); + + + auto oneof_type_tool_customData = input.tool_customData_case(); + switch(oneof_type_tool_customData) + { + + case Kinova::Api::InterconnectCyclic::CustomData::kGripperCustomData: + { + decltype(output.oneof_tool_customData.gripper_custom_data)::value_type temp; + ToRosData(input.gripper_custom_data(), temp); + output.oneof_tool_customData.gripper_custom_data.push_back(temp); + break; + }} + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/productconfiguration_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/productconfiguration_proto_converter.cpp new file mode 100644 index 0000000..c93d9b8 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/productconfiguration_proto_converter.cpp @@ -0,0 +1,43 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" + +int ToProtoData(kortex_driver::CompleteProductConfiguration input, Kinova::Api::ProductConfiguration::CompleteProductConfiguration *output) +{ + + output->set_kin(input.kin); + output->set_model((Kinova::Api::ProductConfiguration::ModelId)input.model); + ToProtoData(input.country_code, output->mutable_country_code()); + output->set_assembly_plant(input.assembly_plant); + output->set_model_year(input.model_year); + output->set_degree_of_freedom(input.degree_of_freedom); + output->set_base_type((Kinova::Api::ProductConfiguration::BaseType)input.base_type); + output->set_end_effector_type((Kinova::Api::ProductConfiguration::EndEffectorType)input.end_effector_type); + output->set_vision_module_type((Kinova::Api::ProductConfiguration::VisionModuleType)input.vision_module_type); + output->set_interface_module_type((Kinova::Api::ProductConfiguration::InterfaceModuleType)input.interface_module_type); + output->set_arm_laterality((Kinova::Api::ProductConfiguration::ArmLaterality)input.arm_laterality); + output->set_wrist_type((Kinova::Api::ProductConfiguration::WristType)input.wrist_type); + + return 0; +} +int ToProtoData(kortex_driver::ProductConfigurationEndEffectorType input, Kinova::Api::ProductConfiguration::ProductConfigurationEndEffectorType *output) +{ + + output->set_end_effector_type((Kinova::Api::ProductConfiguration::EndEffectorType)input.end_effector_type); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/productconfiguration_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/productconfiguration_ros_converter.cpp new file mode 100644 index 0000000..4eeb2ad --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/productconfiguration_ros_converter.cpp @@ -0,0 +1,47 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" + +int ToRosData(Kinova::Api::ProductConfiguration::CompleteProductConfiguration input, kortex_driver::CompleteProductConfiguration &output) +{ + + output.kin = input.kin(); + output.model = input.model(); + ToRosData(input.country_code(), output.country_code); + output.assembly_plant = input.assembly_plant(); + output.model_year = input.model_year(); + output.degree_of_freedom = input.degree_of_freedom(); + output.base_type = input.base_type(); + output.end_effector_type = input.end_effector_type(); + output.vision_module_type = input.vision_module_type(); + output.interface_module_type = input.interface_module_type(); + output.arm_laterality = input.arm_laterality(); + output.wrist_type = input.wrist_type(); + + + + return 0; +} +int ToRosData(Kinova::Api::ProductConfiguration::ProductConfigurationEndEffectorType input, kortex_driver::ProductConfigurationEndEffectorType &output) +{ + + output.end_effector_type = input.end_effector_type(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/visionconfig_proto_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/visionconfig_proto_converter.cpp new file mode 100644 index 0000000..39009bb --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/visionconfig_proto_converter.cpp @@ -0,0 +1,173 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" + +int ToProtoData(kortex_driver::SensorSettings input, Kinova::Api::VisionConfig::SensorSettings *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_resolution((Kinova::Api::VisionConfig::Resolution)input.resolution); + output->set_frame_rate((Kinova::Api::VisionConfig::FrameRate)input.frame_rate); + output->set_bit_rate((Kinova::Api::VisionConfig::BitRate)input.bit_rate); + + return 0; +} +int ToProtoData(kortex_driver::SensorIdentifier input, Kinova::Api::VisionConfig::SensorIdentifier *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + + return 0; +} +int ToProtoData(kortex_driver::IntrinsicProfileIdentifier input, Kinova::Api::VisionConfig::IntrinsicProfileIdentifier *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_resolution((Kinova::Api::VisionConfig::Resolution)input.resolution); + + return 0; +} +int ToProtoData(kortex_driver::OptionIdentifier input, Kinova::Api::VisionConfig::OptionIdentifier *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_option((Kinova::Api::VisionConfig::Option)input.option); + + return 0; +} +int ToProtoData(kortex_driver::OptionValue input, Kinova::Api::VisionConfig::OptionValue *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_option((Kinova::Api::VisionConfig::Option)input.option); + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::OptionInformation input, Kinova::Api::VisionConfig::OptionInformation *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_option((Kinova::Api::VisionConfig::Option)input.option); + output->set_supported(input.supported); + output->set_read_only(input.read_only); + output->set_minimum(input.minimum); + output->set_maximum(input.maximum); + output->set_step(input.step); + output->set_default_value(input.default_value); + + return 0; +} +int ToProtoData(kortex_driver::SensorFocusAction input, Kinova::Api::VisionConfig::SensorFocusAction *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_focus_action((Kinova::Api::VisionConfig::FocusAction)input.focus_action); + if(input.oneof_action_parameters.focus_point.size() > 0) + { + ToProtoData(input.oneof_action_parameters.focus_point[0], output->mutable_focus_point()); + } + if(input.oneof_action_parameters.manual_focus.size() > 0) + { + ToProtoData(input.oneof_action_parameters.manual_focus[0], output->mutable_manual_focus()); + } + + return 0; +} +int ToProtoData(kortex_driver::FocusPoint input, Kinova::Api::VisionConfig::FocusPoint *output) +{ + + output->set_x(input.x); + output->set_y(input.y); + + return 0; +} +int ToProtoData(kortex_driver::ManualFocus input, Kinova::Api::VisionConfig::ManualFocus *output) +{ + + output->set_value(input.value); + + return 0; +} +int ToProtoData(kortex_driver::VisionNotification input, Kinova::Api::VisionConfig::VisionNotification *output) +{ + + output->set_event((Kinova::Api::VisionConfig::VisionEvent)input.event); + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_option((Kinova::Api::VisionConfig::Option)input.option); + + return 0; +} +int ToProtoData(kortex_driver::IntrinsicParameters input, Kinova::Api::VisionConfig::IntrinsicParameters *output) +{ + + output->set_sensor((Kinova::Api::VisionConfig::Sensor)input.sensor); + output->set_resolution((Kinova::Api::VisionConfig::Resolution)input.resolution); + output->set_principal_point_x(input.principal_point_x); + output->set_principal_point_y(input.principal_point_y); + output->set_focal_length_x(input.focal_length_x); + output->set_focal_length_y(input.focal_length_y); + ToProtoData(input.distortion_coeffs, output->mutable_distortion_coeffs()); + + return 0; +} +int ToProtoData(kortex_driver::DistortionCoefficients input, Kinova::Api::VisionConfig::DistortionCoefficients *output) +{ + + output->set_k1(input.k1); + output->set_k2(input.k2); + output->set_k3(input.k3); + output->set_p1(input.p1); + output->set_p2(input.p2); + + return 0; +} +int ToProtoData(kortex_driver::ExtrinsicParameters input, Kinova::Api::VisionConfig::ExtrinsicParameters *output) +{ + + ToProtoData(input.rotation, output->mutable_rotation()); + ToProtoData(input.translation, output->mutable_translation()); + + return 0; +} +int ToProtoData(kortex_driver::VisionConfig_RotationMatrix input, Kinova::Api::VisionConfig::RotationMatrix *output) +{ + + ToProtoData(input.row1, output->mutable_row1()); + ToProtoData(input.row2, output->mutable_row2()); + ToProtoData(input.row3, output->mutable_row3()); + + return 0; +} +int ToProtoData(kortex_driver::VisionConfig_RotationMatrixRow input, Kinova::Api::VisionConfig::RotationMatrixRow *output) +{ + + output->set_column1(input.column1); + output->set_column2(input.column2); + output->set_column3(input.column3); + + return 0; +} +int ToProtoData(kortex_driver::TranslationVector input, Kinova::Api::VisionConfig::TranslationVector *output) +{ + + output->set_t_x(input.t_x); + output->set_t_y(input.t_y); + output->set_t_z(input.t_z); + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/visionconfig_ros_converter.cpp b/ros_kortex/kortex_driver/src/generated/robot/visionconfig_ros_converter.cpp new file mode 100644 index 0000000..caee31c --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/visionconfig_ros_converter.cpp @@ -0,0 +1,216 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" + +int ToRosData(Kinova::Api::VisionConfig::SensorSettings input, kortex_driver::SensorSettings &output) +{ + + output.sensor = input.sensor(); + output.resolution = input.resolution(); + output.frame_rate = input.frame_rate(); + output.bit_rate = input.bit_rate(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::SensorIdentifier input, kortex_driver::SensorIdentifier &output) +{ + + output.sensor = input.sensor(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::IntrinsicProfileIdentifier input, kortex_driver::IntrinsicProfileIdentifier &output) +{ + + output.sensor = input.sensor(); + output.resolution = input.resolution(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::OptionIdentifier input, kortex_driver::OptionIdentifier &output) +{ + + output.sensor = input.sensor(); + output.option = input.option(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::OptionValue input, kortex_driver::OptionValue &output) +{ + + output.sensor = input.sensor(); + output.option = input.option(); + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::OptionInformation input, kortex_driver::OptionInformation &output) +{ + + output.sensor = input.sensor(); + output.option = input.option(); + output.supported = input.supported(); + output.read_only = input.read_only(); + output.minimum = input.minimum(); + output.maximum = input.maximum(); + output.step = input.step(); + output.default_value = input.default_value(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::SensorFocusAction input, kortex_driver::SensorFocusAction &output) +{ + + output.sensor = input.sensor(); + output.focus_action = input.focus_action(); + + + auto oneof_type_action_parameters = input.action_parameters_case(); + switch(oneof_type_action_parameters) + { + + case Kinova::Api::VisionConfig::SensorFocusAction::kFocusPoint: + { + decltype(output.oneof_action_parameters.focus_point)::value_type temp; + ToRosData(input.focus_point(), temp); + output.oneof_action_parameters.focus_point.push_back(temp); + break; + } + + case Kinova::Api::VisionConfig::SensorFocusAction::kManualFocus: + { + decltype(output.oneof_action_parameters.manual_focus)::value_type temp; + ToRosData(input.manual_focus(), temp); + output.oneof_action_parameters.manual_focus.push_back(temp); + break; + }} + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::FocusPoint input, kortex_driver::FocusPoint &output) +{ + + output.x = input.x(); + output.y = input.y(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::ManualFocus input, kortex_driver::ManualFocus &output) +{ + + output.value = input.value(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::VisionNotification input, kortex_driver::VisionNotification &output) +{ + + output.event = input.event(); + output.sensor = input.sensor(); + output.option = input.option(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::IntrinsicParameters input, kortex_driver::IntrinsicParameters &output) +{ + + output.sensor = input.sensor(); + output.resolution = input.resolution(); + output.principal_point_x = input.principal_point_x(); + output.principal_point_y = input.principal_point_y(); + output.focal_length_x = input.focal_length_x(); + output.focal_length_y = input.focal_length_y(); + ToRosData(input.distortion_coeffs(), output.distortion_coeffs); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::DistortionCoefficients input, kortex_driver::DistortionCoefficients &output) +{ + + output.k1 = input.k1(); + output.k2 = input.k2(); + output.k3 = input.k3(); + output.p1 = input.p1(); + output.p2 = input.p2(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::ExtrinsicParameters input, kortex_driver::ExtrinsicParameters &output) +{ + + ToRosData(input.rotation(), output.rotation); + ToRosData(input.translation(), output.translation); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::RotationMatrix input, kortex_driver::VisionConfig_RotationMatrix &output) +{ + + ToRosData(input.row1(), output.row1); + ToRosData(input.row2(), output.row2); + ToRosData(input.row3(), output.row3); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::RotationMatrixRow input, kortex_driver::VisionConfig_RotationMatrixRow &output) +{ + + output.column1 = input.column1(); + output.column2 = input.column2(); + output.column3 = input.column3(); + + + + return 0; +} +int ToRosData(Kinova::Api::VisionConfig::TranslationVector input, kortex_driver::TranslationVector &output) +{ + + output.t_x = input.t_x(); + output.t_y = input.t_y(); + output.t_z = input.t_z(); + + + + return 0; +} diff --git a/ros_kortex/kortex_driver/src/generated/robot/visionconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/robot/visionconfig_services.cpp new file mode 100644 index 0000000..a128bfb --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/robot/visionconfig_services.cpp @@ -0,0 +1,500 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_services.h" + +VisionConfigRobotServices::VisionConfigRobotServices(ros::NodeHandle& node_handle, Kinova::Api::VisionConfig::VisionConfigClient* visionconfig, uint32_t device_id, uint32_t timeout_ms): + IVisionConfigServices(node_handle), + m_visionconfig(visionconfig), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_VisionTopic = m_node_handle.advertise("vision_topic", 1000); + m_is_activated_VisionTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("vision_config/set_device_id", &VisionConfigRobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("vision_config/set_api_options", &VisionConfigRobotServices::SetApiOptions, this); + + m_serviceSetSensorSettings = m_node_handle.advertiseService("vision_config/set_sensor_settings", &VisionConfigRobotServices::SetSensorSettings, this); + m_serviceGetSensorSettings = m_node_handle.advertiseService("vision_config/get_sensor_settings", &VisionConfigRobotServices::GetSensorSettings, this); + m_serviceGetOptionValue = m_node_handle.advertiseService("vision_config/get_option_value", &VisionConfigRobotServices::GetOptionValue, this); + m_serviceSetOptionValue = m_node_handle.advertiseService("vision_config/set_option_value", &VisionConfigRobotServices::SetOptionValue, this); + m_serviceGetOptionInformation = m_node_handle.advertiseService("vision_config/get_option_information", &VisionConfigRobotServices::GetOptionInformation, this); + m_serviceOnNotificationVisionTopic = m_node_handle.advertiseService("vision_config/activate_publishing_of_vision_topic", &VisionConfigRobotServices::OnNotificationVisionTopic, this); + m_serviceDoSensorFocusAction = m_node_handle.advertiseService("vision_config/do_sensor_focus_action", &VisionConfigRobotServices::DoSensorFocusAction, this); + m_serviceGetIntrinsicParameters = m_node_handle.advertiseService("vision_config/get_intrinsic_parameters", &VisionConfigRobotServices::GetIntrinsicParameters, this); + m_serviceGetIntrinsicParametersProfile = m_node_handle.advertiseService("vision_config/get_intrinsic_parameters_profile", &VisionConfigRobotServices::GetIntrinsicParametersProfile, this); + m_serviceSetIntrinsicParameters = m_node_handle.advertiseService("vision_config/set_intrinsic_parameters", &VisionConfigRobotServices::SetIntrinsicParameters, this); + m_serviceGetExtrinsicParameters = m_node_handle.advertiseService("vision_config/get_extrinsic_parameters", &VisionConfigRobotServices::GetExtrinsicParameters, this); + m_serviceSetExtrinsicParameters = m_node_handle.advertiseService("vision_config/set_extrinsic_parameters", &VisionConfigRobotServices::SetExtrinsicParameters, this); +} + +bool VisionConfigRobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool VisionConfigRobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + + +bool VisionConfigRobotServices::SetSensorSettings(kortex_driver::SetSensorSettings::Request &req, kortex_driver::SetSensorSettings::Response &res) +{ + + Kinova::Api::VisionConfig::SensorSettings input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_visionconfig->SetSensorSettings(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool VisionConfigRobotServices::GetSensorSettings(kortex_driver::GetSensorSettings::Request &req, kortex_driver::GetSensorSettings::Response &res) +{ + + Kinova::Api::VisionConfig::SensorIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::VisionConfig::SensorSettings output; + + kortex_driver::KortexError result_error; + + try + { + output = m_visionconfig->GetSensorSettings(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool VisionConfigRobotServices::GetOptionValue(kortex_driver::GetOptionValue::Request &req, kortex_driver::GetOptionValue::Response &res) +{ + + Kinova::Api::VisionConfig::OptionIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::VisionConfig::OptionValue output; + + kortex_driver::KortexError result_error; + + try + { + output = m_visionconfig->GetOptionValue(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool VisionConfigRobotServices::SetOptionValue(kortex_driver::SetOptionValue::Request &req, kortex_driver::SetOptionValue::Response &res) +{ + + Kinova::Api::VisionConfig::OptionValue input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_visionconfig->SetOptionValue(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool VisionConfigRobotServices::GetOptionInformation(kortex_driver::GetOptionInformation::Request &req, kortex_driver::GetOptionInformation::Response &res) +{ + + Kinova::Api::VisionConfig::OptionIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::VisionConfig::OptionInformation output; + + kortex_driver::KortexError result_error; + + try + { + output = m_visionconfig->GetOptionInformation(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool VisionConfigRobotServices::OnNotificationVisionTopic(kortex_driver::OnNotificationVisionTopic::Request &req, kortex_driver::OnNotificationVisionTopic::Response &res) +{ + + // If the notification is already activated, don't activate multiple times + if (m_is_activated_VisionTopic) + return true; + Kinova::Api::Common::NotificationOptions input; + ToProtoData(req.input, &input); + Kinova::Api::Common::NotificationHandle output; + + kortex_driver::KortexError result_error; + + try + { + std::function< void (Kinova::Api::VisionConfig::VisionNotification) > callback = std::bind(&VisionConfigRobotServices::cb_VisionTopic, this, std::placeholders::_1); + output = m_visionconfig->OnNotificationVisionTopic(callback, input, m_current_device_id); + m_is_activated_VisionTopic = true; + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} +void VisionConfigRobotServices::cb_VisionTopic(Kinova::Api::VisionConfig::VisionNotification notif) +{ + kortex_driver::VisionNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_VisionTopic.publish(ros_msg); +} + +bool VisionConfigRobotServices::DoSensorFocusAction(kortex_driver::DoSensorFocusAction::Request &req, kortex_driver::DoSensorFocusAction::Response &res) +{ + + Kinova::Api::VisionConfig::SensorFocusAction input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_visionconfig->DoSensorFocusAction(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool VisionConfigRobotServices::GetIntrinsicParameters(kortex_driver::GetIntrinsicParameters::Request &req, kortex_driver::GetIntrinsicParameters::Response &res) +{ + + Kinova::Api::VisionConfig::SensorIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::VisionConfig::IntrinsicParameters output; + + kortex_driver::KortexError result_error; + + try + { + output = m_visionconfig->GetIntrinsicParameters(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool VisionConfigRobotServices::GetIntrinsicParametersProfile(kortex_driver::GetIntrinsicParametersProfile::Request &req, kortex_driver::GetIntrinsicParametersProfile::Response &res) +{ + + Kinova::Api::VisionConfig::IntrinsicProfileIdentifier input; + ToProtoData(req.input, &input); + Kinova::Api::VisionConfig::IntrinsicParameters output; + + kortex_driver::KortexError result_error; + + try + { + output = m_visionconfig->GetIntrinsicParametersProfile(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool VisionConfigRobotServices::SetIntrinsicParameters(kortex_driver::SetIntrinsicParameters::Request &req, kortex_driver::SetIntrinsicParameters::Response &res) +{ + + Kinova::Api::VisionConfig::IntrinsicParameters input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_visionconfig->SetIntrinsicParameters(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} + +bool VisionConfigRobotServices::GetExtrinsicParameters(kortex_driver::GetExtrinsicParameters::Request &req, kortex_driver::GetExtrinsicParameters::Response &res) +{ + + Kinova::Api::VisionConfig::ExtrinsicParameters output; + + kortex_driver::KortexError result_error; + + try + { + output = m_visionconfig->GetExtrinsicParameters(m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + ToRosData(output, res.output); + return true; +} + +bool VisionConfigRobotServices::SetExtrinsicParameters(kortex_driver::SetExtrinsicParameters::Request &req, kortex_driver::SetExtrinsicParameters::Response &res) +{ + + Kinova::Api::VisionConfig::ExtrinsicParameters input; + ToProtoData(req.input, &input); + kortex_driver::KortexError result_error; + + try + { + m_visionconfig->SetExtrinsicParameters(input, m_current_device_id, m_api_options); + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/actuatorconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/actuatorconfig_services.cpp new file mode 100644 index 0000000..224c14b --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/actuatorconfig_services.cpp @@ -0,0 +1,386 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/actuatorconfig_services.h" + +ActuatorConfigSimulationServices::ActuatorConfigSimulationServices(ros::NodeHandle& node_handle): + IActuatorConfigServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + + m_serviceSetDeviceID = m_node_handle.advertiseService("actuator_config/set_device_id", &ActuatorConfigSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("actuator_config/set_api_options", &ActuatorConfigSimulationServices::SetApiOptions, this); + + m_serviceGetAxisOffsets = m_node_handle.advertiseService("actuator_config/get_axis_offsets", &ActuatorConfigSimulationServices::GetAxisOffsets, this); + m_serviceSetAxisOffsets = m_node_handle.advertiseService("actuator_config/set_axis_offsets", &ActuatorConfigSimulationServices::SetAxisOffsets, this); + m_serviceSetTorqueOffset = m_node_handle.advertiseService("actuator_config/set_torque_offset", &ActuatorConfigSimulationServices::SetTorqueOffset, this); + m_serviceActuatorConfig_GetControlMode = m_node_handle.advertiseService("actuator_config/get_control_mode", &ActuatorConfigSimulationServices::ActuatorConfig_GetControlMode, this); + m_serviceSetControlMode = m_node_handle.advertiseService("actuator_config/set_control_mode", &ActuatorConfigSimulationServices::SetControlMode, this); + m_serviceGetActivatedControlLoop = m_node_handle.advertiseService("actuator_config/get_activated_control_loop", &ActuatorConfigSimulationServices::GetActivatedControlLoop, this); + m_serviceSetActivatedControlLoop = m_node_handle.advertiseService("actuator_config/set_activated_control_loop", &ActuatorConfigSimulationServices::SetActivatedControlLoop, this); + m_serviceGetControlLoopParameters = m_node_handle.advertiseService("actuator_config/get_control_loop_parameters", &ActuatorConfigSimulationServices::GetControlLoopParameters, this); + m_serviceSetControlLoopParameters = m_node_handle.advertiseService("actuator_config/set_control_loop_parameters", &ActuatorConfigSimulationServices::SetControlLoopParameters, this); + m_serviceSelectCustomData = m_node_handle.advertiseService("actuator_config/select_custom_data", &ActuatorConfigSimulationServices::SelectCustomData, this); + m_serviceGetSelectedCustomData = m_node_handle.advertiseService("actuator_config/get_selected_custom_data", &ActuatorConfigSimulationServices::GetSelectedCustomData, this); + m_serviceSetCommandMode = m_node_handle.advertiseService("actuator_config/set_command_mode", &ActuatorConfigSimulationServices::SetCommandMode, this); + m_serviceActuatorConfig_ClearFaults = m_node_handle.advertiseService("actuator_config/clear_faults", &ActuatorConfigSimulationServices::ActuatorConfig_ClearFaults, this); + m_serviceSetServoing = m_node_handle.advertiseService("actuator_config/set_servoing", &ActuatorConfigSimulationServices::SetServoing, this); + m_serviceMoveToPosition = m_node_handle.advertiseService("actuator_config/move_to_position", &ActuatorConfigSimulationServices::MoveToPosition, this); + m_serviceGetCommandMode = m_node_handle.advertiseService("actuator_config/get_command_mode", &ActuatorConfigSimulationServices::GetCommandMode, this); + m_serviceGetServoing = m_node_handle.advertiseService("actuator_config/get_servoing", &ActuatorConfigSimulationServices::GetServoing, this); + m_serviceGetTorqueOffset = m_node_handle.advertiseService("actuator_config/get_torque_offset", &ActuatorConfigSimulationServices::GetTorqueOffset, this); + m_serviceSetCoggingFeedforwardMode = m_node_handle.advertiseService("actuator_config/set_cogging_feedforward_mode", &ActuatorConfigSimulationServices::SetCoggingFeedforwardMode, this); + m_serviceGetCoggingFeedforwardMode = m_node_handle.advertiseService("actuator_config/get_cogging_feedforward_mode", &ActuatorConfigSimulationServices::GetCoggingFeedforwardMode, this); +} + +bool ActuatorConfigSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool ActuatorConfigSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool ActuatorConfigSimulationServices::GetAxisOffsets(kortex_driver::GetAxisOffsets::Request &req, kortex_driver::GetAxisOffsets::Response &res) +{ + + + if (GetAxisOffsetsHandler) + { + res = GetAxisOffsetsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_axis_offsets is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetAxisOffsets(kortex_driver::SetAxisOffsets::Request &req, kortex_driver::SetAxisOffsets::Response &res) +{ + + + if (SetAxisOffsetsHandler) + { + res = SetAxisOffsetsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_axis_offsets is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetTorqueOffset(kortex_driver::SetTorqueOffset::Request &req, kortex_driver::SetTorqueOffset::Response &res) +{ + + + if (SetTorqueOffsetHandler) + { + res = SetTorqueOffsetHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_torque_offset is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::ActuatorConfig_GetControlMode(kortex_driver::ActuatorConfig_GetControlMode::Request &req, kortex_driver::ActuatorConfig_GetControlMode::Response &res) +{ + + + if (ActuatorConfig_GetControlModeHandler) + { + res = ActuatorConfig_GetControlModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_control_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetControlMode(kortex_driver::SetControlMode::Request &req, kortex_driver::SetControlMode::Response &res) +{ + + + if (SetControlModeHandler) + { + res = SetControlModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_control_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetActivatedControlLoop(kortex_driver::GetActivatedControlLoop::Request &req, kortex_driver::GetActivatedControlLoop::Response &res) +{ + + + if (GetActivatedControlLoopHandler) + { + res = GetActivatedControlLoopHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_activated_control_loop is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetActivatedControlLoop(kortex_driver::SetActivatedControlLoop::Request &req, kortex_driver::SetActivatedControlLoop::Response &res) +{ + + + if (SetActivatedControlLoopHandler) + { + res = SetActivatedControlLoopHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_activated_control_loop is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetControlLoopParameters(kortex_driver::GetControlLoopParameters::Request &req, kortex_driver::GetControlLoopParameters::Response &res) +{ + + + if (GetControlLoopParametersHandler) + { + res = GetControlLoopParametersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_control_loop_parameters is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetControlLoopParameters(kortex_driver::SetControlLoopParameters::Request &req, kortex_driver::SetControlLoopParameters::Response &res) +{ + + + if (SetControlLoopParametersHandler) + { + res = SetControlLoopParametersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_control_loop_parameters is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SelectCustomData(kortex_driver::SelectCustomData::Request &req, kortex_driver::SelectCustomData::Response &res) +{ + + + if (SelectCustomDataHandler) + { + res = SelectCustomDataHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/select_custom_data is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetSelectedCustomData(kortex_driver::GetSelectedCustomData::Request &req, kortex_driver::GetSelectedCustomData::Response &res) +{ + + + if (GetSelectedCustomDataHandler) + { + res = GetSelectedCustomDataHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_selected_custom_data is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetCommandMode(kortex_driver::SetCommandMode::Request &req, kortex_driver::SetCommandMode::Response &res) +{ + + + if (SetCommandModeHandler) + { + res = SetCommandModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_command_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::ActuatorConfig_ClearFaults(kortex_driver::ActuatorConfig_ClearFaults::Request &req, kortex_driver::ActuatorConfig_ClearFaults::Response &res) +{ + + + if (ActuatorConfig_ClearFaultsHandler) + { + res = ActuatorConfig_ClearFaultsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/clear_faults is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetServoing(kortex_driver::SetServoing::Request &req, kortex_driver::SetServoing::Response &res) +{ + + + if (SetServoingHandler) + { + res = SetServoingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_servoing is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::MoveToPosition(kortex_driver::MoveToPosition::Request &req, kortex_driver::MoveToPosition::Response &res) +{ + + + if (MoveToPositionHandler) + { + res = MoveToPositionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/move_to_position is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetCommandMode(kortex_driver::GetCommandMode::Request &req, kortex_driver::GetCommandMode::Response &res) +{ + + + if (GetCommandModeHandler) + { + res = GetCommandModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_command_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetServoing(kortex_driver::GetServoing::Request &req, kortex_driver::GetServoing::Response &res) +{ + + + if (GetServoingHandler) + { + res = GetServoingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_servoing is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetTorqueOffset(kortex_driver::GetTorqueOffset::Request &req, kortex_driver::GetTorqueOffset::Response &res) +{ + + + if (GetTorqueOffsetHandler) + { + res = GetTorqueOffsetHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_torque_offset is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::SetCoggingFeedforwardMode(kortex_driver::SetCoggingFeedforwardMode::Request &req, kortex_driver::SetCoggingFeedforwardMode::Response &res) +{ + + + if (SetCoggingFeedforwardModeHandler) + { + res = SetCoggingFeedforwardModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/set_cogging_feedforward_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ActuatorConfigSimulationServices::GetCoggingFeedforwardMode(kortex_driver::GetCoggingFeedforwardMode::Request &req, kortex_driver::GetCoggingFeedforwardMode::Response &res) +{ + + + if (GetCoggingFeedforwardModeHandler) + { + res = GetCoggingFeedforwardModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for actuator_config/get_cogging_feedforward_mode is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/base_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/base_services.cpp new file mode 100644 index 0000000..a8e3589 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/base_services.cpp @@ -0,0 +1,2504 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/base_services.h" + +BaseSimulationServices::BaseSimulationServices(ros::NodeHandle& node_handle): + IBaseServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_ConfigurationChangeTopic = m_node_handle.advertise("configuration_change_topic", 1000); + m_is_activated_ConfigurationChangeTopic = false; + m_pub_MappingInfoTopic = m_node_handle.advertise("mapping_info_topic", 1000); + m_is_activated_MappingInfoTopic = false; + m_pub_ControlModeTopic = m_node_handle.advertise("control_mode_topic", 1000); + m_is_activated_ControlModeTopic = false; + m_pub_OperatingModeTopic = m_node_handle.advertise("operating_mode_topic", 1000); + m_is_activated_OperatingModeTopic = false; + m_pub_SequenceInfoTopic = m_node_handle.advertise("sequence_info_topic", 1000); + m_is_activated_SequenceInfoTopic = false; + m_pub_ProtectionZoneTopic = m_node_handle.advertise("protection_zone_topic", 1000); + m_is_activated_ProtectionZoneTopic = false; + m_pub_UserTopic = m_node_handle.advertise("user_topic", 1000); + m_is_activated_UserTopic = false; + m_pub_ControllerTopic = m_node_handle.advertise("controller_topic", 1000); + m_is_activated_ControllerTopic = false; + m_pub_ActionTopic = m_node_handle.advertise("action_topic", 1000); + m_is_activated_ActionTopic = false; + m_pub_RobotEventTopic = m_node_handle.advertise("robot_event_topic", 1000); + m_is_activated_RobotEventTopic = false; + m_pub_ServoingModeTopic = m_node_handle.advertise("servoing_mode_topic", 1000); + m_is_activated_ServoingModeTopic = false; + m_pub_FactoryTopic = m_node_handle.advertise("factory_topic", 1000); + m_is_activated_FactoryTopic = false; + m_pub_NetworkTopic = m_node_handle.advertise("network_topic", 1000); + m_is_activated_NetworkTopic = false; + m_pub_ArmStateTopic = m_node_handle.advertise("arm_state_topic", 1000); + m_is_activated_ArmStateTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("base/set_device_id", &BaseSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("base/set_api_options", &BaseSimulationServices::SetApiOptions, this); + + m_serviceCreateUserProfile = m_node_handle.advertiseService("base/create_user_profile", &BaseSimulationServices::CreateUserProfile, this); + m_serviceUpdateUserProfile = m_node_handle.advertiseService("base/update_user_profile", &BaseSimulationServices::UpdateUserProfile, this); + m_serviceReadUserProfile = m_node_handle.advertiseService("base/read_user_profile", &BaseSimulationServices::ReadUserProfile, this); + m_serviceDeleteUserProfile = m_node_handle.advertiseService("base/delete_user_profile", &BaseSimulationServices::DeleteUserProfile, this); + m_serviceReadAllUserProfiles = m_node_handle.advertiseService("base/read_all_user_profiles", &BaseSimulationServices::ReadAllUserProfiles, this); + m_serviceReadAllUsers = m_node_handle.advertiseService("base/read_all_users", &BaseSimulationServices::ReadAllUsers, this); + m_serviceChangePassword = m_node_handle.advertiseService("base/change_password", &BaseSimulationServices::ChangePassword, this); + m_serviceCreateSequence = m_node_handle.advertiseService("base/create_sequence", &BaseSimulationServices::CreateSequence, this); + m_serviceUpdateSequence = m_node_handle.advertiseService("base/update_sequence", &BaseSimulationServices::UpdateSequence, this); + m_serviceReadSequence = m_node_handle.advertiseService("base/read_sequence", &BaseSimulationServices::ReadSequence, this); + m_serviceDeleteSequence = m_node_handle.advertiseService("base/delete_sequence", &BaseSimulationServices::DeleteSequence, this); + m_serviceReadAllSequences = m_node_handle.advertiseService("base/read_all_sequences", &BaseSimulationServices::ReadAllSequences, this); + m_servicePlaySequence = m_node_handle.advertiseService("base/play_sequence", &BaseSimulationServices::PlaySequence, this); + m_servicePlayAdvancedSequence = m_node_handle.advertiseService("base/play_advanced_sequence", &BaseSimulationServices::PlayAdvancedSequence, this); + m_serviceStopSequence = m_node_handle.advertiseService("base/stop_sequence", &BaseSimulationServices::StopSequence, this); + m_servicePauseSequence = m_node_handle.advertiseService("base/pause_sequence", &BaseSimulationServices::PauseSequence, this); + m_serviceResumeSequence = m_node_handle.advertiseService("base/resume_sequence", &BaseSimulationServices::ResumeSequence, this); + m_serviceCreateProtectionZone = m_node_handle.advertiseService("base/create_protection_zone", &BaseSimulationServices::CreateProtectionZone, this); + m_serviceUpdateProtectionZone = m_node_handle.advertiseService("base/update_protection_zone", &BaseSimulationServices::UpdateProtectionZone, this); + m_serviceReadProtectionZone = m_node_handle.advertiseService("base/read_protection_zone", &BaseSimulationServices::ReadProtectionZone, this); + m_serviceDeleteProtectionZone = m_node_handle.advertiseService("base/delete_protection_zone", &BaseSimulationServices::DeleteProtectionZone, this); + m_serviceReadAllProtectionZones = m_node_handle.advertiseService("base/read_all_protection_zones", &BaseSimulationServices::ReadAllProtectionZones, this); + m_serviceCreateMapping = m_node_handle.advertiseService("base/create_mapping", &BaseSimulationServices::CreateMapping, this); + m_serviceReadMapping = m_node_handle.advertiseService("base/read_mapping", &BaseSimulationServices::ReadMapping, this); + m_serviceUpdateMapping = m_node_handle.advertiseService("base/update_mapping", &BaseSimulationServices::UpdateMapping, this); + m_serviceDeleteMapping = m_node_handle.advertiseService("base/delete_mapping", &BaseSimulationServices::DeleteMapping, this); + m_serviceReadAllMappings = m_node_handle.advertiseService("base/read_all_mappings", &BaseSimulationServices::ReadAllMappings, this); + m_serviceCreateMap = m_node_handle.advertiseService("base/create_map", &BaseSimulationServices::CreateMap, this); + m_serviceReadMap = m_node_handle.advertiseService("base/read_map", &BaseSimulationServices::ReadMap, this); + m_serviceUpdateMap = m_node_handle.advertiseService("base/update_map", &BaseSimulationServices::UpdateMap, this); + m_serviceDeleteMap = m_node_handle.advertiseService("base/delete_map", &BaseSimulationServices::DeleteMap, this); + m_serviceReadAllMaps = m_node_handle.advertiseService("base/read_all_maps", &BaseSimulationServices::ReadAllMaps, this); + m_serviceActivateMap = m_node_handle.advertiseService("base/activate_map", &BaseSimulationServices::ActivateMap, this); + m_serviceCreateAction = m_node_handle.advertiseService("base/create_action", &BaseSimulationServices::CreateAction, this); + m_serviceReadAction = m_node_handle.advertiseService("base/read_action", &BaseSimulationServices::ReadAction, this); + m_serviceReadAllActions = m_node_handle.advertiseService("base/read_all_actions", &BaseSimulationServices::ReadAllActions, this); + m_serviceDeleteAction = m_node_handle.advertiseService("base/delete_action", &BaseSimulationServices::DeleteAction, this); + m_serviceUpdateAction = m_node_handle.advertiseService("base/update_action", &BaseSimulationServices::UpdateAction, this); + m_serviceExecuteActionFromReference = m_node_handle.advertiseService("base/execute_action_from_reference", &BaseSimulationServices::ExecuteActionFromReference, this); + m_serviceExecuteAction = m_node_handle.advertiseService("base/execute_action", &BaseSimulationServices::ExecuteAction, this); + m_servicePauseAction = m_node_handle.advertiseService("base/pause_action", &BaseSimulationServices::PauseAction, this); + m_serviceStopAction = m_node_handle.advertiseService("base/stop_action", &BaseSimulationServices::StopAction, this); + m_serviceResumeAction = m_node_handle.advertiseService("base/resume_action", &BaseSimulationServices::ResumeAction, this); + m_serviceGetIPv4Configuration = m_node_handle.advertiseService("base/get_i_pv4_configuration", &BaseSimulationServices::GetIPv4Configuration, this); + m_serviceSetIPv4Configuration = m_node_handle.advertiseService("base/set_i_pv4_configuration", &BaseSimulationServices::SetIPv4Configuration, this); + m_serviceSetCommunicationInterfaceEnable = m_node_handle.advertiseService("base/set_communication_interface_enable", &BaseSimulationServices::SetCommunicationInterfaceEnable, this); + m_serviceIsCommunicationInterfaceEnable = m_node_handle.advertiseService("base/is_communication_interface_enable", &BaseSimulationServices::IsCommunicationInterfaceEnable, this); + m_serviceGetAvailableWifi = m_node_handle.advertiseService("base/get_available_wifi", &BaseSimulationServices::GetAvailableWifi, this); + m_serviceGetWifiInformation = m_node_handle.advertiseService("base/get_wifi_information", &BaseSimulationServices::GetWifiInformation, this); + m_serviceAddWifiConfiguration = m_node_handle.advertiseService("base/add_wifi_configuration", &BaseSimulationServices::AddWifiConfiguration, this); + m_serviceDeleteWifiConfiguration = m_node_handle.advertiseService("base/delete_wifi_configuration", &BaseSimulationServices::DeleteWifiConfiguration, this); + m_serviceGetAllConfiguredWifis = m_node_handle.advertiseService("base/get_all_configured_wifis", &BaseSimulationServices::GetAllConfiguredWifis, this); + m_serviceConnectWifi = m_node_handle.advertiseService("base/connect_wifi", &BaseSimulationServices::ConnectWifi, this); + m_serviceDisconnectWifi = m_node_handle.advertiseService("base/disconnect_wifi", &BaseSimulationServices::DisconnectWifi, this); + m_serviceGetConnectedWifiInformation = m_node_handle.advertiseService("base/get_connected_wifi_information", &BaseSimulationServices::GetConnectedWifiInformation, this); + m_serviceBase_Unsubscribe = m_node_handle.advertiseService("base/unsubscribe", &BaseSimulationServices::Base_Unsubscribe, this); + m_serviceOnNotificationConfigurationChangeTopic = m_node_handle.advertiseService("base/activate_publishing_of_configuration_change_topic", &BaseSimulationServices::OnNotificationConfigurationChangeTopic, this); + m_serviceOnNotificationMappingInfoTopic = m_node_handle.advertiseService("base/activate_publishing_of_mapping_info_topic", &BaseSimulationServices::OnNotificationMappingInfoTopic, this); + m_serviceOnNotificationControlModeTopic = m_node_handle.advertiseService("base/activate_publishing_of_control_mode_topic", &BaseSimulationServices::OnNotificationControlModeTopic, this); + m_serviceOnNotificationOperatingModeTopic = m_node_handle.advertiseService("base/activate_publishing_of_operating_mode_topic", &BaseSimulationServices::OnNotificationOperatingModeTopic, this); + m_serviceOnNotificationSequenceInfoTopic = m_node_handle.advertiseService("base/activate_publishing_of_sequence_info_topic", &BaseSimulationServices::OnNotificationSequenceInfoTopic, this); + m_serviceOnNotificationProtectionZoneTopic = m_node_handle.advertiseService("base/activate_publishing_of_protection_zone_topic", &BaseSimulationServices::OnNotificationProtectionZoneTopic, this); + m_serviceOnNotificationUserTopic = m_node_handle.advertiseService("base/activate_publishing_of_user_topic", &BaseSimulationServices::OnNotificationUserTopic, this); + m_serviceOnNotificationControllerTopic = m_node_handle.advertiseService("base/activate_publishing_of_controller_topic", &BaseSimulationServices::OnNotificationControllerTopic, this); + m_serviceOnNotificationActionTopic = m_node_handle.advertiseService("base/activate_publishing_of_action_topic", &BaseSimulationServices::OnNotificationActionTopic, this); + m_serviceOnNotificationRobotEventTopic = m_node_handle.advertiseService("base/activate_publishing_of_robot_event_topic", &BaseSimulationServices::OnNotificationRobotEventTopic, this); + m_servicePlayCartesianTrajectory = m_node_handle.advertiseService("base/play_cartesian_trajectory", &BaseSimulationServices::PlayCartesianTrajectory, this); + m_servicePlayCartesianTrajectoryPosition = m_node_handle.advertiseService("base/play_cartesian_trajectory_position", &BaseSimulationServices::PlayCartesianTrajectoryPosition, this); + m_servicePlayCartesianTrajectoryOrientation = m_node_handle.advertiseService("base/play_cartesian_trajectory_orientation", &BaseSimulationServices::PlayCartesianTrajectoryOrientation, this); + m_serviceStop = m_node_handle.advertiseService("base/stop", &BaseSimulationServices::Stop, this); + m_serviceGetMeasuredCartesianPose = m_node_handle.advertiseService("base/get_measured_cartesian_pose", &BaseSimulationServices::GetMeasuredCartesianPose, this); + m_serviceSendWrenchCommand = m_node_handle.advertiseService("base/send_wrench_command", &BaseSimulationServices::SendWrenchCommand, this); + m_serviceSendWrenchJoystickCommand = m_node_handle.advertiseService("base/send_wrench_joystick_command", &BaseSimulationServices::SendWrenchJoystickCommand, this); + m_serviceSendTwistJoystickCommand = m_node_handle.advertiseService("base/send_twist_joystick_command", &BaseSimulationServices::SendTwistJoystickCommand, this); + m_serviceSendTwistCommand = m_node_handle.advertiseService("base/send_twist_command", &BaseSimulationServices::SendTwistCommand, this); + m_servicePlayJointTrajectory = m_node_handle.advertiseService("base/play_joint_trajectory", &BaseSimulationServices::PlayJointTrajectory, this); + m_servicePlaySelectedJointTrajectory = m_node_handle.advertiseService("base/play_selected_joint_trajectory", &BaseSimulationServices::PlaySelectedJointTrajectory, this); + m_serviceGetMeasuredJointAngles = m_node_handle.advertiseService("base/get_measured_joint_angles", &BaseSimulationServices::GetMeasuredJointAngles, this); + m_serviceSendJointSpeedsCommand = m_node_handle.advertiseService("base/send_joint_speeds_command", &BaseSimulationServices::SendJointSpeedsCommand, this); + m_serviceSendSelectedJointSpeedCommand = m_node_handle.advertiseService("base/send_selected_joint_speed_command", &BaseSimulationServices::SendSelectedJointSpeedCommand, this); + m_serviceSendGripperCommand = m_node_handle.advertiseService("base/send_gripper_command", &BaseSimulationServices::SendGripperCommand, this); + m_serviceGetMeasuredGripperMovement = m_node_handle.advertiseService("base/get_measured_gripper_movement", &BaseSimulationServices::GetMeasuredGripperMovement, this); + m_serviceSetAdmittance = m_node_handle.advertiseService("base/set_admittance", &BaseSimulationServices::SetAdmittance, this); + m_serviceSetOperatingMode = m_node_handle.advertiseService("base/set_operating_mode", &BaseSimulationServices::SetOperatingMode, this); + m_serviceApplyEmergencyStop = m_node_handle.advertiseService("base/apply_emergency_stop", &BaseSimulationServices::ApplyEmergencyStop, this); + m_serviceBase_ClearFaults = m_node_handle.advertiseService("base/clear_faults", &BaseSimulationServices::Base_ClearFaults, this); + m_serviceBase_GetControlMode = m_node_handle.advertiseService("base/get_control_mode", &BaseSimulationServices::Base_GetControlMode, this); + m_serviceGetOperatingMode = m_node_handle.advertiseService("base/get_operating_mode", &BaseSimulationServices::GetOperatingMode, this); + m_serviceSetServoingMode = m_node_handle.advertiseService("base/set_servoing_mode", &BaseSimulationServices::SetServoingMode, this); + m_serviceGetServoingMode = m_node_handle.advertiseService("base/get_servoing_mode", &BaseSimulationServices::GetServoingMode, this); + m_serviceOnNotificationServoingModeTopic = m_node_handle.advertiseService("base/activate_publishing_of_servoing_mode_topic", &BaseSimulationServices::OnNotificationServoingModeTopic, this); + m_serviceRestoreFactorySettings = m_node_handle.advertiseService("base/restore_factory_settings", &BaseSimulationServices::RestoreFactorySettings, this); + m_serviceOnNotificationFactoryTopic = m_node_handle.advertiseService("base/activate_publishing_of_factory_topic", &BaseSimulationServices::OnNotificationFactoryTopic, this); + m_serviceGetAllConnectedControllers = m_node_handle.advertiseService("base/get_all_connected_controllers", &BaseSimulationServices::GetAllConnectedControllers, this); + m_serviceGetControllerState = m_node_handle.advertiseService("base/get_controller_state", &BaseSimulationServices::GetControllerState, this); + m_serviceGetActuatorCount = m_node_handle.advertiseService("base/get_actuator_count", &BaseSimulationServices::GetActuatorCount, this); + m_serviceStartWifiScan = m_node_handle.advertiseService("base/start_wifi_scan", &BaseSimulationServices::StartWifiScan, this); + m_serviceGetConfiguredWifi = m_node_handle.advertiseService("base/get_configured_wifi", &BaseSimulationServices::GetConfiguredWifi, this); + m_serviceOnNotificationNetworkTopic = m_node_handle.advertiseService("base/activate_publishing_of_network_topic", &BaseSimulationServices::OnNotificationNetworkTopic, this); + m_serviceGetArmState = m_node_handle.advertiseService("base/get_arm_state", &BaseSimulationServices::GetArmState, this); + m_serviceOnNotificationArmStateTopic = m_node_handle.advertiseService("base/activate_publishing_of_arm_state_topic", &BaseSimulationServices::OnNotificationArmStateTopic, this); + m_serviceGetIPv4Information = m_node_handle.advertiseService("base/get_i_pv4_information", &BaseSimulationServices::GetIPv4Information, this); + m_serviceSetWifiCountryCode = m_node_handle.advertiseService("base/set_wifi_country_code", &BaseSimulationServices::SetWifiCountryCode, this); + m_serviceGetWifiCountryCode = m_node_handle.advertiseService("base/get_wifi_country_code", &BaseSimulationServices::GetWifiCountryCode, this); + m_serviceBase_SetCapSenseConfig = m_node_handle.advertiseService("base/set_cap_sense_config", &BaseSimulationServices::Base_SetCapSenseConfig, this); + m_serviceBase_GetCapSenseConfig = m_node_handle.advertiseService("base/get_cap_sense_config", &BaseSimulationServices::Base_GetCapSenseConfig, this); + m_serviceGetAllJointsSpeedHardLimitation = m_node_handle.advertiseService("base/get_all_joints_speed_hard_limitation", &BaseSimulationServices::GetAllJointsSpeedHardLimitation, this); + m_serviceGetAllJointsTorqueHardLimitation = m_node_handle.advertiseService("base/get_all_joints_torque_hard_limitation", &BaseSimulationServices::GetAllJointsTorqueHardLimitation, this); + m_serviceGetTwistHardLimitation = m_node_handle.advertiseService("base/get_twist_hard_limitation", &BaseSimulationServices::GetTwistHardLimitation, this); + m_serviceGetWrenchHardLimitation = m_node_handle.advertiseService("base/get_wrench_hard_limitation", &BaseSimulationServices::GetWrenchHardLimitation, this); + m_serviceSendJointSpeedsJoystickCommand = m_node_handle.advertiseService("base/send_joint_speeds_joystick_command", &BaseSimulationServices::SendJointSpeedsJoystickCommand, this); + m_serviceSendSelectedJointSpeedJoystickCommand = m_node_handle.advertiseService("base/send_selected_joint_speed_joystick_command", &BaseSimulationServices::SendSelectedJointSpeedJoystickCommand, this); + m_serviceEnableBridge = m_node_handle.advertiseService("base/enable_bridge", &BaseSimulationServices::EnableBridge, this); + m_serviceDisableBridge = m_node_handle.advertiseService("base/disable_bridge", &BaseSimulationServices::DisableBridge, this); + m_serviceGetBridgeList = m_node_handle.advertiseService("base/get_bridge_list", &BaseSimulationServices::GetBridgeList, this); + m_serviceGetBridgeConfig = m_node_handle.advertiseService("base/get_bridge_config", &BaseSimulationServices::GetBridgeConfig, this); + m_servicePlayPreComputedJointTrajectory = m_node_handle.advertiseService("base/play_pre_computed_joint_trajectory", &BaseSimulationServices::PlayPreComputedJointTrajectory, this); + m_serviceGetProductConfiguration = m_node_handle.advertiseService("base/get_product_configuration", &BaseSimulationServices::GetProductConfiguration, this); + m_serviceUpdateEndEffectorTypeConfiguration = m_node_handle.advertiseService("base/update_end_effector_type_configuration", &BaseSimulationServices::UpdateEndEffectorTypeConfiguration, this); + m_serviceRestoreFactoryProductConfiguration = m_node_handle.advertiseService("base/restore_factory_product_configuration", &BaseSimulationServices::RestoreFactoryProductConfiguration, this); + m_serviceGetTrajectoryErrorReport = m_node_handle.advertiseService("base/get_trajectory_error_report", &BaseSimulationServices::GetTrajectoryErrorReport, this); + m_serviceGetAllJointsSpeedSoftLimitation = m_node_handle.advertiseService("base/get_all_joints_speed_soft_limitation", &BaseSimulationServices::GetAllJointsSpeedSoftLimitation, this); + m_serviceGetAllJointsTorqueSoftLimitation = m_node_handle.advertiseService("base/get_all_joints_torque_soft_limitation", &BaseSimulationServices::GetAllJointsTorqueSoftLimitation, this); + m_serviceGetTwistSoftLimitation = m_node_handle.advertiseService("base/get_twist_soft_limitation", &BaseSimulationServices::GetTwistSoftLimitation, this); + m_serviceGetWrenchSoftLimitation = m_node_handle.advertiseService("base/get_wrench_soft_limitation", &BaseSimulationServices::GetWrenchSoftLimitation, this); + m_serviceSetControllerConfigurationMode = m_node_handle.advertiseService("base/set_controller_configuration_mode", &BaseSimulationServices::SetControllerConfigurationMode, this); + m_serviceGetControllerConfigurationMode = m_node_handle.advertiseService("base/get_controller_configuration_mode", &BaseSimulationServices::GetControllerConfigurationMode, this); + m_serviceStartTeaching = m_node_handle.advertiseService("base/start_teaching", &BaseSimulationServices::StartTeaching, this); + m_serviceStopTeaching = m_node_handle.advertiseService("base/stop_teaching", &BaseSimulationServices::StopTeaching, this); + m_serviceAddSequenceTasks = m_node_handle.advertiseService("base/add_sequence_tasks", &BaseSimulationServices::AddSequenceTasks, this); + m_serviceUpdateSequenceTask = m_node_handle.advertiseService("base/update_sequence_task", &BaseSimulationServices::UpdateSequenceTask, this); + m_serviceSwapSequenceTasks = m_node_handle.advertiseService("base/swap_sequence_tasks", &BaseSimulationServices::SwapSequenceTasks, this); + m_serviceReadSequenceTask = m_node_handle.advertiseService("base/read_sequence_task", &BaseSimulationServices::ReadSequenceTask, this); + m_serviceReadAllSequenceTasks = m_node_handle.advertiseService("base/read_all_sequence_tasks", &BaseSimulationServices::ReadAllSequenceTasks, this); + m_serviceDeleteSequenceTask = m_node_handle.advertiseService("base/delete_sequence_task", &BaseSimulationServices::DeleteSequenceTask, this); + m_serviceDeleteAllSequenceTasks = m_node_handle.advertiseService("base/delete_all_sequence_tasks", &BaseSimulationServices::DeleteAllSequenceTasks, this); + m_serviceTakeSnapshot = m_node_handle.advertiseService("base/take_snapshot", &BaseSimulationServices::TakeSnapshot, this); + m_serviceGetFirmwareBundleVersions = m_node_handle.advertiseService("base/get_firmware_bundle_versions", &BaseSimulationServices::GetFirmwareBundleVersions, this); + m_serviceMoveSequenceTask = m_node_handle.advertiseService("base/move_sequence_task", &BaseSimulationServices::MoveSequenceTask, this); + m_serviceDuplicateMapping = m_node_handle.advertiseService("base/duplicate_mapping", &BaseSimulationServices::DuplicateMapping, this); + m_serviceDuplicateMap = m_node_handle.advertiseService("base/duplicate_map", &BaseSimulationServices::DuplicateMap, this); + m_serviceSetControllerConfiguration = m_node_handle.advertiseService("base/set_controller_configuration", &BaseSimulationServices::SetControllerConfiguration, this); + m_serviceGetControllerConfiguration = m_node_handle.advertiseService("base/get_controller_configuration", &BaseSimulationServices::GetControllerConfiguration, this); + m_serviceGetAllControllerConfigurations = m_node_handle.advertiseService("base/get_all_controller_configurations", &BaseSimulationServices::GetAllControllerConfigurations, this); +} + +bool BaseSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool BaseSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool BaseSimulationServices::CreateUserProfile(kortex_driver::CreateUserProfile::Request &req, kortex_driver::CreateUserProfile::Response &res) +{ + + + if (CreateUserProfileHandler) + { + res = CreateUserProfileHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/create_user_profile is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateUserProfile(kortex_driver::UpdateUserProfile::Request &req, kortex_driver::UpdateUserProfile::Response &res) +{ + + + if (UpdateUserProfileHandler) + { + res = UpdateUserProfileHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_user_profile is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadUserProfile(kortex_driver::ReadUserProfile::Request &req, kortex_driver::ReadUserProfile::Response &res) +{ + + + if (ReadUserProfileHandler) + { + res = ReadUserProfileHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_user_profile is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteUserProfile(kortex_driver::DeleteUserProfile::Request &req, kortex_driver::DeleteUserProfile::Response &res) +{ + + + if (DeleteUserProfileHandler) + { + res = DeleteUserProfileHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_user_profile is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllUserProfiles(kortex_driver::ReadAllUserProfiles::Request &req, kortex_driver::ReadAllUserProfiles::Response &res) +{ + + + if (ReadAllUserProfilesHandler) + { + res = ReadAllUserProfilesHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_user_profiles is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllUsers(kortex_driver::ReadAllUsers::Request &req, kortex_driver::ReadAllUsers::Response &res) +{ + + + if (ReadAllUsersHandler) + { + res = ReadAllUsersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_users is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ChangePassword(kortex_driver::ChangePassword::Request &req, kortex_driver::ChangePassword::Response &res) +{ + + + if (ChangePasswordHandler) + { + res = ChangePasswordHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/change_password is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::CreateSequence(kortex_driver::CreateSequence::Request &req, kortex_driver::CreateSequence::Response &res) +{ + + + if (CreateSequenceHandler) + { + res = CreateSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/create_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateSequence(kortex_driver::UpdateSequence::Request &req, kortex_driver::UpdateSequence::Response &res) +{ + + + if (UpdateSequenceHandler) + { + res = UpdateSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadSequence(kortex_driver::ReadSequence::Request &req, kortex_driver::ReadSequence::Response &res) +{ + + + if (ReadSequenceHandler) + { + res = ReadSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteSequence(kortex_driver::DeleteSequence::Request &req, kortex_driver::DeleteSequence::Response &res) +{ + + + if (DeleteSequenceHandler) + { + res = DeleteSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllSequences(kortex_driver::ReadAllSequences::Request &req, kortex_driver::ReadAllSequences::Response &res) +{ + + + if (ReadAllSequencesHandler) + { + res = ReadAllSequencesHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_sequences is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlaySequence(kortex_driver::PlaySequence::Request &req, kortex_driver::PlaySequence::Response &res) +{ + + + if (PlaySequenceHandler) + { + res = PlaySequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlayAdvancedSequence(kortex_driver::PlayAdvancedSequence::Request &req, kortex_driver::PlayAdvancedSequence::Response &res) +{ + + + if (PlayAdvancedSequenceHandler) + { + res = PlayAdvancedSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_advanced_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::StopSequence(kortex_driver::StopSequence::Request &req, kortex_driver::StopSequence::Response &res) +{ + + + if (StopSequenceHandler) + { + res = StopSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/stop_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PauseSequence(kortex_driver::PauseSequence::Request &req, kortex_driver::PauseSequence::Response &res) +{ + + + if (PauseSequenceHandler) + { + res = PauseSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/pause_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ResumeSequence(kortex_driver::ResumeSequence::Request &req, kortex_driver::ResumeSequence::Response &res) +{ + + + if (ResumeSequenceHandler) + { + res = ResumeSequenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/resume_sequence is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::CreateProtectionZone(kortex_driver::CreateProtectionZone::Request &req, kortex_driver::CreateProtectionZone::Response &res) +{ + + + if (CreateProtectionZoneHandler) + { + res = CreateProtectionZoneHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/create_protection_zone is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateProtectionZone(kortex_driver::UpdateProtectionZone::Request &req, kortex_driver::UpdateProtectionZone::Response &res) +{ + + + if (UpdateProtectionZoneHandler) + { + res = UpdateProtectionZoneHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_protection_zone is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadProtectionZone(kortex_driver::ReadProtectionZone::Request &req, kortex_driver::ReadProtectionZone::Response &res) +{ + + + if (ReadProtectionZoneHandler) + { + res = ReadProtectionZoneHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_protection_zone is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteProtectionZone(kortex_driver::DeleteProtectionZone::Request &req, kortex_driver::DeleteProtectionZone::Response &res) +{ + + + if (DeleteProtectionZoneHandler) + { + res = DeleteProtectionZoneHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_protection_zone is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllProtectionZones(kortex_driver::ReadAllProtectionZones::Request &req, kortex_driver::ReadAllProtectionZones::Response &res) +{ + + + if (ReadAllProtectionZonesHandler) + { + res = ReadAllProtectionZonesHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_protection_zones is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::CreateMapping(kortex_driver::CreateMapping::Request &req, kortex_driver::CreateMapping::Response &res) +{ + + + if (CreateMappingHandler) + { + res = CreateMappingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/create_mapping is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadMapping(kortex_driver::ReadMapping::Request &req, kortex_driver::ReadMapping::Response &res) +{ + + + if (ReadMappingHandler) + { + res = ReadMappingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_mapping is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateMapping(kortex_driver::UpdateMapping::Request &req, kortex_driver::UpdateMapping::Response &res) +{ + + + if (UpdateMappingHandler) + { + res = UpdateMappingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_mapping is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteMapping(kortex_driver::DeleteMapping::Request &req, kortex_driver::DeleteMapping::Response &res) +{ + + + if (DeleteMappingHandler) + { + res = DeleteMappingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_mapping is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllMappings(kortex_driver::ReadAllMappings::Request &req, kortex_driver::ReadAllMappings::Response &res) +{ + + + if (ReadAllMappingsHandler) + { + res = ReadAllMappingsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_mappings is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::CreateMap(kortex_driver::CreateMap::Request &req, kortex_driver::CreateMap::Response &res) +{ + + + if (CreateMapHandler) + { + res = CreateMapHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/create_map is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadMap(kortex_driver::ReadMap::Request &req, kortex_driver::ReadMap::Response &res) +{ + + + if (ReadMapHandler) + { + res = ReadMapHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_map is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateMap(kortex_driver::UpdateMap::Request &req, kortex_driver::UpdateMap::Response &res) +{ + + + if (UpdateMapHandler) + { + res = UpdateMapHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_map is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteMap(kortex_driver::DeleteMap::Request &req, kortex_driver::DeleteMap::Response &res) +{ + + + if (DeleteMapHandler) + { + res = DeleteMapHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_map is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllMaps(kortex_driver::ReadAllMaps::Request &req, kortex_driver::ReadAllMaps::Response &res) +{ + + + if (ReadAllMapsHandler) + { + res = ReadAllMapsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_maps is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ActivateMap(kortex_driver::ActivateMap::Request &req, kortex_driver::ActivateMap::Response &res) +{ + + + if (ActivateMapHandler) + { + res = ActivateMapHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_map is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::CreateAction(kortex_driver::CreateAction::Request &req, kortex_driver::CreateAction::Response &res) +{ + + + if (CreateActionHandler) + { + res = CreateActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/create_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAction(kortex_driver::ReadAction::Request &req, kortex_driver::ReadAction::Response &res) +{ + + + if (ReadActionHandler) + { + res = ReadActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllActions(kortex_driver::ReadAllActions::Request &req, kortex_driver::ReadAllActions::Response &res) +{ + + + if (ReadAllActionsHandler) + { + res = ReadAllActionsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_actions is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteAction(kortex_driver::DeleteAction::Request &req, kortex_driver::DeleteAction::Response &res) +{ + + + if (DeleteActionHandler) + { + res = DeleteActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateAction(kortex_driver::UpdateAction::Request &req, kortex_driver::UpdateAction::Response &res) +{ + + + if (UpdateActionHandler) + { + res = UpdateActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ExecuteActionFromReference(kortex_driver::ExecuteActionFromReference::Request &req, kortex_driver::ExecuteActionFromReference::Response &res) +{ + + + if (ExecuteActionFromReferenceHandler) + { + res = ExecuteActionFromReferenceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/execute_action_from_reference is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ExecuteAction(kortex_driver::ExecuteAction::Request &req, kortex_driver::ExecuteAction::Response &res) +{ + + + if (ExecuteActionHandler) + { + res = ExecuteActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/execute_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PauseAction(kortex_driver::PauseAction::Request &req, kortex_driver::PauseAction::Response &res) +{ + + + if (PauseActionHandler) + { + res = PauseActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/pause_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::StopAction(kortex_driver::StopAction::Request &req, kortex_driver::StopAction::Response &res) +{ + + + if (StopActionHandler) + { + res = StopActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/stop_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ResumeAction(kortex_driver::ResumeAction::Request &req, kortex_driver::ResumeAction::Response &res) +{ + + + if (ResumeActionHandler) + { + res = ResumeActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/resume_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetIPv4Configuration(kortex_driver::GetIPv4Configuration::Request &req, kortex_driver::GetIPv4Configuration::Response &res) +{ + + + if (GetIPv4ConfigurationHandler) + { + res = GetIPv4ConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_i_pv4_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetIPv4Configuration(kortex_driver::SetIPv4Configuration::Request &req, kortex_driver::SetIPv4Configuration::Response &res) +{ + + + if (SetIPv4ConfigurationHandler) + { + res = SetIPv4ConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_i_pv4_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetCommunicationInterfaceEnable(kortex_driver::SetCommunicationInterfaceEnable::Request &req, kortex_driver::SetCommunicationInterfaceEnable::Response &res) +{ + + + if (SetCommunicationInterfaceEnableHandler) + { + res = SetCommunicationInterfaceEnableHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_communication_interface_enable is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::IsCommunicationInterfaceEnable(kortex_driver::IsCommunicationInterfaceEnable::Request &req, kortex_driver::IsCommunicationInterfaceEnable::Response &res) +{ + + + if (IsCommunicationInterfaceEnableHandler) + { + res = IsCommunicationInterfaceEnableHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/is_communication_interface_enable is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAvailableWifi(kortex_driver::GetAvailableWifi::Request &req, kortex_driver::GetAvailableWifi::Response &res) +{ + + + if (GetAvailableWifiHandler) + { + res = GetAvailableWifiHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_available_wifi is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetWifiInformation(kortex_driver::GetWifiInformation::Request &req, kortex_driver::GetWifiInformation::Response &res) +{ + + + if (GetWifiInformationHandler) + { + res = GetWifiInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_wifi_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::AddWifiConfiguration(kortex_driver::AddWifiConfiguration::Request &req, kortex_driver::AddWifiConfiguration::Response &res) +{ + + + if (AddWifiConfigurationHandler) + { + res = AddWifiConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/add_wifi_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteWifiConfiguration(kortex_driver::DeleteWifiConfiguration::Request &req, kortex_driver::DeleteWifiConfiguration::Response &res) +{ + + + if (DeleteWifiConfigurationHandler) + { + res = DeleteWifiConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_wifi_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAllConfiguredWifis(kortex_driver::GetAllConfiguredWifis::Request &req, kortex_driver::GetAllConfiguredWifis::Response &res) +{ + + + if (GetAllConfiguredWifisHandler) + { + res = GetAllConfiguredWifisHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_configured_wifis is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ConnectWifi(kortex_driver::ConnectWifi::Request &req, kortex_driver::ConnectWifi::Response &res) +{ + + + if (ConnectWifiHandler) + { + res = ConnectWifiHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/connect_wifi is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DisconnectWifi(kortex_driver::DisconnectWifi::Request &req, kortex_driver::DisconnectWifi::Response &res) +{ + + + if (DisconnectWifiHandler) + { + res = DisconnectWifiHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/disconnect_wifi is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetConnectedWifiInformation(kortex_driver::GetConnectedWifiInformation::Request &req, kortex_driver::GetConnectedWifiInformation::Response &res) +{ + + + if (GetConnectedWifiInformationHandler) + { + res = GetConnectedWifiInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_connected_wifi_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::Base_Unsubscribe(kortex_driver::Base_Unsubscribe::Request &req, kortex_driver::Base_Unsubscribe::Response &res) +{ + + + if (Base_UnsubscribeHandler) + { + res = Base_UnsubscribeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/unsubscribe is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::OnNotificationConfigurationChangeTopic(kortex_driver::OnNotificationConfigurationChangeTopic::Request &req, kortex_driver::OnNotificationConfigurationChangeTopic::Response &res) +{ + + m_is_activated_ConfigurationChangeTopic = true; + + if (OnNotificationConfigurationChangeTopicHandler) + { + res = OnNotificationConfigurationChangeTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_configuration_change_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ConfigurationChangeTopic(Kinova::Api::Base::ConfigurationChangeNotification notif) +{ + kortex_driver::ConfigurationChangeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ConfigurationChangeTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationMappingInfoTopic(kortex_driver::OnNotificationMappingInfoTopic::Request &req, kortex_driver::OnNotificationMappingInfoTopic::Response &res) +{ + + m_is_activated_MappingInfoTopic = true; + + if (OnNotificationMappingInfoTopicHandler) + { + res = OnNotificationMappingInfoTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_mapping_info_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_MappingInfoTopic(Kinova::Api::Base::MappingInfoNotification notif) +{ + kortex_driver::MappingInfoNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_MappingInfoTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationControlModeTopic(kortex_driver::OnNotificationControlModeTopic::Request &req, kortex_driver::OnNotificationControlModeTopic::Response &res) +{ + + m_is_activated_ControlModeTopic = true; + + if (OnNotificationControlModeTopicHandler) + { + res = OnNotificationControlModeTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_control_mode_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ControlModeTopic(Kinova::Api::Base::ControlModeNotification notif) +{ + kortex_driver::ControlModeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ControlModeTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationOperatingModeTopic(kortex_driver::OnNotificationOperatingModeTopic::Request &req, kortex_driver::OnNotificationOperatingModeTopic::Response &res) +{ + + m_is_activated_OperatingModeTopic = true; + + if (OnNotificationOperatingModeTopicHandler) + { + res = OnNotificationOperatingModeTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_operating_mode_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_OperatingModeTopic(Kinova::Api::Base::OperatingModeNotification notif) +{ + kortex_driver::OperatingModeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_OperatingModeTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationSequenceInfoTopic(kortex_driver::OnNotificationSequenceInfoTopic::Request &req, kortex_driver::OnNotificationSequenceInfoTopic::Response &res) +{ + + m_is_activated_SequenceInfoTopic = true; + + if (OnNotificationSequenceInfoTopicHandler) + { + res = OnNotificationSequenceInfoTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_sequence_info_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_SequenceInfoTopic(Kinova::Api::Base::SequenceInfoNotification notif) +{ + kortex_driver::SequenceInfoNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_SequenceInfoTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationProtectionZoneTopic(kortex_driver::OnNotificationProtectionZoneTopic::Request &req, kortex_driver::OnNotificationProtectionZoneTopic::Response &res) +{ + + m_is_activated_ProtectionZoneTopic = true; + + if (OnNotificationProtectionZoneTopicHandler) + { + res = OnNotificationProtectionZoneTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_protection_zone_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ProtectionZoneTopic(Kinova::Api::Base::ProtectionZoneNotification notif) +{ + kortex_driver::ProtectionZoneNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ProtectionZoneTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationUserTopic(kortex_driver::OnNotificationUserTopic::Request &req, kortex_driver::OnNotificationUserTopic::Response &res) +{ + + m_is_activated_UserTopic = true; + + if (OnNotificationUserTopicHandler) + { + res = OnNotificationUserTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_user_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_UserTopic(Kinova::Api::Base::UserNotification notif) +{ + kortex_driver::UserNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_UserTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationControllerTopic(kortex_driver::OnNotificationControllerTopic::Request &req, kortex_driver::OnNotificationControllerTopic::Response &res) +{ + + m_is_activated_ControllerTopic = true; + + if (OnNotificationControllerTopicHandler) + { + res = OnNotificationControllerTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_controller_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ControllerTopic(Kinova::Api::Base::ControllerNotification notif) +{ + kortex_driver::ControllerNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ControllerTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationActionTopic(kortex_driver::OnNotificationActionTopic::Request &req, kortex_driver::OnNotificationActionTopic::Response &res) +{ + + m_is_activated_ActionTopic = true; + + if (OnNotificationActionTopicHandler) + { + res = OnNotificationActionTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_action_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ActionTopic(Kinova::Api::Base::ActionNotification notif) +{ + kortex_driver::ActionNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ActionTopic.publish(ros_msg); +} + +bool BaseSimulationServices::OnNotificationRobotEventTopic(kortex_driver::OnNotificationRobotEventTopic::Request &req, kortex_driver::OnNotificationRobotEventTopic::Response &res) +{ + + m_is_activated_RobotEventTopic = true; + + if (OnNotificationRobotEventTopicHandler) + { + res = OnNotificationRobotEventTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_robot_event_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_RobotEventTopic(Kinova::Api::Base::RobotEventNotification notif) +{ + kortex_driver::RobotEventNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_RobotEventTopic.publish(ros_msg); +} + +bool BaseSimulationServices::PlayCartesianTrajectory(kortex_driver::PlayCartesianTrajectory::Request &req, kortex_driver::PlayCartesianTrajectory::Response &res) +{ + + + if (PlayCartesianTrajectoryHandler) + { + res = PlayCartesianTrajectoryHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_cartesian_trajectory is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlayCartesianTrajectoryPosition(kortex_driver::PlayCartesianTrajectoryPosition::Request &req, kortex_driver::PlayCartesianTrajectoryPosition::Response &res) +{ + + + if (PlayCartesianTrajectoryPositionHandler) + { + res = PlayCartesianTrajectoryPositionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_cartesian_trajectory_position is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlayCartesianTrajectoryOrientation(kortex_driver::PlayCartesianTrajectoryOrientation::Request &req, kortex_driver::PlayCartesianTrajectoryOrientation::Response &res) +{ + + + if (PlayCartesianTrajectoryOrientationHandler) + { + res = PlayCartesianTrajectoryOrientationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_cartesian_trajectory_orientation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::Stop(kortex_driver::Stop::Request &req, kortex_driver::Stop::Response &res) +{ + + + if (StopHandler) + { + res = StopHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/stop is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetMeasuredCartesianPose(kortex_driver::GetMeasuredCartesianPose::Request &req, kortex_driver::GetMeasuredCartesianPose::Response &res) +{ + + + if (GetMeasuredCartesianPoseHandler) + { + res = GetMeasuredCartesianPoseHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_measured_cartesian_pose is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendWrenchCommand(kortex_driver::SendWrenchCommand::Request &req, kortex_driver::SendWrenchCommand::Response &res) +{ + + + if (SendWrenchCommandHandler) + { + res = SendWrenchCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_wrench_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendWrenchJoystickCommand(kortex_driver::SendWrenchJoystickCommand::Request &req, kortex_driver::SendWrenchJoystickCommand::Response &res) +{ + + + if (SendWrenchJoystickCommandHandler) + { + res = SendWrenchJoystickCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_wrench_joystick_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendTwistJoystickCommand(kortex_driver::SendTwistJoystickCommand::Request &req, kortex_driver::SendTwistJoystickCommand::Response &res) +{ + + + if (SendTwistJoystickCommandHandler) + { + res = SendTwistJoystickCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_twist_joystick_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendTwistCommand(kortex_driver::SendTwistCommand::Request &req, kortex_driver::SendTwistCommand::Response &res) +{ + + + if (SendTwistCommandHandler) + { + res = SendTwistCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_twist_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlayJointTrajectory(kortex_driver::PlayJointTrajectory::Request &req, kortex_driver::PlayJointTrajectory::Response &res) +{ + + + if (PlayJointTrajectoryHandler) + { + res = PlayJointTrajectoryHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_joint_trajectory is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlaySelectedJointTrajectory(kortex_driver::PlaySelectedJointTrajectory::Request &req, kortex_driver::PlaySelectedJointTrajectory::Response &res) +{ + + + if (PlaySelectedJointTrajectoryHandler) + { + res = PlaySelectedJointTrajectoryHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_selected_joint_trajectory is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetMeasuredJointAngles(kortex_driver::GetMeasuredJointAngles::Request &req, kortex_driver::GetMeasuredJointAngles::Response &res) +{ + + + if (GetMeasuredJointAnglesHandler) + { + res = GetMeasuredJointAnglesHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_measured_joint_angles is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendJointSpeedsCommand(kortex_driver::SendJointSpeedsCommand::Request &req, kortex_driver::SendJointSpeedsCommand::Response &res) +{ + + + if (SendJointSpeedsCommandHandler) + { + res = SendJointSpeedsCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_joint_speeds_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendSelectedJointSpeedCommand(kortex_driver::SendSelectedJointSpeedCommand::Request &req, kortex_driver::SendSelectedJointSpeedCommand::Response &res) +{ + + + if (SendSelectedJointSpeedCommandHandler) + { + res = SendSelectedJointSpeedCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_selected_joint_speed_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendGripperCommand(kortex_driver::SendGripperCommand::Request &req, kortex_driver::SendGripperCommand::Response &res) +{ + + + if (SendGripperCommandHandler) + { + res = SendGripperCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_gripper_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetMeasuredGripperMovement(kortex_driver::GetMeasuredGripperMovement::Request &req, kortex_driver::GetMeasuredGripperMovement::Response &res) +{ + + + if (GetMeasuredGripperMovementHandler) + { + res = GetMeasuredGripperMovementHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_measured_gripper_movement is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetAdmittance(kortex_driver::SetAdmittance::Request &req, kortex_driver::SetAdmittance::Response &res) +{ + + + if (SetAdmittanceHandler) + { + res = SetAdmittanceHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_admittance is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetOperatingMode(kortex_driver::SetOperatingMode::Request &req, kortex_driver::SetOperatingMode::Response &res) +{ + + + if (SetOperatingModeHandler) + { + res = SetOperatingModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_operating_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ApplyEmergencyStop(kortex_driver::ApplyEmergencyStop::Request &req, kortex_driver::ApplyEmergencyStop::Response &res) +{ + + + if (ApplyEmergencyStopHandler) + { + res = ApplyEmergencyStopHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/apply_emergency_stop is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::Base_ClearFaults(kortex_driver::Base_ClearFaults::Request &req, kortex_driver::Base_ClearFaults::Response &res) +{ + + + if (Base_ClearFaultsHandler) + { + res = Base_ClearFaultsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/clear_faults is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::Base_GetControlMode(kortex_driver::Base_GetControlMode::Request &req, kortex_driver::Base_GetControlMode::Response &res) +{ + + + if (Base_GetControlModeHandler) + { + res = Base_GetControlModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_control_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetOperatingMode(kortex_driver::GetOperatingMode::Request &req, kortex_driver::GetOperatingMode::Response &res) +{ + + + if (GetOperatingModeHandler) + { + res = GetOperatingModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_operating_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetServoingMode(kortex_driver::SetServoingMode::Request &req, kortex_driver::SetServoingMode::Response &res) +{ + + + if (SetServoingModeHandler) + { + res = SetServoingModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_servoing_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetServoingMode(kortex_driver::GetServoingMode::Request &req, kortex_driver::GetServoingMode::Response &res) +{ + + + if (GetServoingModeHandler) + { + res = GetServoingModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_servoing_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::OnNotificationServoingModeTopic(kortex_driver::OnNotificationServoingModeTopic::Request &req, kortex_driver::OnNotificationServoingModeTopic::Response &res) +{ + + m_is_activated_ServoingModeTopic = true; + + if (OnNotificationServoingModeTopicHandler) + { + res = OnNotificationServoingModeTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_servoing_mode_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ServoingModeTopic(Kinova::Api::Base::ServoingModeNotification notif) +{ + kortex_driver::ServoingModeNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ServoingModeTopic.publish(ros_msg); +} + +bool BaseSimulationServices::RestoreFactorySettings(kortex_driver::RestoreFactorySettings::Request &req, kortex_driver::RestoreFactorySettings::Response &res) +{ + + + if (RestoreFactorySettingsHandler) + { + res = RestoreFactorySettingsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/restore_factory_settings is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::OnNotificationFactoryTopic(kortex_driver::OnNotificationFactoryTopic::Request &req, kortex_driver::OnNotificationFactoryTopic::Response &res) +{ + + m_is_activated_FactoryTopic = true; + + if (OnNotificationFactoryTopicHandler) + { + res = OnNotificationFactoryTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_factory_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_FactoryTopic(Kinova::Api::Base::FactoryNotification notif) +{ + kortex_driver::FactoryNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_FactoryTopic.publish(ros_msg); +} + +bool BaseSimulationServices::GetAllConnectedControllers(kortex_driver::GetAllConnectedControllers::Request &req, kortex_driver::GetAllConnectedControllers::Response &res) +{ + + + if (GetAllConnectedControllersHandler) + { + res = GetAllConnectedControllersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_connected_controllers is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetControllerState(kortex_driver::GetControllerState::Request &req, kortex_driver::GetControllerState::Response &res) +{ + + + if (GetControllerStateHandler) + { + res = GetControllerStateHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_controller_state is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetActuatorCount(kortex_driver::GetActuatorCount::Request &req, kortex_driver::GetActuatorCount::Response &res) +{ + + + if (GetActuatorCountHandler) + { + res = GetActuatorCountHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_actuator_count is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::StartWifiScan(kortex_driver::StartWifiScan::Request &req, kortex_driver::StartWifiScan::Response &res) +{ + + + if (StartWifiScanHandler) + { + res = StartWifiScanHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/start_wifi_scan is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetConfiguredWifi(kortex_driver::GetConfiguredWifi::Request &req, kortex_driver::GetConfiguredWifi::Response &res) +{ + + + if (GetConfiguredWifiHandler) + { + res = GetConfiguredWifiHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_configured_wifi is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::OnNotificationNetworkTopic(kortex_driver::OnNotificationNetworkTopic::Request &req, kortex_driver::OnNotificationNetworkTopic::Response &res) +{ + + m_is_activated_NetworkTopic = true; + + if (OnNotificationNetworkTopicHandler) + { + res = OnNotificationNetworkTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_network_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_NetworkTopic(Kinova::Api::Base::NetworkNotification notif) +{ + kortex_driver::NetworkNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_NetworkTopic.publish(ros_msg); +} + +bool BaseSimulationServices::GetArmState(kortex_driver::GetArmState::Request &req, kortex_driver::GetArmState::Response &res) +{ + + + if (GetArmStateHandler) + { + res = GetArmStateHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_arm_state is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::OnNotificationArmStateTopic(kortex_driver::OnNotificationArmStateTopic::Request &req, kortex_driver::OnNotificationArmStateTopic::Response &res) +{ + + m_is_activated_ArmStateTopic = true; + + if (OnNotificationArmStateTopicHandler) + { + res = OnNotificationArmStateTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/activate_publishing_of_arm_state_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void BaseSimulationServices::cb_ArmStateTopic(Kinova::Api::Base::ArmStateNotification notif) +{ + kortex_driver::ArmStateNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ArmStateTopic.publish(ros_msg); +} + +bool BaseSimulationServices::GetIPv4Information(kortex_driver::GetIPv4Information::Request &req, kortex_driver::GetIPv4Information::Response &res) +{ + + + if (GetIPv4InformationHandler) + { + res = GetIPv4InformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_i_pv4_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetWifiCountryCode(kortex_driver::SetWifiCountryCode::Request &req, kortex_driver::SetWifiCountryCode::Response &res) +{ + + + if (SetWifiCountryCodeHandler) + { + res = SetWifiCountryCodeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_wifi_country_code is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetWifiCountryCode(kortex_driver::GetWifiCountryCode::Request &req, kortex_driver::GetWifiCountryCode::Response &res) +{ + + + if (GetWifiCountryCodeHandler) + { + res = GetWifiCountryCodeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_wifi_country_code is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::Base_SetCapSenseConfig(kortex_driver::Base_SetCapSenseConfig::Request &req, kortex_driver::Base_SetCapSenseConfig::Response &res) +{ + + + if (Base_SetCapSenseConfigHandler) + { + res = Base_SetCapSenseConfigHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_cap_sense_config is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::Base_GetCapSenseConfig(kortex_driver::Base_GetCapSenseConfig::Request &req, kortex_driver::Base_GetCapSenseConfig::Response &res) +{ + + + if (Base_GetCapSenseConfigHandler) + { + res = Base_GetCapSenseConfigHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_cap_sense_config is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAllJointsSpeedHardLimitation(kortex_driver::GetAllJointsSpeedHardLimitation::Request &req, kortex_driver::GetAllJointsSpeedHardLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_speed_hard_limitation service is now deprecated and will be removed in a future release."); + + + if (GetAllJointsSpeedHardLimitationHandler) + { + res = GetAllJointsSpeedHardLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_joints_speed_hard_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAllJointsTorqueHardLimitation(kortex_driver::GetAllJointsTorqueHardLimitation::Request &req, kortex_driver::GetAllJointsTorqueHardLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_torque_hard_limitation service is now deprecated and will be removed in a future release."); + + + if (GetAllJointsTorqueHardLimitationHandler) + { + res = GetAllJointsTorqueHardLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_joints_torque_hard_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetTwistHardLimitation(kortex_driver::GetTwistHardLimitation::Request &req, kortex_driver::GetTwistHardLimitation::Response &res) +{ + ROS_WARN("The base/get_twist_hard_limitation service is now deprecated and will be removed in a future release."); + + + if (GetTwistHardLimitationHandler) + { + res = GetTwistHardLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_twist_hard_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetWrenchHardLimitation(kortex_driver::GetWrenchHardLimitation::Request &req, kortex_driver::GetWrenchHardLimitation::Response &res) +{ + ROS_WARN("The base/get_wrench_hard_limitation service is now deprecated and will be removed in a future release."); + + + if (GetWrenchHardLimitationHandler) + { + res = GetWrenchHardLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_wrench_hard_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendJointSpeedsJoystickCommand(kortex_driver::SendJointSpeedsJoystickCommand::Request &req, kortex_driver::SendJointSpeedsJoystickCommand::Response &res) +{ + + + if (SendJointSpeedsJoystickCommandHandler) + { + res = SendJointSpeedsJoystickCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_joint_speeds_joystick_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SendSelectedJointSpeedJoystickCommand(kortex_driver::SendSelectedJointSpeedJoystickCommand::Request &req, kortex_driver::SendSelectedJointSpeedJoystickCommand::Response &res) +{ + + + if (SendSelectedJointSpeedJoystickCommandHandler) + { + res = SendSelectedJointSpeedJoystickCommandHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/send_selected_joint_speed_joystick_command is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::EnableBridge(kortex_driver::EnableBridge::Request &req, kortex_driver::EnableBridge::Response &res) +{ + + + if (EnableBridgeHandler) + { + res = EnableBridgeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/enable_bridge is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DisableBridge(kortex_driver::DisableBridge::Request &req, kortex_driver::DisableBridge::Response &res) +{ + + + if (DisableBridgeHandler) + { + res = DisableBridgeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/disable_bridge is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetBridgeList(kortex_driver::GetBridgeList::Request &req, kortex_driver::GetBridgeList::Response &res) +{ + + + if (GetBridgeListHandler) + { + res = GetBridgeListHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_bridge_list is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetBridgeConfig(kortex_driver::GetBridgeConfig::Request &req, kortex_driver::GetBridgeConfig::Response &res) +{ + + + if (GetBridgeConfigHandler) + { + res = GetBridgeConfigHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_bridge_config is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::PlayPreComputedJointTrajectory(kortex_driver::PlayPreComputedJointTrajectory::Request &req, kortex_driver::PlayPreComputedJointTrajectory::Response &res) +{ + + + if (PlayPreComputedJointTrajectoryHandler) + { + res = PlayPreComputedJointTrajectoryHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/play_pre_computed_joint_trajectory is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetProductConfiguration(kortex_driver::GetProductConfiguration::Request &req, kortex_driver::GetProductConfiguration::Response &res) +{ + + + if (GetProductConfigurationHandler) + { + res = GetProductConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_product_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateEndEffectorTypeConfiguration(kortex_driver::UpdateEndEffectorTypeConfiguration::Request &req, kortex_driver::UpdateEndEffectorTypeConfiguration::Response &res) +{ + + + if (UpdateEndEffectorTypeConfigurationHandler) + { + res = UpdateEndEffectorTypeConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_end_effector_type_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::RestoreFactoryProductConfiguration(kortex_driver::RestoreFactoryProductConfiguration::Request &req, kortex_driver::RestoreFactoryProductConfiguration::Response &res) +{ + + + if (RestoreFactoryProductConfigurationHandler) + { + res = RestoreFactoryProductConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/restore_factory_product_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetTrajectoryErrorReport(kortex_driver::GetTrajectoryErrorReport::Request &req, kortex_driver::GetTrajectoryErrorReport::Response &res) +{ + + + if (GetTrajectoryErrorReportHandler) + { + res = GetTrajectoryErrorReportHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_trajectory_error_report is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAllJointsSpeedSoftLimitation(kortex_driver::GetAllJointsSpeedSoftLimitation::Request &req, kortex_driver::GetAllJointsSpeedSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_speed_soft_limitation service is now deprecated and will be removed in a future release."); + + + if (GetAllJointsSpeedSoftLimitationHandler) + { + res = GetAllJointsSpeedSoftLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_joints_speed_soft_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAllJointsTorqueSoftLimitation(kortex_driver::GetAllJointsTorqueSoftLimitation::Request &req, kortex_driver::GetAllJointsTorqueSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_all_joints_torque_soft_limitation service is now deprecated and will be removed in a future release."); + + + if (GetAllJointsTorqueSoftLimitationHandler) + { + res = GetAllJointsTorqueSoftLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_joints_torque_soft_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetTwistSoftLimitation(kortex_driver::GetTwistSoftLimitation::Request &req, kortex_driver::GetTwistSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_twist_soft_limitation service is now deprecated and will be removed in a future release."); + + + if (GetTwistSoftLimitationHandler) + { + res = GetTwistSoftLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_twist_soft_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetWrenchSoftLimitation(kortex_driver::GetWrenchSoftLimitation::Request &req, kortex_driver::GetWrenchSoftLimitation::Response &res) +{ + ROS_WARN("The base/get_wrench_soft_limitation service is now deprecated and will be removed in a future release."); + + + if (GetWrenchSoftLimitationHandler) + { + res = GetWrenchSoftLimitationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_wrench_soft_limitation is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetControllerConfigurationMode(kortex_driver::SetControllerConfigurationMode::Request &req, kortex_driver::SetControllerConfigurationMode::Response &res) +{ + + + if (SetControllerConfigurationModeHandler) + { + res = SetControllerConfigurationModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_controller_configuration_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetControllerConfigurationMode(kortex_driver::GetControllerConfigurationMode::Request &req, kortex_driver::GetControllerConfigurationMode::Response &res) +{ + + + if (GetControllerConfigurationModeHandler) + { + res = GetControllerConfigurationModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_controller_configuration_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::StartTeaching(kortex_driver::StartTeaching::Request &req, kortex_driver::StartTeaching::Response &res) +{ + + + if (StartTeachingHandler) + { + res = StartTeachingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/start_teaching is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::StopTeaching(kortex_driver::StopTeaching::Request &req, kortex_driver::StopTeaching::Response &res) +{ + + + if (StopTeachingHandler) + { + res = StopTeachingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/stop_teaching is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::AddSequenceTasks(kortex_driver::AddSequenceTasks::Request &req, kortex_driver::AddSequenceTasks::Response &res) +{ + + + if (AddSequenceTasksHandler) + { + res = AddSequenceTasksHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/add_sequence_tasks is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::UpdateSequenceTask(kortex_driver::UpdateSequenceTask::Request &req, kortex_driver::UpdateSequenceTask::Response &res) +{ + + + if (UpdateSequenceTaskHandler) + { + res = UpdateSequenceTaskHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/update_sequence_task is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SwapSequenceTasks(kortex_driver::SwapSequenceTasks::Request &req, kortex_driver::SwapSequenceTasks::Response &res) +{ + + + if (SwapSequenceTasksHandler) + { + res = SwapSequenceTasksHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/swap_sequence_tasks is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadSequenceTask(kortex_driver::ReadSequenceTask::Request &req, kortex_driver::ReadSequenceTask::Response &res) +{ + + + if (ReadSequenceTaskHandler) + { + res = ReadSequenceTaskHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_sequence_task is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::ReadAllSequenceTasks(kortex_driver::ReadAllSequenceTasks::Request &req, kortex_driver::ReadAllSequenceTasks::Response &res) +{ + + + if (ReadAllSequenceTasksHandler) + { + res = ReadAllSequenceTasksHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/read_all_sequence_tasks is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteSequenceTask(kortex_driver::DeleteSequenceTask::Request &req, kortex_driver::DeleteSequenceTask::Response &res) +{ + + + if (DeleteSequenceTaskHandler) + { + res = DeleteSequenceTaskHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_sequence_task is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DeleteAllSequenceTasks(kortex_driver::DeleteAllSequenceTasks::Request &req, kortex_driver::DeleteAllSequenceTasks::Response &res) +{ + + + if (DeleteAllSequenceTasksHandler) + { + res = DeleteAllSequenceTasksHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/delete_all_sequence_tasks is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::TakeSnapshot(kortex_driver::TakeSnapshot::Request &req, kortex_driver::TakeSnapshot::Response &res) +{ + + + if (TakeSnapshotHandler) + { + res = TakeSnapshotHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/take_snapshot is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetFirmwareBundleVersions(kortex_driver::GetFirmwareBundleVersions::Request &req, kortex_driver::GetFirmwareBundleVersions::Response &res) +{ + + + if (GetFirmwareBundleVersionsHandler) + { + res = GetFirmwareBundleVersionsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_firmware_bundle_versions is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::MoveSequenceTask(kortex_driver::MoveSequenceTask::Request &req, kortex_driver::MoveSequenceTask::Response &res) +{ + + + if (MoveSequenceTaskHandler) + { + res = MoveSequenceTaskHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/move_sequence_task is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DuplicateMapping(kortex_driver::DuplicateMapping::Request &req, kortex_driver::DuplicateMapping::Response &res) +{ + + + if (DuplicateMappingHandler) + { + res = DuplicateMappingHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/duplicate_mapping is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::DuplicateMap(kortex_driver::DuplicateMap::Request &req, kortex_driver::DuplicateMap::Response &res) +{ + + + if (DuplicateMapHandler) + { + res = DuplicateMapHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/duplicate_map is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::SetControllerConfiguration(kortex_driver::SetControllerConfiguration::Request &req, kortex_driver::SetControllerConfiguration::Response &res) +{ + + + if (SetControllerConfigurationHandler) + { + res = SetControllerConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/set_controller_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetControllerConfiguration(kortex_driver::GetControllerConfiguration::Request &req, kortex_driver::GetControllerConfiguration::Response &res) +{ + + + if (GetControllerConfigurationHandler) + { + res = GetControllerConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_controller_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool BaseSimulationServices::GetAllControllerConfigurations(kortex_driver::GetAllControllerConfigurations::Request &req, kortex_driver::GetAllControllerConfigurations::Response &res) +{ + + + if (GetAllControllerConfigurationsHandler) + { + res = GetAllControllerConfigurationsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for base/get_all_controller_configurations is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/controlconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/controlconfig_services.cpp new file mode 100644 index 0000000..1dfd266 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/controlconfig_services.cpp @@ -0,0 +1,539 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/controlconfig_services.h" + +ControlConfigSimulationServices::ControlConfigSimulationServices(ros::NodeHandle& node_handle): + IControlConfigServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_ControlConfigurationTopic = m_node_handle.advertise("control_configuration_topic", 1000); + m_is_activated_ControlConfigurationTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("control_config/set_device_id", &ControlConfigSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("control_config/set_api_options", &ControlConfigSimulationServices::SetApiOptions, this); + + m_serviceSetGravityVector = m_node_handle.advertiseService("control_config/set_gravity_vector", &ControlConfigSimulationServices::SetGravityVector, this); + m_serviceGetGravityVector = m_node_handle.advertiseService("control_config/get_gravity_vector", &ControlConfigSimulationServices::GetGravityVector, this); + m_serviceSetPayloadInformation = m_node_handle.advertiseService("control_config/set_payload_information", &ControlConfigSimulationServices::SetPayloadInformation, this); + m_serviceGetPayloadInformation = m_node_handle.advertiseService("control_config/get_payload_information", &ControlConfigSimulationServices::GetPayloadInformation, this); + m_serviceSetToolConfiguration = m_node_handle.advertiseService("control_config/set_tool_configuration", &ControlConfigSimulationServices::SetToolConfiguration, this); + m_serviceGetToolConfiguration = m_node_handle.advertiseService("control_config/get_tool_configuration", &ControlConfigSimulationServices::GetToolConfiguration, this); + m_serviceOnNotificationControlConfigurationTopic = m_node_handle.advertiseService("control_config/activate_publishing_of_control_configuration_topic", &ControlConfigSimulationServices::OnNotificationControlConfigurationTopic, this); + m_serviceControlConfig_Unsubscribe = m_node_handle.advertiseService("control_config/unsubscribe", &ControlConfigSimulationServices::ControlConfig_Unsubscribe, this); + m_serviceSetCartesianReferenceFrame = m_node_handle.advertiseService("control_config/set_cartesian_reference_frame", &ControlConfigSimulationServices::SetCartesianReferenceFrame, this); + m_serviceGetCartesianReferenceFrame = m_node_handle.advertiseService("control_config/get_cartesian_reference_frame", &ControlConfigSimulationServices::GetCartesianReferenceFrame, this); + m_serviceControlConfig_GetControlMode = m_node_handle.advertiseService("control_config/get_control_mode", &ControlConfigSimulationServices::ControlConfig_GetControlMode, this); + m_serviceSetJointSpeedSoftLimits = m_node_handle.advertiseService("control_config/set_joint_speed_soft_limits", &ControlConfigSimulationServices::SetJointSpeedSoftLimits, this); + m_serviceSetTwistLinearSoftLimit = m_node_handle.advertiseService("control_config/set_twist_linear_soft_limit", &ControlConfigSimulationServices::SetTwistLinearSoftLimit, this); + m_serviceSetTwistAngularSoftLimit = m_node_handle.advertiseService("control_config/set_twist_angular_soft_limit", &ControlConfigSimulationServices::SetTwistAngularSoftLimit, this); + m_serviceSetJointAccelerationSoftLimits = m_node_handle.advertiseService("control_config/set_joint_acceleration_soft_limits", &ControlConfigSimulationServices::SetJointAccelerationSoftLimits, this); + m_serviceGetKinematicHardLimits = m_node_handle.advertiseService("control_config/get_kinematic_hard_limits", &ControlConfigSimulationServices::GetKinematicHardLimits, this); + m_serviceGetKinematicSoftLimits = m_node_handle.advertiseService("control_config/get_kinematic_soft_limits", &ControlConfigSimulationServices::GetKinematicSoftLimits, this); + m_serviceGetAllKinematicSoftLimits = m_node_handle.advertiseService("control_config/get_all_kinematic_soft_limits", &ControlConfigSimulationServices::GetAllKinematicSoftLimits, this); + m_serviceSetDesiredLinearTwist = m_node_handle.advertiseService("control_config/set_desired_linear_twist", &ControlConfigSimulationServices::SetDesiredLinearTwist, this); + m_serviceSetDesiredAngularTwist = m_node_handle.advertiseService("control_config/set_desired_angular_twist", &ControlConfigSimulationServices::SetDesiredAngularTwist, this); + m_serviceSetDesiredJointSpeeds = m_node_handle.advertiseService("control_config/set_desired_joint_speeds", &ControlConfigSimulationServices::SetDesiredJointSpeeds, this); + m_serviceGetDesiredSpeeds = m_node_handle.advertiseService("control_config/get_desired_speeds", &ControlConfigSimulationServices::GetDesiredSpeeds, this); + m_serviceResetGravityVector = m_node_handle.advertiseService("control_config/reset_gravity_vector", &ControlConfigSimulationServices::ResetGravityVector, this); + m_serviceResetPayloadInformation = m_node_handle.advertiseService("control_config/reset_payload_information", &ControlConfigSimulationServices::ResetPayloadInformation, this); + m_serviceResetToolConfiguration = m_node_handle.advertiseService("control_config/reset_tool_configuration", &ControlConfigSimulationServices::ResetToolConfiguration, this); + m_serviceResetJointSpeedSoftLimits = m_node_handle.advertiseService("control_config/reset_joint_speed_soft_limits", &ControlConfigSimulationServices::ResetJointSpeedSoftLimits, this); + m_serviceResetTwistLinearSoftLimit = m_node_handle.advertiseService("control_config/reset_twist_linear_soft_limit", &ControlConfigSimulationServices::ResetTwistLinearSoftLimit, this); + m_serviceResetTwistAngularSoftLimit = m_node_handle.advertiseService("control_config/reset_twist_angular_soft_limit", &ControlConfigSimulationServices::ResetTwistAngularSoftLimit, this); + m_serviceResetJointAccelerationSoftLimits = m_node_handle.advertiseService("control_config/reset_joint_acceleration_soft_limits", &ControlConfigSimulationServices::ResetJointAccelerationSoftLimits, this); +} + +bool ControlConfigSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool ControlConfigSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool ControlConfigSimulationServices::SetGravityVector(kortex_driver::SetGravityVector::Request &req, kortex_driver::SetGravityVector::Response &res) +{ + + + if (SetGravityVectorHandler) + { + res = SetGravityVectorHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_gravity_vector is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetGravityVector(kortex_driver::GetGravityVector::Request &req, kortex_driver::GetGravityVector::Response &res) +{ + + + if (GetGravityVectorHandler) + { + res = GetGravityVectorHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_gravity_vector is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetPayloadInformation(kortex_driver::SetPayloadInformation::Request &req, kortex_driver::SetPayloadInformation::Response &res) +{ + + + if (SetPayloadInformationHandler) + { + res = SetPayloadInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_payload_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetPayloadInformation(kortex_driver::GetPayloadInformation::Request &req, kortex_driver::GetPayloadInformation::Response &res) +{ + + + if (GetPayloadInformationHandler) + { + res = GetPayloadInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_payload_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetToolConfiguration(kortex_driver::SetToolConfiguration::Request &req, kortex_driver::SetToolConfiguration::Response &res) +{ + + + if (SetToolConfigurationHandler) + { + res = SetToolConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_tool_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetToolConfiguration(kortex_driver::GetToolConfiguration::Request &req, kortex_driver::GetToolConfiguration::Response &res) +{ + + + if (GetToolConfigurationHandler) + { + res = GetToolConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_tool_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::OnNotificationControlConfigurationTopic(kortex_driver::OnNotificationControlConfigurationTopic::Request &req, kortex_driver::OnNotificationControlConfigurationTopic::Response &res) +{ + + m_is_activated_ControlConfigurationTopic = true; + + if (OnNotificationControlConfigurationTopicHandler) + { + res = OnNotificationControlConfigurationTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/activate_publishing_of_control_configuration_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void ControlConfigSimulationServices::cb_ControlConfigurationTopic(Kinova::Api::ControlConfig::ControlConfigurationNotification notif) +{ + kortex_driver::ControlConfigurationNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_ControlConfigurationTopic.publish(ros_msg); +} + +bool ControlConfigSimulationServices::ControlConfig_Unsubscribe(kortex_driver::ControlConfig_Unsubscribe::Request &req, kortex_driver::ControlConfig_Unsubscribe::Response &res) +{ + + + if (ControlConfig_UnsubscribeHandler) + { + res = ControlConfig_UnsubscribeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/unsubscribe is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetCartesianReferenceFrame(kortex_driver::SetCartesianReferenceFrame::Request &req, kortex_driver::SetCartesianReferenceFrame::Response &res) +{ + + + if (SetCartesianReferenceFrameHandler) + { + res = SetCartesianReferenceFrameHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_cartesian_reference_frame is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetCartesianReferenceFrame(kortex_driver::GetCartesianReferenceFrame::Request &req, kortex_driver::GetCartesianReferenceFrame::Response &res) +{ + + + if (GetCartesianReferenceFrameHandler) + { + res = GetCartesianReferenceFrameHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_cartesian_reference_frame is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ControlConfig_GetControlMode(kortex_driver::ControlConfig_GetControlMode::Request &req, kortex_driver::ControlConfig_GetControlMode::Response &res) +{ + + + if (ControlConfig_GetControlModeHandler) + { + res = ControlConfig_GetControlModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_control_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetJointSpeedSoftLimits(kortex_driver::SetJointSpeedSoftLimits::Request &req, kortex_driver::SetJointSpeedSoftLimits::Response &res) +{ + + + if (SetJointSpeedSoftLimitsHandler) + { + res = SetJointSpeedSoftLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_joint_speed_soft_limits is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetTwistLinearSoftLimit(kortex_driver::SetTwistLinearSoftLimit::Request &req, kortex_driver::SetTwistLinearSoftLimit::Response &res) +{ + + + if (SetTwistLinearSoftLimitHandler) + { + res = SetTwistLinearSoftLimitHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_twist_linear_soft_limit is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetTwistAngularSoftLimit(kortex_driver::SetTwistAngularSoftLimit::Request &req, kortex_driver::SetTwistAngularSoftLimit::Response &res) +{ + + + if (SetTwistAngularSoftLimitHandler) + { + res = SetTwistAngularSoftLimitHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_twist_angular_soft_limit is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetJointAccelerationSoftLimits(kortex_driver::SetJointAccelerationSoftLimits::Request &req, kortex_driver::SetJointAccelerationSoftLimits::Response &res) +{ + + + if (SetJointAccelerationSoftLimitsHandler) + { + res = SetJointAccelerationSoftLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_joint_acceleration_soft_limits is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetKinematicHardLimits(kortex_driver::GetKinematicHardLimits::Request &req, kortex_driver::GetKinematicHardLimits::Response &res) +{ + + + if (GetKinematicHardLimitsHandler) + { + res = GetKinematicHardLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_kinematic_hard_limits is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetKinematicSoftLimits(kortex_driver::GetKinematicSoftLimits::Request &req, kortex_driver::GetKinematicSoftLimits::Response &res) +{ + + + if (GetKinematicSoftLimitsHandler) + { + res = GetKinematicSoftLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_kinematic_soft_limits is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetAllKinematicSoftLimits(kortex_driver::GetAllKinematicSoftLimits::Request &req, kortex_driver::GetAllKinematicSoftLimits::Response &res) +{ + + + if (GetAllKinematicSoftLimitsHandler) + { + res = GetAllKinematicSoftLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_all_kinematic_soft_limits is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetDesiredLinearTwist(kortex_driver::SetDesiredLinearTwist::Request &req, kortex_driver::SetDesiredLinearTwist::Response &res) +{ + + + if (SetDesiredLinearTwistHandler) + { + res = SetDesiredLinearTwistHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_desired_linear_twist is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetDesiredAngularTwist(kortex_driver::SetDesiredAngularTwist::Request &req, kortex_driver::SetDesiredAngularTwist::Response &res) +{ + + + if (SetDesiredAngularTwistHandler) + { + res = SetDesiredAngularTwistHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_desired_angular_twist is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::SetDesiredJointSpeeds(kortex_driver::SetDesiredJointSpeeds::Request &req, kortex_driver::SetDesiredJointSpeeds::Response &res) +{ + + + if (SetDesiredJointSpeedsHandler) + { + res = SetDesiredJointSpeedsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/set_desired_joint_speeds is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::GetDesiredSpeeds(kortex_driver::GetDesiredSpeeds::Request &req, kortex_driver::GetDesiredSpeeds::Response &res) +{ + + + if (GetDesiredSpeedsHandler) + { + res = GetDesiredSpeedsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/get_desired_speeds is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetGravityVector(kortex_driver::ResetGravityVector::Request &req, kortex_driver::ResetGravityVector::Response &res) +{ + + + if (ResetGravityVectorHandler) + { + res = ResetGravityVectorHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_gravity_vector is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetPayloadInformation(kortex_driver::ResetPayloadInformation::Request &req, kortex_driver::ResetPayloadInformation::Response &res) +{ + + + if (ResetPayloadInformationHandler) + { + res = ResetPayloadInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_payload_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetToolConfiguration(kortex_driver::ResetToolConfiguration::Request &req, kortex_driver::ResetToolConfiguration::Response &res) +{ + + + if (ResetToolConfigurationHandler) + { + res = ResetToolConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_tool_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetJointSpeedSoftLimits(kortex_driver::ResetJointSpeedSoftLimits::Request &req, kortex_driver::ResetJointSpeedSoftLimits::Response &res) +{ + + + if (ResetJointSpeedSoftLimitsHandler) + { + res = ResetJointSpeedSoftLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_joint_speed_soft_limits is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetTwistLinearSoftLimit(kortex_driver::ResetTwistLinearSoftLimit::Request &req, kortex_driver::ResetTwistLinearSoftLimit::Response &res) +{ + + + if (ResetTwistLinearSoftLimitHandler) + { + res = ResetTwistLinearSoftLimitHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_twist_linear_soft_limit is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetTwistAngularSoftLimit(kortex_driver::ResetTwistAngularSoftLimit::Request &req, kortex_driver::ResetTwistAngularSoftLimit::Response &res) +{ + + + if (ResetTwistAngularSoftLimitHandler) + { + res = ResetTwistAngularSoftLimitHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_twist_angular_soft_limit is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool ControlConfigSimulationServices::ResetJointAccelerationSoftLimits(kortex_driver::ResetJointAccelerationSoftLimits::Request &req, kortex_driver::ResetJointAccelerationSoftLimits::Response &res) +{ + + + if (ResetJointAccelerationSoftLimitsHandler) + { + res = ResetJointAccelerationSoftLimitsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for control_config/reset_joint_acceleration_soft_limits is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/deviceconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/deviceconfig_services.cpp new file mode 100644 index 0000000..0f17821 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/deviceconfig_services.cpp @@ -0,0 +1,587 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/deviceconfig_services.h" + +DeviceConfigSimulationServices::DeviceConfigSimulationServices(ros::NodeHandle& node_handle): + IDeviceConfigServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_SafetyTopic = m_node_handle.advertise("safety_topic", 1000); + m_is_activated_SafetyTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("device_config/set_device_id", &DeviceConfigSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("device_config/set_api_options", &DeviceConfigSimulationServices::SetApiOptions, this); + + m_serviceGetRunMode = m_node_handle.advertiseService("device_config/get_run_mode", &DeviceConfigSimulationServices::GetRunMode, this); + m_serviceSetRunMode = m_node_handle.advertiseService("device_config/set_run_mode", &DeviceConfigSimulationServices::SetRunMode, this); + m_serviceGetDeviceType = m_node_handle.advertiseService("device_config/get_device_type", &DeviceConfigSimulationServices::GetDeviceType, this); + m_serviceGetFirmwareVersion = m_node_handle.advertiseService("device_config/get_firmware_version", &DeviceConfigSimulationServices::GetFirmwareVersion, this); + m_serviceGetBootloaderVersion = m_node_handle.advertiseService("device_config/get_bootloader_version", &DeviceConfigSimulationServices::GetBootloaderVersion, this); + m_serviceGetModelNumber = m_node_handle.advertiseService("device_config/get_model_number", &DeviceConfigSimulationServices::GetModelNumber, this); + m_serviceGetPartNumber = m_node_handle.advertiseService("device_config/get_part_number", &DeviceConfigSimulationServices::GetPartNumber, this); + m_serviceGetSerialNumber = m_node_handle.advertiseService("device_config/get_serial_number", &DeviceConfigSimulationServices::GetSerialNumber, this); + m_serviceGetMACAddress = m_node_handle.advertiseService("device_config/get_m_a_c_address", &DeviceConfigSimulationServices::GetMACAddress, this); + m_serviceGetIPv4Settings = m_node_handle.advertiseService("device_config/get_i_pv4_settings", &DeviceConfigSimulationServices::GetIPv4Settings, this); + m_serviceSetIPv4Settings = m_node_handle.advertiseService("device_config/set_i_pv4_settings", &DeviceConfigSimulationServices::SetIPv4Settings, this); + m_serviceGetPartNumberRevision = m_node_handle.advertiseService("device_config/get_part_number_revision", &DeviceConfigSimulationServices::GetPartNumberRevision, this); + m_serviceRebootRequest = m_node_handle.advertiseService("device_config/reboot_request", &DeviceConfigSimulationServices::RebootRequest, this); + m_serviceSetSafetyEnable = m_node_handle.advertiseService("device_config/set_safety_enable", &DeviceConfigSimulationServices::SetSafetyEnable, this); + m_serviceSetSafetyErrorThreshold = m_node_handle.advertiseService("device_config/set_safety_error_threshold", &DeviceConfigSimulationServices::SetSafetyErrorThreshold, this); + m_serviceSetSafetyWarningThreshold = m_node_handle.advertiseService("device_config/set_safety_warning_threshold", &DeviceConfigSimulationServices::SetSafetyWarningThreshold, this); + m_serviceSetSafetyConfiguration = m_node_handle.advertiseService("device_config/set_safety_configuration", &DeviceConfigSimulationServices::SetSafetyConfiguration, this); + m_serviceGetSafetyConfiguration = m_node_handle.advertiseService("device_config/get_safety_configuration", &DeviceConfigSimulationServices::GetSafetyConfiguration, this); + m_serviceGetSafetyInformation = m_node_handle.advertiseService("device_config/get_safety_information", &DeviceConfigSimulationServices::GetSafetyInformation, this); + m_serviceGetSafetyEnable = m_node_handle.advertiseService("device_config/get_safety_enable", &DeviceConfigSimulationServices::GetSafetyEnable, this); + m_serviceGetSafetyStatus = m_node_handle.advertiseService("device_config/get_safety_status", &DeviceConfigSimulationServices::GetSafetyStatus, this); + m_serviceClearAllSafetyStatus = m_node_handle.advertiseService("device_config/clear_all_safety_status", &DeviceConfigSimulationServices::ClearAllSafetyStatus, this); + m_serviceClearSafetyStatus = m_node_handle.advertiseService("device_config/clear_safety_status", &DeviceConfigSimulationServices::ClearSafetyStatus, this); + m_serviceGetAllSafetyConfiguration = m_node_handle.advertiseService("device_config/get_all_safety_configuration", &DeviceConfigSimulationServices::GetAllSafetyConfiguration, this); + m_serviceGetAllSafetyInformation = m_node_handle.advertiseService("device_config/get_all_safety_information", &DeviceConfigSimulationServices::GetAllSafetyInformation, this); + m_serviceResetSafetyDefaults = m_node_handle.advertiseService("device_config/reset_safety_defaults", &DeviceConfigSimulationServices::ResetSafetyDefaults, this); + m_serviceOnNotificationSafetyTopic = m_node_handle.advertiseService("device_config/activate_publishing_of_safety_topic", &DeviceConfigSimulationServices::OnNotificationSafetyTopic, this); + m_serviceExecuteCalibration = m_node_handle.advertiseService("device_config/execute_calibration", &DeviceConfigSimulationServices::ExecuteCalibration, this); + m_serviceGetCalibrationResult = m_node_handle.advertiseService("device_config/get_calibration_result", &DeviceConfigSimulationServices::GetCalibrationResult, this); + m_serviceStopCalibration = m_node_handle.advertiseService("device_config/stop_calibration", &DeviceConfigSimulationServices::StopCalibration, this); + m_serviceDeviceConfig_SetCapSenseConfig = m_node_handle.advertiseService("device_config/set_cap_sense_config", &DeviceConfigSimulationServices::DeviceConfig_SetCapSenseConfig, this); + m_serviceDeviceConfig_GetCapSenseConfig = m_node_handle.advertiseService("device_config/get_cap_sense_config", &DeviceConfigSimulationServices::DeviceConfig_GetCapSenseConfig, this); +} + +bool DeviceConfigSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool DeviceConfigSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool DeviceConfigSimulationServices::GetRunMode(kortex_driver::GetRunMode::Request &req, kortex_driver::GetRunMode::Response &res) +{ + + + if (GetRunModeHandler) + { + res = GetRunModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_run_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::SetRunMode(kortex_driver::SetRunMode::Request &req, kortex_driver::SetRunMode::Response &res) +{ + + + if (SetRunModeHandler) + { + res = SetRunModeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_run_mode is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetDeviceType(kortex_driver::GetDeviceType::Request &req, kortex_driver::GetDeviceType::Response &res) +{ + + + if (GetDeviceTypeHandler) + { + res = GetDeviceTypeHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_device_type is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetFirmwareVersion(kortex_driver::GetFirmwareVersion::Request &req, kortex_driver::GetFirmwareVersion::Response &res) +{ + + + if (GetFirmwareVersionHandler) + { + res = GetFirmwareVersionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_firmware_version is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetBootloaderVersion(kortex_driver::GetBootloaderVersion::Request &req, kortex_driver::GetBootloaderVersion::Response &res) +{ + + + if (GetBootloaderVersionHandler) + { + res = GetBootloaderVersionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_bootloader_version is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetModelNumber(kortex_driver::GetModelNumber::Request &req, kortex_driver::GetModelNumber::Response &res) +{ + + + if (GetModelNumberHandler) + { + res = GetModelNumberHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_model_number is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetPartNumber(kortex_driver::GetPartNumber::Request &req, kortex_driver::GetPartNumber::Response &res) +{ + + + if (GetPartNumberHandler) + { + res = GetPartNumberHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_part_number is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetSerialNumber(kortex_driver::GetSerialNumber::Request &req, kortex_driver::GetSerialNumber::Response &res) +{ + + + if (GetSerialNumberHandler) + { + res = GetSerialNumberHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_serial_number is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetMACAddress(kortex_driver::GetMACAddress::Request &req, kortex_driver::GetMACAddress::Response &res) +{ + + + if (GetMACAddressHandler) + { + res = GetMACAddressHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_m_a_c_address is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetIPv4Settings(kortex_driver::GetIPv4Settings::Request &req, kortex_driver::GetIPv4Settings::Response &res) +{ + + + if (GetIPv4SettingsHandler) + { + res = GetIPv4SettingsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_i_pv4_settings is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::SetIPv4Settings(kortex_driver::SetIPv4Settings::Request &req, kortex_driver::SetIPv4Settings::Response &res) +{ + + + if (SetIPv4SettingsHandler) + { + res = SetIPv4SettingsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_i_pv4_settings is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetPartNumberRevision(kortex_driver::GetPartNumberRevision::Request &req, kortex_driver::GetPartNumberRevision::Response &res) +{ + + + if (GetPartNumberRevisionHandler) + { + res = GetPartNumberRevisionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_part_number_revision is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::RebootRequest(kortex_driver::RebootRequest::Request &req, kortex_driver::RebootRequest::Response &res) +{ + + + if (RebootRequestHandler) + { + res = RebootRequestHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/reboot_request is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::SetSafetyEnable(kortex_driver::SetSafetyEnable::Request &req, kortex_driver::SetSafetyEnable::Response &res) +{ + + + if (SetSafetyEnableHandler) + { + res = SetSafetyEnableHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_safety_enable is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::SetSafetyErrorThreshold(kortex_driver::SetSafetyErrorThreshold::Request &req, kortex_driver::SetSafetyErrorThreshold::Response &res) +{ + + + if (SetSafetyErrorThresholdHandler) + { + res = SetSafetyErrorThresholdHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_safety_error_threshold is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::SetSafetyWarningThreshold(kortex_driver::SetSafetyWarningThreshold::Request &req, kortex_driver::SetSafetyWarningThreshold::Response &res) +{ + + + if (SetSafetyWarningThresholdHandler) + { + res = SetSafetyWarningThresholdHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_safety_warning_threshold is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::SetSafetyConfiguration(kortex_driver::SetSafetyConfiguration::Request &req, kortex_driver::SetSafetyConfiguration::Response &res) +{ + + + if (SetSafetyConfigurationHandler) + { + res = SetSafetyConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_safety_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetSafetyConfiguration(kortex_driver::GetSafetyConfiguration::Request &req, kortex_driver::GetSafetyConfiguration::Response &res) +{ + + + if (GetSafetyConfigurationHandler) + { + res = GetSafetyConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_safety_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetSafetyInformation(kortex_driver::GetSafetyInformation::Request &req, kortex_driver::GetSafetyInformation::Response &res) +{ + + + if (GetSafetyInformationHandler) + { + res = GetSafetyInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_safety_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetSafetyEnable(kortex_driver::GetSafetyEnable::Request &req, kortex_driver::GetSafetyEnable::Response &res) +{ + + + if (GetSafetyEnableHandler) + { + res = GetSafetyEnableHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_safety_enable is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetSafetyStatus(kortex_driver::GetSafetyStatus::Request &req, kortex_driver::GetSafetyStatus::Response &res) +{ + + + if (GetSafetyStatusHandler) + { + res = GetSafetyStatusHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_safety_status is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::ClearAllSafetyStatus(kortex_driver::ClearAllSafetyStatus::Request &req, kortex_driver::ClearAllSafetyStatus::Response &res) +{ + + + if (ClearAllSafetyStatusHandler) + { + res = ClearAllSafetyStatusHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/clear_all_safety_status is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::ClearSafetyStatus(kortex_driver::ClearSafetyStatus::Request &req, kortex_driver::ClearSafetyStatus::Response &res) +{ + + + if (ClearSafetyStatusHandler) + { + res = ClearSafetyStatusHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/clear_safety_status is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetAllSafetyConfiguration(kortex_driver::GetAllSafetyConfiguration::Request &req, kortex_driver::GetAllSafetyConfiguration::Response &res) +{ + + + if (GetAllSafetyConfigurationHandler) + { + res = GetAllSafetyConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_all_safety_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetAllSafetyInformation(kortex_driver::GetAllSafetyInformation::Request &req, kortex_driver::GetAllSafetyInformation::Response &res) +{ + + + if (GetAllSafetyInformationHandler) + { + res = GetAllSafetyInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_all_safety_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::ResetSafetyDefaults(kortex_driver::ResetSafetyDefaults::Request &req, kortex_driver::ResetSafetyDefaults::Response &res) +{ + + + if (ResetSafetyDefaultsHandler) + { + res = ResetSafetyDefaultsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/reset_safety_defaults is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::OnNotificationSafetyTopic(kortex_driver::OnNotificationSafetyTopic::Request &req, kortex_driver::OnNotificationSafetyTopic::Response &res) +{ + + m_is_activated_SafetyTopic = true; + + if (OnNotificationSafetyTopicHandler) + { + res = OnNotificationSafetyTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/activate_publishing_of_safety_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void DeviceConfigSimulationServices::cb_SafetyTopic(Kinova::Api::Common::SafetyNotification notif) +{ + kortex_driver::SafetyNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_SafetyTopic.publish(ros_msg); +} + +bool DeviceConfigSimulationServices::ExecuteCalibration(kortex_driver::ExecuteCalibration::Request &req, kortex_driver::ExecuteCalibration::Response &res) +{ + + + if (ExecuteCalibrationHandler) + { + res = ExecuteCalibrationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/execute_calibration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::GetCalibrationResult(kortex_driver::GetCalibrationResult::Request &req, kortex_driver::GetCalibrationResult::Response &res) +{ + + + if (GetCalibrationResultHandler) + { + res = GetCalibrationResultHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_calibration_result is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::StopCalibration(kortex_driver::StopCalibration::Request &req, kortex_driver::StopCalibration::Response &res) +{ + + + if (StopCalibrationHandler) + { + res = StopCalibrationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/stop_calibration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::DeviceConfig_SetCapSenseConfig(kortex_driver::DeviceConfig_SetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_SetCapSenseConfig::Response &res) +{ + + + if (DeviceConfig_SetCapSenseConfigHandler) + { + res = DeviceConfig_SetCapSenseConfigHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/set_cap_sense_config is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool DeviceConfigSimulationServices::DeviceConfig_GetCapSenseConfig(kortex_driver::DeviceConfig_GetCapSenseConfig::Request &req, kortex_driver::DeviceConfig_GetCapSenseConfig::Response &res) +{ + + + if (DeviceConfig_GetCapSenseConfigHandler) + { + res = DeviceConfig_GetCapSenseConfigHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_config/get_cap_sense_config is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/devicemanager_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/devicemanager_services.cpp new file mode 100644 index 0000000..f0be4c0 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/devicemanager_services.cpp @@ -0,0 +1,82 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/devicemanager_services.h" + +DeviceManagerSimulationServices::DeviceManagerSimulationServices(ros::NodeHandle& node_handle): + IDeviceManagerServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + + m_serviceSetDeviceID = m_node_handle.advertiseService("device_manager/set_device_id", &DeviceManagerSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("device_manager/set_api_options", &DeviceManagerSimulationServices::SetApiOptions, this); + + m_serviceReadAllDevices = m_node_handle.advertiseService("device_manager/read_all_devices", &DeviceManagerSimulationServices::ReadAllDevices, this); +} + +bool DeviceManagerSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool DeviceManagerSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool DeviceManagerSimulationServices::ReadAllDevices(kortex_driver::ReadAllDevices::Request &req, kortex_driver::ReadAllDevices::Response &res) +{ + + + if (ReadAllDevicesHandler) + { + res = ReadAllDevicesHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for device_manager/read_all_devices is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/interconnectconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/interconnectconfig_services.cpp new file mode 100644 index 0000000..32287a2 --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/interconnectconfig_services.cpp @@ -0,0 +1,290 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/interconnectconfig_services.h" + +InterconnectConfigSimulationServices::InterconnectConfigSimulationServices(ros::NodeHandle& node_handle): + IInterconnectConfigServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + + m_serviceSetDeviceID = m_node_handle.advertiseService("interconnect_config/set_device_id", &InterconnectConfigSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("interconnect_config/set_api_options", &InterconnectConfigSimulationServices::SetApiOptions, this); + + m_serviceGetUARTConfiguration = m_node_handle.advertiseService("interconnect_config/get_u_a_r_t_configuration", &InterconnectConfigSimulationServices::GetUARTConfiguration, this); + m_serviceSetUARTConfiguration = m_node_handle.advertiseService("interconnect_config/set_u_a_r_t_configuration", &InterconnectConfigSimulationServices::SetUARTConfiguration, this); + m_serviceGetEthernetConfiguration = m_node_handle.advertiseService("interconnect_config/get_ethernet_configuration", &InterconnectConfigSimulationServices::GetEthernetConfiguration, this); + m_serviceSetEthernetConfiguration = m_node_handle.advertiseService("interconnect_config/set_ethernet_configuration", &InterconnectConfigSimulationServices::SetEthernetConfiguration, this); + m_serviceGetGPIOConfiguration = m_node_handle.advertiseService("interconnect_config/get_g_p_i_o_configuration", &InterconnectConfigSimulationServices::GetGPIOConfiguration, this); + m_serviceSetGPIOConfiguration = m_node_handle.advertiseService("interconnect_config/set_g_p_i_o_configuration", &InterconnectConfigSimulationServices::SetGPIOConfiguration, this); + m_serviceGetGPIOState = m_node_handle.advertiseService("interconnect_config/get_g_p_i_o_state", &InterconnectConfigSimulationServices::GetGPIOState, this); + m_serviceSetGPIOState = m_node_handle.advertiseService("interconnect_config/set_g_p_i_o_state", &InterconnectConfigSimulationServices::SetGPIOState, this); + m_serviceGetI2CConfiguration = m_node_handle.advertiseService("interconnect_config/get_i2_c_configuration", &InterconnectConfigSimulationServices::GetI2CConfiguration, this); + m_serviceSetI2CConfiguration = m_node_handle.advertiseService("interconnect_config/set_i2_c_configuration", &InterconnectConfigSimulationServices::SetI2CConfiguration, this); + m_serviceI2CRead = m_node_handle.advertiseService("interconnect_config/i2_c_read", &InterconnectConfigSimulationServices::I2CRead, this); + m_serviceI2CReadRegister = m_node_handle.advertiseService("interconnect_config/i2_c_read_register", &InterconnectConfigSimulationServices::I2CReadRegister, this); + m_serviceI2CWrite = m_node_handle.advertiseService("interconnect_config/i2_c_write", &InterconnectConfigSimulationServices::I2CWrite, this); + m_serviceI2CWriteRegister = m_node_handle.advertiseService("interconnect_config/i2_c_write_register", &InterconnectConfigSimulationServices::I2CWriteRegister, this); +} + +bool InterconnectConfigSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool InterconnectConfigSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool InterconnectConfigSimulationServices::GetUARTConfiguration(kortex_driver::GetUARTConfiguration::Request &req, kortex_driver::GetUARTConfiguration::Response &res) +{ + + + if (GetUARTConfigurationHandler) + { + res = GetUARTConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/get_u_a_r_t_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::SetUARTConfiguration(kortex_driver::SetUARTConfiguration::Request &req, kortex_driver::SetUARTConfiguration::Response &res) +{ + + + if (SetUARTConfigurationHandler) + { + res = SetUARTConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/set_u_a_r_t_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::GetEthernetConfiguration(kortex_driver::GetEthernetConfiguration::Request &req, kortex_driver::GetEthernetConfiguration::Response &res) +{ + + + if (GetEthernetConfigurationHandler) + { + res = GetEthernetConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/get_ethernet_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::SetEthernetConfiguration(kortex_driver::SetEthernetConfiguration::Request &req, kortex_driver::SetEthernetConfiguration::Response &res) +{ + + + if (SetEthernetConfigurationHandler) + { + res = SetEthernetConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/set_ethernet_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::GetGPIOConfiguration(kortex_driver::GetGPIOConfiguration::Request &req, kortex_driver::GetGPIOConfiguration::Response &res) +{ + + + if (GetGPIOConfigurationHandler) + { + res = GetGPIOConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/get_g_p_i_o_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::SetGPIOConfiguration(kortex_driver::SetGPIOConfiguration::Request &req, kortex_driver::SetGPIOConfiguration::Response &res) +{ + + + if (SetGPIOConfigurationHandler) + { + res = SetGPIOConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/set_g_p_i_o_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::GetGPIOState(kortex_driver::GetGPIOState::Request &req, kortex_driver::GetGPIOState::Response &res) +{ + + + if (GetGPIOStateHandler) + { + res = GetGPIOStateHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/get_g_p_i_o_state is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::SetGPIOState(kortex_driver::SetGPIOState::Request &req, kortex_driver::SetGPIOState::Response &res) +{ + + + if (SetGPIOStateHandler) + { + res = SetGPIOStateHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/set_g_p_i_o_state is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::GetI2CConfiguration(kortex_driver::GetI2CConfiguration::Request &req, kortex_driver::GetI2CConfiguration::Response &res) +{ + + + if (GetI2CConfigurationHandler) + { + res = GetI2CConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/get_i2_c_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::SetI2CConfiguration(kortex_driver::SetI2CConfiguration::Request &req, kortex_driver::SetI2CConfiguration::Response &res) +{ + + + if (SetI2CConfigurationHandler) + { + res = SetI2CConfigurationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/set_i2_c_configuration is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::I2CRead(kortex_driver::I2CRead::Request &req, kortex_driver::I2CRead::Response &res) +{ + + + if (I2CReadHandler) + { + res = I2CReadHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/i2_c_read is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::I2CReadRegister(kortex_driver::I2CReadRegister::Request &req, kortex_driver::I2CReadRegister::Response &res) +{ + + + if (I2CReadRegisterHandler) + { + res = I2CReadRegisterHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/i2_c_read_register is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::I2CWrite(kortex_driver::I2CWrite::Request &req, kortex_driver::I2CWrite::Response &res) +{ + + + if (I2CWriteHandler) + { + res = I2CWriteHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/i2_c_write is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool InterconnectConfigSimulationServices::I2CWriteRegister(kortex_driver::I2CWriteRegister::Request &req, kortex_driver::I2CWriteRegister::Response &res) +{ + + + if (I2CWriteRegisterHandler) + { + res = I2CWriteRegisterHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for interconnect_config/i2_c_write_register is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/generated/simulation/visionconfig_services.cpp b/ros_kortex/kortex_driver/src/generated/simulation/visionconfig_services.cpp new file mode 100644 index 0000000..b50c05c --- /dev/null +++ b/ros_kortex/kortex_driver/src/generated/simulation/visionconfig_services.cpp @@ -0,0 +1,267 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "kortex_driver/generated/robot/common_proto_converter.h" +#include "kortex_driver/generated/robot/common_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorconfig_ros_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/actuatorcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_proto_converter.h" +#include "kortex_driver/generated/robot/productconfiguration_ros_converter.h" +#include "kortex_driver/generated/robot/base_proto_converter.h" +#include "kortex_driver/generated/robot/base_ros_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_proto_converter.h" +#include "kortex_driver/generated/robot/grippercyclic_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectcyclic_ros_converter.h" +#include "kortex_driver/generated/robot/basecyclic_proto_converter.h" +#include "kortex_driver/generated/robot/basecyclic_ros_converter.h" +#include "kortex_driver/generated/robot/controlconfig_proto_converter.h" +#include "kortex_driver/generated/robot/controlconfig_ros_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_proto_converter.h" +#include "kortex_driver/generated/robot/deviceconfig_ros_converter.h" +#include "kortex_driver/generated/robot/devicemanager_proto_converter.h" +#include "kortex_driver/generated/robot/devicemanager_ros_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_proto_converter.h" +#include "kortex_driver/generated/robot/interconnectconfig_ros_converter.h" +#include "kortex_driver/generated/robot/visionconfig_proto_converter.h" +#include "kortex_driver/generated/robot/visionconfig_ros_converter.h" +#include "kortex_driver/generated/simulation/visionconfig_services.h" + +VisionConfigSimulationServices::VisionConfigSimulationServices(ros::NodeHandle& node_handle): + IVisionConfigServices(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); + m_pub_VisionTopic = m_node_handle.advertise("vision_topic", 1000); + m_is_activated_VisionTopic = false; + + m_serviceSetDeviceID = m_node_handle.advertiseService("vision_config/set_device_id", &VisionConfigSimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("vision_config/set_api_options", &VisionConfigSimulationServices::SetApiOptions, this); + + m_serviceSetSensorSettings = m_node_handle.advertiseService("vision_config/set_sensor_settings", &VisionConfigSimulationServices::SetSensorSettings, this); + m_serviceGetSensorSettings = m_node_handle.advertiseService("vision_config/get_sensor_settings", &VisionConfigSimulationServices::GetSensorSettings, this); + m_serviceGetOptionValue = m_node_handle.advertiseService("vision_config/get_option_value", &VisionConfigSimulationServices::GetOptionValue, this); + m_serviceSetOptionValue = m_node_handle.advertiseService("vision_config/set_option_value", &VisionConfigSimulationServices::SetOptionValue, this); + m_serviceGetOptionInformation = m_node_handle.advertiseService("vision_config/get_option_information", &VisionConfigSimulationServices::GetOptionInformation, this); + m_serviceOnNotificationVisionTopic = m_node_handle.advertiseService("vision_config/activate_publishing_of_vision_topic", &VisionConfigSimulationServices::OnNotificationVisionTopic, this); + m_serviceDoSensorFocusAction = m_node_handle.advertiseService("vision_config/do_sensor_focus_action", &VisionConfigSimulationServices::DoSensorFocusAction, this); + m_serviceGetIntrinsicParameters = m_node_handle.advertiseService("vision_config/get_intrinsic_parameters", &VisionConfigSimulationServices::GetIntrinsicParameters, this); + m_serviceGetIntrinsicParametersProfile = m_node_handle.advertiseService("vision_config/get_intrinsic_parameters_profile", &VisionConfigSimulationServices::GetIntrinsicParametersProfile, this); + m_serviceSetIntrinsicParameters = m_node_handle.advertiseService("vision_config/set_intrinsic_parameters", &VisionConfigSimulationServices::SetIntrinsicParameters, this); + m_serviceGetExtrinsicParameters = m_node_handle.advertiseService("vision_config/get_extrinsic_parameters", &VisionConfigSimulationServices::GetExtrinsicParameters, this); + m_serviceSetExtrinsicParameters = m_node_handle.advertiseService("vision_config/set_extrinsic_parameters", &VisionConfigSimulationServices::SetExtrinsicParameters, this); +} + +bool VisionConfigSimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool VisionConfigSimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + + +bool VisionConfigSimulationServices::SetSensorSettings(kortex_driver::SetSensorSettings::Request &req, kortex_driver::SetSensorSettings::Response &res) +{ + + + if (SetSensorSettingsHandler) + { + res = SetSensorSettingsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/set_sensor_settings is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::GetSensorSettings(kortex_driver::GetSensorSettings::Request &req, kortex_driver::GetSensorSettings::Response &res) +{ + + + if (GetSensorSettingsHandler) + { + res = GetSensorSettingsHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/get_sensor_settings is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::GetOptionValue(kortex_driver::GetOptionValue::Request &req, kortex_driver::GetOptionValue::Response &res) +{ + + + if (GetOptionValueHandler) + { + res = GetOptionValueHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/get_option_value is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::SetOptionValue(kortex_driver::SetOptionValue::Request &req, kortex_driver::SetOptionValue::Response &res) +{ + + + if (SetOptionValueHandler) + { + res = SetOptionValueHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/set_option_value is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::GetOptionInformation(kortex_driver::GetOptionInformation::Request &req, kortex_driver::GetOptionInformation::Response &res) +{ + + + if (GetOptionInformationHandler) + { + res = GetOptionInformationHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/get_option_information is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::OnNotificationVisionTopic(kortex_driver::OnNotificationVisionTopic::Request &req, kortex_driver::OnNotificationVisionTopic::Response &res) +{ + + m_is_activated_VisionTopic = true; + + if (OnNotificationVisionTopicHandler) + { + res = OnNotificationVisionTopicHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/activate_publishing_of_vision_topic is not implemented, so the service calls will return the default response."); + } + return true; +} +void VisionConfigSimulationServices::cb_VisionTopic(Kinova::Api::VisionConfig::VisionNotification notif) +{ + kortex_driver::VisionNotification ros_msg; + ToRosData(notif, ros_msg); + m_pub_VisionTopic.publish(ros_msg); +} + +bool VisionConfigSimulationServices::DoSensorFocusAction(kortex_driver::DoSensorFocusAction::Request &req, kortex_driver::DoSensorFocusAction::Response &res) +{ + + + if (DoSensorFocusActionHandler) + { + res = DoSensorFocusActionHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/do_sensor_focus_action is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::GetIntrinsicParameters(kortex_driver::GetIntrinsicParameters::Request &req, kortex_driver::GetIntrinsicParameters::Response &res) +{ + + + if (GetIntrinsicParametersHandler) + { + res = GetIntrinsicParametersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/get_intrinsic_parameters is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::GetIntrinsicParametersProfile(kortex_driver::GetIntrinsicParametersProfile::Request &req, kortex_driver::GetIntrinsicParametersProfile::Response &res) +{ + + + if (GetIntrinsicParametersProfileHandler) + { + res = GetIntrinsicParametersProfileHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/get_intrinsic_parameters_profile is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::SetIntrinsicParameters(kortex_driver::SetIntrinsicParameters::Request &req, kortex_driver::SetIntrinsicParameters::Response &res) +{ + + + if (SetIntrinsicParametersHandler) + { + res = SetIntrinsicParametersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/set_intrinsic_parameters is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::GetExtrinsicParameters(kortex_driver::GetExtrinsicParameters::Request &req, kortex_driver::GetExtrinsicParameters::Response &res) +{ + + + if (GetExtrinsicParametersHandler) + { + res = GetExtrinsicParametersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/get_extrinsic_parameters is not implemented, so the service calls will return the default response."); + } + return true; +} + +bool VisionConfigSimulationServices::SetExtrinsicParameters(kortex_driver::SetExtrinsicParameters::Request &req, kortex_driver::SetExtrinsicParameters::Response &res) +{ + + + if (SetExtrinsicParametersHandler) + { + res = SetExtrinsicParametersHandler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for vision_config/set_extrinsic_parameters is not implemented, so the service calls will return the default response."); + } + return true; +} diff --git a/ros_kortex/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp new file mode 100644 index 0000000..e266547 --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp @@ -0,0 +1,685 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/kortex_arm_driver.h" + +KortexArmDriver::KortexArmDriver(ros::NodeHandle nh): m_node_handle(nh), + m_node_is_running(true), + m_consecutive_base_cyclic_timeouts(0), + m_is_interconnect_module_present(false), + m_is_vision_module_present(false), + m_simulator{} +{ + // Parameter to let the other nodes know this node is up + ros::param::set("is_initialized", false); + + parseRosArguments(); + + // If with a real robot, start the robot-specific stuff + if (m_is_real_robot) + { + initApi(); + verifyProductConfiguration(); + initSubscribers(); + startActionServers(); + } + + // ROS Services are always started + initRosServices(); + + // Enable ROS Service simulation if not with a real robot + if (!m_is_real_robot) + { + m_simulator.reset(new KortexArmSimulation(nh)); + registerSimulationHandlers(); + } + + // Start the thread to publish the feedback and joint states + m_pub_base_feedback = m_node_handle.advertise("base_feedback", 1000); + m_pub_joint_state = m_node_handle.advertise("base_feedback/joint_state", 1000); + if (m_is_real_robot) + { + m_publish_feedback_thread = std::thread(&KortexArmDriver::publishRobotFeedback, this); + } + else + { + m_publish_feedback_thread = std::thread(&KortexArmDriver::publishSimulationFeedback, this); + } + + // If we get here and no error was thrown we started the node correctly + ROS_INFO("%sThe Kortex driver has been initialized correctly!%s", GREEN_COLOR_CONSOLE, RESET_COLOR_CONSOLE); + ros::param::set("is_initialized", true); +} + +KortexArmDriver::~KortexArmDriver() +{ + // Kill the thread that publishes the joint states and feedback + m_node_is_running = false; + if (m_publish_feedback_thread.joinable()) + { + m_publish_feedback_thread.join(); + } + + delete m_actuator_config_ros_services; + delete m_base_ros_services; + delete m_control_config_ros_services; + delete m_device_config_ros_services; + delete m_device_manager_ros_services; + if (m_interconnect_config_ros_services) + { + delete m_interconnect_config_ros_services; + } + if (m_vision_config_ros_services) + { + delete m_vision_config_ros_services; + } + + if (!m_is_real_robot) + { + + delete m_action_server_follow_joint_trajectory; + if (m_action_server_gripper_command) + { + delete m_action_server_gripper_command; + } + + delete m_topic_subscribers; + + m_tcp_session_manager->CloseSession(); + m_udp_session_manager->CloseSession(); + m_tcp_router->SetActivationStatus(false); + m_udp_router->SetActivationStatus(false); + m_tcp_transport->disconnect(); + m_udp_transport->disconnect(); + + delete m_actuator_config; + delete m_base; + delete m_control_config; + delete m_device_config; + delete m_device_manager; + delete m_interconnect_config; + delete m_vision_config; + delete m_base_cyclic; + + delete m_tcp_session_manager; + delete m_udp_session_manager; + + delete m_tcp_router; + delete m_udp_router; + delete m_tcp_transport; + delete m_udp_transport; + } +} + +void KortexArmDriver::parseRosArguments() +{ + bool sim; + if (!ros::param::get("~sim", sim)) + { + std::string error_string = "Simulation was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + m_is_real_robot = !sim; + + // Some parameters are only necessary with a real robot + if (m_is_real_robot) + { + bool use_sim_time = false; + if (ros::param::get("/use_sim_time", use_sim_time)) + { + if (use_sim_time) + { + std::string error_string = "ROS parameter /use_sim_time is true : you may experience problems and you should set it to false and restart the driver."; + ROS_WARN("%s", error_string.c_str()); + } + } + + if (!ros::param::get("~ip_address", m_ip_address)) + { + std::string error_string = "IP address of the robot was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~username", m_username)) + { + std::string error_string = "Username for the robot session was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~password", m_password)) + { + std::string error_string = "Password for the robot session was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~use_hard_limits", m_use_hard_limits)) + { + std::string error_string = "Usage of hard limits as soft was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~api_rpc_timeout_ms", m_api_rpc_timeout_ms)) + { + std::string error_string = "API RPC timeout duration was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~api_session_inactivity_timeout_ms", m_api_session_inactivity_timeout_ms)) + { + std::string error_string = "API session inactivity timeout duration was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~api_connection_inactivity_timeout_ms", m_api_connection_inactivity_timeout_ms)) + { + std::string error_string = "API connection inactivity timeout duration was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } + + + if (!ros::param::get("~cyclic_data_publish_rate", m_cyclic_data_publish_rate)) + { + std::string error_string = "Publish rate of the cyclic data was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~arm", m_arm_name)) + { + std::string error_string = "Arm name was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~dof", m_degrees_of_freedom)) + { + std::string error_string = "Number of degrees of freedom was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~joint_names", m_arm_joint_names)) + { + std::string error_string = "Arm joint_names were not specified, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (!ros::param::get("~gripper", m_gripper_name)) + { + std::string error_string = "Gripper name was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + std::string robot_name; + if (!ros::param::get("~robot_name", robot_name)) + { + std::string error_string = "Robot name was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + if (!ros::param::get("~prefix", m_prefix)) + { + std::string error_string = "Prefix name was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + if (isGripperPresent()) + { + // Get the gripper_joint_names size + if (!ros::param::get("~gripper_joint_names", m_gripper_joint_names)) + { + std::string error_string = "Gripper joint names were not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + // Get the gripper_joint_limits size + if (!ros::param::get("~gripper_joint_limits_min", m_gripper_joint_limits_min)) + { + std::string error_string = "Gripper joint min limits were not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + // Get the gripper_joint_limits size + if (!ros::param::get("~gripper_joint_limits_max", m_gripper_joint_limits_max)) + { + std::string error_string = "Gripper joint max limits were not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } +} + +void KortexArmDriver::initApi() +{ + // Create the transport objects and connect to the robot + // TCP for all the Config services + // UDP for the Cyclic services (the feedback) + m_tcp_transport = new Kinova::Api::TransportClientTcp(); + m_udp_transport = new Kinova::Api::TransportClientUdp(); + m_tcp_transport->connect(m_ip_address, TCP_PORT); + m_udp_transport->connect(m_ip_address, UDP_PORT); + + // Create the routers + m_tcp_router = new Kinova::Api::RouterClient(m_tcp_transport, [](Kinova::Api::KError err) { ROS_ERROR("Kortex API error was encountered with the TCP router: %s", err.toString().c_str()); }); + m_udp_router = new Kinova::Api::RouterClient(m_udp_transport, [](Kinova::Api::KError err) { ROS_ERROR("Kortex API error was encountered with the UDP router: %s", err.toString().c_str()); }); + + // Create the Protobuf services we are going to use in the ServiceProxy's + m_actuator_config = new Kinova::Api::ActuatorConfig::ActuatorConfigClient(m_tcp_router); + m_base = new Kinova::Api::Base::BaseClient(m_tcp_router); + m_control_config = new Kinova::Api::ControlConfig::ControlConfigClient(m_tcp_router); + m_device_config = new Kinova::Api::DeviceConfig::DeviceConfigClient(m_tcp_router); + m_device_manager = new Kinova::Api::DeviceManager::DeviceManagerClient(m_tcp_router); + m_interconnect_config = new Kinova::Api::InterconnectConfig::InterconnectConfigClient(m_tcp_router); + m_vision_config = new Kinova::Api::VisionConfig::VisionConfigClient(m_tcp_router); + + // Create the BaseCyclic Protobuf service for the feedback + m_base_cyclic = new Kinova::Api::BaseCyclic::BaseCyclicClient(m_udp_router); + + // Create the sessions so we can start using the robot + auto createSessionInfo = Kinova::Api::Session::CreateSessionInfo(); + createSessionInfo.set_username(m_username); + createSessionInfo.set_password(m_password); + createSessionInfo.set_session_inactivity_timeout(m_api_session_inactivity_timeout_ms); + createSessionInfo.set_connection_inactivity_timeout(m_api_connection_inactivity_timeout_ms); + + m_tcp_session_manager = new Kinova::Api::SessionManager(m_tcp_router); + m_udp_session_manager = new Kinova::Api::SessionManager(m_udp_router); + + try + { + m_tcp_session_manager->CreateSession(createSessionInfo); + ROS_INFO("Session created successfully for TCP services"); + + m_udp_session_manager->CreateSession(createSessionInfo); + ROS_INFO("Session created successfully for UDP services"); + } + catch(std::runtime_error& ex_runtime) + { + std::string error_string = "The node could not connect to the arm. Did you specify the right IP address and is the arm powered on?"; + ROS_ERROR("%s", error_string.c_str()); + throw ex_runtime; + } +} + +void KortexArmDriver::verifyProductConfiguration() +{ + // Retrieve the Product Configuration + Kinova::Api::ProductConfiguration::CompleteProductConfiguration product_config = m_base->GetProductConfiguration(); + + // Compare arm model (ModelId) + if (m_arm_name == "gen3") + { + if (product_config.model() != Kinova::Api::ProductConfiguration::ModelId::MODEL_ID_L53) + { + std::string error_string = "The arm model specified in the launch file doesn't match the detected arm's model, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + // Set Angular Trajectories soft limits to max if the option is true in the launch file + if (m_use_hard_limits) + { + setAngularTrajectorySoftLimitsToMax(); + } + } + else if (m_arm_name == "gen3_lite") + { + if (product_config.model() != Kinova::Api::ProductConfiguration::ModelId::MODEL_ID_L31) + { + std::string error_string = "The arm model specified in the launch file doesn't match the detected arm's model, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } + else + { + std::string error_string = "The arm model specified in the launch file is not supported, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + // Compare number of degrees of freedom specified in the launch file with the number of detected actuators + if (product_config.degree_of_freedom() != m_degrees_of_freedom) + { + std::string error_string = "The degrees of freedom specified in the launch file doesn't match the detected number of actuators, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + // Compare gripper type (EndEffectorType) + if (!isGripperPresent()) + { + if (product_config.end_effector_type() != Kinova::Api::ProductConfiguration::EndEffectorType::END_EFFECTOR_TYPE_NOT_INSTALLED) + { + std::string error_string = "The gripper model specified in the launch file doesn't match the detected arm's gripper model, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } + else if (m_gripper_name == "robotiq_2f_85") + { + if (product_config.end_effector_type() != Kinova::Api::ProductConfiguration::EndEffectorType::END_EFFECTOR_TYPE_ROBOTIQ_2F_85) + { + std::string error_string = "The gripper model specified in the launch file doesn't match the detected arm's gripper model, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } + else if (m_gripper_name == "robotiq_2f_140") + { + if (product_config.end_effector_type() != Kinova::Api::ProductConfiguration::EndEffectorType::END_EFFECTOR_TYPE_ROBOTIQ_2F_140) + { + std::string error_string = "The gripper model specified in the launch file doesn't match the detected arm's gripper model, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } + else if (m_gripper_name == "gen3_lite_2f") + { + if (product_config.end_effector_type() != Kinova::Api::ProductConfiguration::EndEffectorType::END_EFFECTOR_TYPE_L31_GRIPPER_2F) + { + std::string error_string = "The gripper model specified in the launch file doesn't match the detected arm's gripper model, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + } + else + { + std::string error_string = "The gripper model specified in the launch file is not supported, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + // Find all the devices and print the device ID's + ROS_INFO("-------------------------------------------------"); + ROS_INFO("Scanning all devices in robot... "); + +// Loop through the devices to find the device ID's + auto devices = m_device_manager->ReadAllDevices(); + for (auto device : devices.device_handle()) + { + if (device.device_type() == Kinova::Api::Common::DeviceTypes::BASE) + { + ROS_INFO("Base device was found on device identifier %u", device.device_identifier()); + } + else if (device.device_type() == Kinova::Api::Common::DeviceTypes::SMALL_ACTUATOR + || device.device_type() == Kinova::Api::Common::DeviceTypes::MEDIUM_ACTUATOR + || device.device_type() == Kinova::Api::Common::DeviceTypes::BIG_ACTUATOR + || device.device_type() == Kinova::Api::Common::DeviceTypes::XBIG_ACTUATOR) + { + ROS_INFO("Actuator device of type %s was found on device identifier %u", Kinova::Api::Common::DeviceTypes_Name(device.device_type()).c_str(), device.device_identifier()); + } + else if (device.device_type() == Kinova::Api::Common::DeviceTypes::INTERCONNECT) + { + m_interconnect_device_id = device.device_identifier(); + m_is_interconnect_module_present = true; + ROS_INFO("Interconnect device was found on device identifier %u", m_interconnect_device_id); + } + else if (device.device_type() == Kinova::Api::Common::DeviceTypes::VISION) + { + m_vision_device_id = device.device_identifier(); + m_is_vision_module_present = true; + ROS_INFO("Vision device was found on device identifier %u", m_vision_device_id); + } + } + ROS_INFO("-------------------------------------------------"); + + // Set the ROS Param for the degrees of freedom + m_node_handle.setParam("degrees_of_freedom", int(product_config.degree_of_freedom())); + m_node_handle.setParam("is_gripper_present", isGripperPresent()); + m_node_handle.setParam("gripper_joint_names", m_gripper_joint_names); + m_node_handle.setParam("has_vision_module", m_is_vision_module_present); + m_node_handle.setParam("has_interconnect_module", m_is_interconnect_module_present); +} + +void KortexArmDriver::initSubscribers() +{ + m_topic_subscribers = new KortexSubscribers(m_node_handle, m_base); +} + +void KortexArmDriver::initRosServices() +{ + ROS_INFO("-------------------------------------------------"); + ROS_INFO("Initializing Kortex Driver's services..."); + if (m_is_real_robot) + { + m_actuator_config_ros_services = new ActuatorConfigRobotServices(m_node_handle, m_actuator_config, 0, m_api_rpc_timeout_ms); + m_base_ros_services = new BaseRobotServices(m_node_handle, m_base, 0, m_api_rpc_timeout_ms); + m_control_config_ros_services = new ControlConfigRobotServices(m_node_handle, m_control_config, 0, m_api_rpc_timeout_ms); + m_device_config_ros_services = new DeviceConfigRobotServices(m_node_handle, m_device_config, 0, m_api_rpc_timeout_ms); + m_device_manager_ros_services = new DeviceManagerRobotServices(m_node_handle, m_device_manager, 0, m_api_rpc_timeout_ms); + if (m_is_interconnect_module_present) + { + m_interconnect_config_ros_services = new InterconnectConfigRobotServices(m_node_handle, m_interconnect_config, m_interconnect_device_id, m_api_rpc_timeout_ms); + } + else + { + m_interconnect_config_ros_services = nullptr; + } + if (m_is_vision_module_present) + { + m_vision_config_ros_services = new VisionConfigRobotServices(m_node_handle, m_vision_config, m_vision_device_id, m_api_rpc_timeout_ms); + } + else + { + m_vision_config_ros_services = nullptr; + } + } + else + { + m_actuator_config_ros_services = new ActuatorConfigSimulationServices(m_node_handle); + m_base_ros_services = new BaseSimulationServices(m_node_handle); + m_control_config_ros_services = new ControlConfigSimulationServices(m_node_handle); + m_device_config_ros_services = new DeviceConfigSimulationServices(m_node_handle); + m_device_manager_ros_services = new DeviceManagerSimulationServices(m_node_handle); + if (m_is_interconnect_module_present) + { + m_interconnect_config_ros_services = new InterconnectConfigSimulationServices(m_node_handle); + } + else + { + m_interconnect_config_ros_services = nullptr; + } + if (m_is_vision_module_present) + { + m_vision_config_ros_services = new VisionConfigSimulationServices(m_node_handle); + } + else + { + m_vision_config_ros_services = nullptr; + } + } + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + ROS_INFO("Kortex Driver's services initialized correctly."); + ROS_INFO("-------------------------------------------------"); +} + +void KortexArmDriver::startActionServers() +{ + // Start Action servers + m_action_server_follow_joint_trajectory = new PreComputedJointTrajectoryActionServer(m_arm_name + "_joint_trajectory_controller/follow_joint_trajectory", m_node_handle, m_base, m_base_cyclic); + // Start Gripper Action Server if the arm has a gripper + m_action_server_gripper_command = nullptr; + if (isGripperPresent()) + { + m_action_server_gripper_command = new RobotiqGripperCommandActionServer(m_gripper_name + "_gripper_controller/gripper_cmd", m_gripper_joint_names[0], m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0], m_node_handle, m_base, m_base_cyclic); + } +} + +bool KortexArmDriver::isGripperPresent() +{ + return m_gripper_name != ""; +} + +void KortexArmDriver::setAngularTrajectorySoftLimitsToMax() +{ + try + { + auto hard_limits = m_control_config->GetKinematicHardLimits(); + Kinova::Api::ControlConfig::ControlMode target_control_mode = Kinova::Api::ControlConfig::ANGULAR_TRAJECTORY; + + // Set Joint Speed limits to max + Kinova::Api::ControlConfig::JointSpeedSoftLimits jpsl; + jpsl.set_control_mode(target_control_mode); + for (auto j : hard_limits.joint_speed_limits()) + { + jpsl.add_joint_speed_soft_limits(j); + } + m_control_config->SetJointSpeedSoftLimits(jpsl); + + // Set Joint Acceleration limits to max + Kinova::Api::ControlConfig::JointAccelerationSoftLimits jasl; + jasl.set_control_mode(target_control_mode); + for (auto j : hard_limits.joint_acceleration_limits()) + { + jasl.add_joint_acceleration_soft_limits(j); + } + m_control_config->SetJointAccelerationSoftLimits(jasl); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while getting the base_feedback"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } +} + +void KortexArmDriver::publishRobotFeedback() +{ + + Kinova::Api::BaseCyclic::Feedback feedback_from_api; + sensor_msgs::JointState joint_state; + + ros::Rate rate(m_cyclic_data_publish_rate); + while (m_node_is_running) + { + try + { + feedback_from_api = m_base_cyclic->RefreshFeedback(); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while getting the base_feedback"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } + catch (std::runtime_error& ex_runtime) + { + ROS_DEBUG("Runtime exception detected while getting feedback! %d", ++m_consecutive_base_cyclic_timeouts); + ROS_DEBUG("%s", ex_runtime.what()); + } + catch (std::future_error& ex_future) + { + ROS_DEBUG("Future exception detected while getting feedback : %s", ex_future.what()); + } + + // If the arm has disconnected, the node cannot continue running + if (m_consecutive_base_cyclic_timeouts > MAX_CONSECUTIVE_TIMEOUTS_BEFORE_SHUTDOWN) + { + std::string error_string = "Too many consecutive timeouts : killing the node."; + ROS_ERROR("%s", error_string.c_str()); + ros::shutdown(); + return; + } + + m_consecutive_base_cyclic_timeouts = 0; + kortex_driver::BaseCyclic_Feedback base_feedback; + ToRosData(feedback_from_api, base_feedback); + + joint_state.name.resize(base_feedback.actuators.size() + base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.size()); + joint_state.position.resize(base_feedback.actuators.size() + base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.size()); + joint_state.velocity.resize(base_feedback.actuators.size() + base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.size()); + joint_state.effort.resize(base_feedback.actuators.size() + base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.size()); + joint_state.header.stamp = ros::Time::now(); + + for (int i = 0; i < base_feedback.actuators.size(); i++) + { + joint_state.name[i] = m_arm_joint_names[i]; + joint_state.position[i] = m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(base_feedback.actuators[i].position)); + joint_state.velocity[i] = m_math_util.toRad(base_feedback.actuators[i].velocity); + joint_state.effort[i] = base_feedback.actuators[i].torque; + } + + if (isGripperPresent()) + { + for (int i = 0; i < base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.size(); i++) + { + int joint_state_index = base_feedback.actuators.size() + i; + joint_state.name[joint_state_index] = m_gripper_joint_names[i]; + // Arm feedback is between 0 and 100, and limits in URDF are specified in gripper_joint_limits_min[i] and gripper_joint_limits_max[i] parameters + joint_state.position[joint_state_index] = m_math_util.absolute_position_from_relative(base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor[i].position / 100.0, m_gripper_joint_limits_min[i], m_gripper_joint_limits_max[i]); + joint_state.velocity[joint_state_index] = base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor[i].velocity; + // Not supported for now + joint_state.effort[joint_state_index] = 0.0; + } + } + + m_pub_base_feedback.publish(base_feedback); + m_pub_joint_state.publish(joint_state); + + rate.sleep(); + } +} + +void KortexArmDriver::publishSimulationFeedback() +{ + ros::Rate rate(m_cyclic_data_publish_rate); + while (m_node_is_running) + { + m_pub_base_feedback.publish(m_simulator->GetFeedback()); + rate.sleep(); + } +} + +void KortexArmDriver::registerSimulationHandlers() +{ + BaseSimulationServices* base_services_simulation = dynamic_cast(m_base_ros_services); + // Link the m_simulator handlers to the ROS services callbacks + // Action services + base_services_simulation->CreateActionHandler = std::bind(&KortexArmSimulation::CreateAction, m_simulator.get(), std::placeholders::_1); + base_services_simulation->ReadActionHandler = std::bind(&KortexArmSimulation::ReadAction, m_simulator.get(), std::placeholders::_1); + base_services_simulation->ReadAllActionsHandler = std::bind(&KortexArmSimulation::ReadAllActions, m_simulator.get(), std::placeholders::_1); + base_services_simulation->DeleteActionHandler = std::bind(&KortexArmSimulation::DeleteAction, m_simulator.get(), std::placeholders::_1); + base_services_simulation->UpdateActionHandler = std::bind(&KortexArmSimulation::UpdateAction, m_simulator.get(), std::placeholders::_1); + base_services_simulation->ExecuteActionFromReferenceHandler = std::bind(&KortexArmSimulation::ExecuteActionFromReference, m_simulator.get(), std::placeholders::_1); + base_services_simulation->ExecuteActionHandler = std::bind(&KortexArmSimulation::ExecuteAction, m_simulator.get(), std::placeholders::_1); + base_services_simulation->StopActionHandler = std::bind(&KortexArmSimulation::StopAction, m_simulator.get(), std::placeholders::_1); + // Other services + base_services_simulation->PlayCartesianTrajectoryHandler = std::bind(&KortexArmSimulation::PlayCartesianTrajectory, m_simulator.get(), std::placeholders::_1); + base_services_simulation->PlayJointTrajectoryHandler = std::bind(&KortexArmSimulation::PlayJointTrajectory, m_simulator.get(), std::placeholders::_1); + base_services_simulation->SendJointSpeedsCommandHandler = std::bind(&KortexArmSimulation::SendJointSpeedsCommand, m_simulator.get(), std::placeholders::_1); + base_services_simulation->SendGripperCommandHandler = std::bind(&KortexArmSimulation::SendGripperCommand, m_simulator.get(), std::placeholders::_1); + base_services_simulation->StopHandler = std::bind(&KortexArmSimulation::Stop, m_simulator.get(), std::placeholders::_1); + base_services_simulation->ApplyEmergencyStopHandler = std::bind(&KortexArmSimulation::ApplyEmergencyStop, m_simulator.get(), std::placeholders::_1); + + // Uncomment this SendTwistCommand handler to use the twist command simulation - not stable + // base_services_simulation->SendTwistCommandHandler = std::bind(&KortexArmSimulation::SendTwistCommand, m_simulator.get(), std::placeholders::_1); + + // Prospects + //SendSelectedJointSpeedCommand + //PlaySelectedJointTrajectory + //PlayCartesianTrajectoryPosition + //PlayCartesianTrajectoryOrientation +} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp new file mode 100644 index 0000000..bfd61bc --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_arm_simulation.cpp @@ -0,0 +1,1652 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2020 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/kortex_arm_simulation.h" +#include "kortex_driver/ErrorCodes.h" +#include "kortex_driver/SubErrorCodes.h" +#include "kortex_driver/ActionNotification.h" +#include "kortex_driver/ActionEvent.h" +#include "kortex_driver/JointTrajectoryConstraintType.h" +#include "kortex_driver/GripperMode.h" +#include "kortex_driver/CartesianReferenceFrame.h" + +#include "trajectory_msgs/JointTrajectory.h" +#include "controller_manager_msgs/SwitchController.h" +#include "std_msgs/Float64.h" + +#include +#include +#include +#include + +#include + +#include +#include + +namespace +{ + static const std::string ARM_PLANNING_GROUP = "arm"; + static const std::string GRIPPER_PLANNING_GROUP = "gripper"; + static constexpr unsigned int FIRST_CREATED_ACTION_ID = 10000; + static const std::set DEFAULT_ACTIONS_IDENTIFIERS{1,2,3}; + static constexpr double JOINT_TRAJECTORY_TIMESTEP_SECONDS = 0.01; + static constexpr double MINIMUM_JOINT_VELOCITY_RAD_PER_SECONDS = 0.001; +} + +KortexArmSimulation::KortexArmSimulation(ros::NodeHandle& node_handle): m_node_handle(node_handle), + m_map_actions{}, + m_is_action_being_executed{false}, + m_action_preempted{false}, + m_current_action_type{0}, + m_first_state_received{false}, + m_active_controller_type{ControllerType::kTrajectory} +{ + // Namespacing and prefixing information + ros::param::get("~robot_name", m_robot_name); + ros::param::get("~prefix", m_prefix); + + // Arm information + urdf::Model model; + model.initParam("/" + m_robot_name + "/robot_description"); + ros::param::get("~dof", m_degrees_of_freedom); + ros::param::get("~arm", m_arm_name); + ros::param::get("~joint_names", m_arm_joint_names); + ros::param::get("~maximum_velocities", m_arm_velocity_max_limits); + ros::param::get("~maximum_accelerations", m_arm_acceleration_max_limits); + m_arm_joint_limits_min.resize(GetDOF()); + m_arm_joint_limits_max.resize(GetDOF()); + for (int i = 0; i < GetDOF(); i++) + { + auto joint = model.getJoint(m_arm_joint_names[i]); + m_arm_joint_limits_min[i] = joint->limits->lower; + m_arm_joint_limits_max[i] = joint->limits->upper; + } + + // Cartesian Twist limits + ros::param::get("~maximum_linear_velocity", m_max_cartesian_twist_linear); + ros::param::get("~maximum_angular_velocity", m_max_cartesian_twist_angular); + ros::param::get("~maximum_linear_acceleration", m_max_cartesian_acceleration_linear); + ros::param::get("~maximum_angular_acceleration", m_max_cartesian_acceleration_angular); + + // Gripper information + ros::param::get("~gripper", m_gripper_name); + if (IsGripperPresent()) + { + ros::param::get("~gripper_joint_names", m_gripper_joint_names); + + // The joint_states feedback uses alphabetical order for the indexes + // If the gripper joint is before + if (m_gripper_joint_names[0] < m_arm_joint_names[0]) + { + m_gripper_joint_index = 0; + m_first_arm_joint_index = 1; + } + // If the gripper joint is after the arm joints + else + { + m_gripper_joint_index = GetDOF(); + m_first_arm_joint_index = 0; + } + + for (auto s : m_gripper_joint_names) + { + s.insert(0, m_prefix); + } + ros::param::get("~gripper_joint_limits_max", m_gripper_joint_limits_max); + ros::param::get("~gripper_joint_limits_min", m_gripper_joint_limits_min); + } + + // Print out simulation configuration + ROS_INFO("Simulating arm with following characteristics:"); + ROS_INFO("Arm type : %s", m_arm_name.c_str()); + ROS_INFO("Gripper type : %s", m_gripper_name.empty() ? "None" : m_gripper_name.c_str()); + ROS_INFO("Arm namespace : %s", m_robot_name.c_str()); + ROS_INFO("URDF prefix : %s", m_prefix.c_str()); + + // Building the KDL chain from the robot description + // The chain goes from 'base_link' to 'tool_frame' + KDL::Tree tree; + if (!kdl_parser::treeFromParam("robot_description", tree)) + { + const std::string error_string("Failed to parse robot_description parameter to build the kinematic tree!"); + ROS_ERROR("%s", error_string.c_str()); + throw(std::runtime_error(error_string)); + } + if (!tree.getChain(m_prefix + "base_link", m_prefix + "tool_frame", m_chain)) + { + const std::string error_string("Failed to extract kinematic chain from parsed tree!"); + ROS_ERROR("%s", error_string.c_str()); + throw(std::runtime_error(error_string)); + } + m_fk_solver.reset(new KDL::ChainFkSolverPos_recursive(m_chain)); + m_ik_vel_solver.reset(new KDL::ChainIkSolverVel_pinv(m_chain)); + m_ik_pos_solver.reset(new KDL::ChainIkSolverPos_NR(m_chain, *m_fk_solver, *m_ik_vel_solver)); + + // Build the velocity profile for each joint using the max velocities and max accelerations + for (int i = 0; i < GetDOF(); i++) + { + m_velocity_trap_profiles.push_back(KDL::VelocityProfile_Trap(m_arm_velocity_max_limits[i], m_arm_acceleration_max_limits[i])); + } + + // Start MoveIt client + m_moveit_arm_interface.reset(new moveit::planning_interface::MoveGroupInterface(ARM_PLANNING_GROUP)); + if (IsGripperPresent()) + { + m_moveit_gripper_interface.reset(new moveit::planning_interface::MoveGroupInterface(GRIPPER_PLANNING_GROUP)); + } + + // Create default actions + CreateDefaultActions(); + + // Create publishers and subscribers + for (int i = 0; i < GetDOF(); i++) + { + m_pub_position_controllers.push_back(m_node_handle.advertise( + "/" + m_robot_name + "/" + m_prefix + "joint_" + std::to_string(i+1) + "_position_controller/command", 1000)); + } + m_pub_action_topic = m_node_handle.advertise("action_topic", 1000); + m_sub_joint_state = m_node_handle.subscribe("/" + m_robot_name + "/" + "joint_states", 1, &KortexArmSimulation::cb_joint_states, this); + m_feedback.actuators.resize(GetDOF()); + m_feedback.interconnect.oneof_tool_feedback.gripper_feedback.resize(1); + m_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.resize(1); + + m_sub_joint_speeds = m_node_handle.subscribe("in/joint_velocity", 1, &KortexArmSimulation::new_joint_speeds_cb, this); + m_sub_twist = m_node_handle.subscribe("in/cartesian_velocity", 1, &KortexArmSimulation::new_twist_cb, this); + m_sub_clear_faults = m_node_handle.subscribe("in/clear_faults", 1, &KortexArmSimulation::clear_faults_cb, this); + m_sub_stop = m_node_handle.subscribe("in/stop", 1, &KortexArmSimulation::stop_cb, this); + m_sub_emergency_stop = m_node_handle.subscribe("in/emergency_stop", 1, &KortexArmSimulation::emergency_stop_cb, this); + + // Create service clients + m_client_switch_controllers = m_node_handle.serviceClient + ("/" + m_robot_name + "/controller_manager/switch_controller"); + + // Fill controllers'names + m_trajectory_controllers_list.push_back(m_prefix + m_arm_name + "_joint_trajectory_controller"); // only one trajectory controller + m_position_controllers_list.resize(GetDOF()); // one position controller per + std::generate(m_position_controllers_list.begin(), + m_position_controllers_list.end(), + [this]() -> std::string + { + static int i = 1; + return m_prefix + "joint_" + std::to_string(i++) + "_position_controller"; + }); + + // Initialize the velocity commands to null + m_velocity_commands.resize(GetDOF()); + std::fill(m_velocity_commands.begin(), m_velocity_commands.end(), 0.0); + + // Create and connect action clients + m_follow_joint_trajectory_action_client.reset(new actionlib::SimpleActionClient( + "/" + m_robot_name + "/" + m_prefix + m_arm_name + "_joint_trajectory_controller" + "/follow_joint_trajectory", true)); + m_follow_joint_trajectory_action_client->waitForServer(); + if (IsGripperPresent()) + { + m_gripper_action_client.reset(new actionlib::SimpleActionClient( + "/" + m_robot_name + "/" + m_prefix + m_gripper_name + "_gripper_controller" + "/gripper_cmd", true)); + m_gripper_action_client->waitForServer(); + } + + // Create usual ROS parameters + m_node_handle.setParam("degrees_of_freedom", m_degrees_of_freedom); + m_node_handle.setParam("is_gripper_present", IsGripperPresent()); + m_node_handle.setParam("gripper_joint_names", m_gripper_joint_names); + m_node_handle.setParam("has_vision_module", false); + m_node_handle.setParam("has_interconnect_module", false); +} + +KortexArmSimulation::~KortexArmSimulation() +{ + JoinThreadAndCancelAction(); +} + +kortex_driver::BaseCyclic_Feedback KortexArmSimulation::GetFeedback() +{ + // If the feedback is not yet received, return now + if (!m_first_state_received) + { + return m_feedback; + } + + // Make a copy of current state + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Fill joint angles feedback + for (int i = 0; i < GetDOF(); i++) + { + m_feedback.actuators[i].position = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(current.position[m_first_arm_joint_index + i])); + m_feedback.actuators[i].velocity = m_math_util.toDeg(current.velocity[m_first_arm_joint_index + i]); + } + + // Calculate FK to get end effector pose + auto frame = KDL::Frame(); + Eigen::VectorXd positions_eigen(GetDOF()); + for (int i = 0; i < GetDOF(); i++) + { + positions_eigen[i] = current.position[m_first_arm_joint_index + i]; + } + KDL::JntArray current_kdl(GetDOF()); + current_kdl.data = positions_eigen; + m_fk_solver->JntToCart(current_kdl, frame); + m_feedback.base.tool_pose_x = frame.p.x(); + m_feedback.base.commanded_tool_pose_x = frame.p.x(); + m_feedback.base.tool_pose_y = frame.p.y(); + m_feedback.base.commanded_tool_pose_y = frame.p.y(); + m_feedback.base.tool_pose_z = frame.p.z(); + m_feedback.base.commanded_tool_pose_z = frame.p.z(); + double alpha, beta, gamma; + frame.M.GetEulerZYX(alpha, beta, gamma); + m_feedback.base.tool_pose_theta_x = m_math_util.toDeg(gamma); + m_feedback.base.commanded_tool_pose_theta_x = m_math_util.toDeg(gamma); + m_feedback.base.tool_pose_theta_y = m_math_util.toDeg(beta); + m_feedback.base.commanded_tool_pose_theta_y = m_math_util.toDeg(beta); + m_feedback.base.tool_pose_theta_z = m_math_util.toDeg(alpha); + m_feedback.base.commanded_tool_pose_theta_z = m_math_util.toDeg(alpha); + + // Fill gripper information + if (IsGripperPresent()) + { + // Gripper index is right after last actuator and is expressed in % in the base feedback (not in absolute position like in joint_states) + m_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor[0].position = 100.0 * m_math_util.relative_position_from_absolute(current.position[m_gripper_joint_index], m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0]); + } + + return m_feedback; +} + +kortex_driver::CreateAction::Response KortexArmSimulation::CreateAction(const kortex_driver::CreateAction::Request& req) +{ + auto new_action = req.input; + unsigned int identifier = FIRST_CREATED_ACTION_ID; + bool identifier_taken = true; + // Find unique identifier for new action + while (identifier_taken) + { + identifier_taken = m_map_actions.count(identifier) == 1; + if (identifier_taken) + { + ++identifier; + } + } + // Add Action to map if type is supported + switch (new_action.handle.action_type) + { + case kortex_driver::ActionType::REACH_JOINT_ANGLES: + case kortex_driver::ActionType::REACH_POSE: + case kortex_driver::ActionType::SEND_GRIPPER_COMMAND: + case kortex_driver::ActionType::TIME_DELAY: + new_action.handle.identifier = identifier; + new_action.handle.permission = 7; + m_map_actions.emplace(std::make_pair(identifier, new_action)); + break; + default: + ROS_ERROR("Unsupported action type %d : could not create simulated action.", new_action.handle.action_type); + break; + } + // Return ActionHandle for added action + kortex_driver::CreateAction::Response response; + response.output = new_action.handle; + return response; +} + +kortex_driver::ReadAction::Response KortexArmSimulation::ReadAction(const kortex_driver::ReadAction::Request& req) +{ + auto input = req.input; + kortex_driver::ReadAction::Response response; + auto it = m_map_actions.find(input.identifier); + if (it != m_map_actions.end()) + { + response.output = it->second; + } + return response; +} + +kortex_driver::ReadAllActions::Response KortexArmSimulation::ReadAllActions(const kortex_driver::ReadAllActions::Request& req) +{ + auto input = req.input; + kortex_driver::ReadAllActions::Response response; + kortex_driver::ActionList action_list; + for (auto a : m_map_actions) + { + // If requested action type is specified and matches iterated action's type, add it to the list + if (input.action_type == 0 || input.action_type == a.second.handle.action_type) + { + action_list.action_list.push_back(a.second); + } + + } + response.output = action_list; + return response; +} + +kortex_driver::DeleteAction::Response KortexArmSimulation::DeleteAction(const kortex_driver::DeleteAction::Request& req) +{ + auto handle = req.input; + // If the action is not a default action + if (DEFAULT_ACTIONS_IDENTIFIERS.find(handle.identifier) == DEFAULT_ACTIONS_IDENTIFIERS.end()) + { + auto it = m_map_actions.find(handle.identifier); + if (it != m_map_actions.end()) + { + m_map_actions.erase(it); + ROS_INFO("Simulated action #%u properly deleted.", handle.identifier); + } + else + { + ROS_WARN("Could not find simulated action #%u to delete in actions map.", handle.identifier); + } + } + else + { + ROS_ERROR("Cannot delete default simulated actions."); + } + + return kortex_driver::DeleteAction::Response(); +} + +kortex_driver::UpdateAction::Response KortexArmSimulation::UpdateAction(const kortex_driver::UpdateAction::Request& req) +{ + auto action = req.input; + // If the action is not a default action + if (DEFAULT_ACTIONS_IDENTIFIERS.find(action.handle.identifier) == DEFAULT_ACTIONS_IDENTIFIERS.end()) + { + auto it = m_map_actions.find(action.handle.identifier); + if (it != m_map_actions.end()) + { + if (it->second.handle.action_type == action.handle.action_type) + { + it->second = action; + ROS_INFO("Simulated action #%u properly updated.", action.handle.identifier); + } + else + { + ROS_ERROR("Cannot update action with different type."); + } + } + else + { + ROS_ERROR("Could not find simulated action #%u to update in actions map.", action.handle.identifier); + } + } + else + { + ROS_ERROR("Cannot update default simulated actions."); + } + + return kortex_driver::UpdateAction::Response(); +} + +kortex_driver::ExecuteActionFromReference::Response KortexArmSimulation::ExecuteActionFromReference(const kortex_driver::ExecuteActionFromReference::Request& req) +{ + auto handle = req.input; + auto it = m_map_actions.find(handle.identifier); + if (it != m_map_actions.end()) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, it->second); + } + else + { + ROS_ERROR("Could not find action with given identifier %d", handle.identifier); + } + + return kortex_driver::ExecuteActionFromReference::Response(); +} + +kortex_driver::ExecuteAction::Response KortexArmSimulation::ExecuteAction(const kortex_driver::ExecuteAction::Request& req) +{ + auto action = req.input; + // Add Action to map if type is supported + switch (action.handle.action_type) + { + case kortex_driver::ActionType::REACH_JOINT_ANGLES: + case kortex_driver::ActionType::REACH_POSE: + case kortex_driver::ActionType::SEND_GRIPPER_COMMAND: + case kortex_driver::ActionType::TIME_DELAY: + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + break; + default: + ROS_ERROR("Unsupported action type %d : could not execute simulated action.", action.handle.action_type); + break; + } + + return kortex_driver::ExecuteAction::Response(); +} + +kortex_driver::StopAction::Response KortexArmSimulation::StopAction(const kortex_driver::StopAction::Request& req) +{ + if (m_is_action_being_executed.load()) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + } + + m_follow_joint_trajectory_action_client->cancelAllGoals(); + if (IsGripperPresent()) + { + m_gripper_action_client->cancelAllGoals(); + } + + return kortex_driver::StopAction::Response(); +} + +kortex_driver::PlayCartesianTrajectory::Response KortexArmSimulation::PlayCartesianTrajectory(const kortex_driver::PlayCartesianTrajectory::Request& req) +{ + auto constrained_pose = req.input; + kortex_driver::Action action; + action.name = "PlayCartesianTrajectory"; + action.handle.action_type = kortex_driver::ActionType::REACH_POSE; + action.oneof_action_parameters.reach_pose.push_back(constrained_pose); + + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + + return kortex_driver::PlayCartesianTrajectory::Response(); +} + +kortex_driver::SendTwistCommand::Response KortexArmSimulation::SendTwistCommand(const kortex_driver::SendTwistCommand::Request& req) +{ + auto twist_command = req.input; + kortex_driver::Action action; + action.name = "SendTwistCommand"; + action.handle.action_type = kortex_driver::ActionType::SEND_TWIST_COMMAND; + action.oneof_action_parameters.send_twist_command.push_back(twist_command); + + // Convert orientations to rad + m_twist_command.angular_x = m_math_util.toRad(m_twist_command.angular_x); + m_twist_command.angular_x = m_math_util.toRad(m_twist_command.angular_y); + m_twist_command.angular_x = m_math_util.toRad(m_twist_command.angular_z); + + // Fill the twist command + m_twist_command = twist_command.twist; + + // If we are already executing twist control, don't cancel the thread + if (m_current_action_type != kortex_driver::ActionType::SEND_TWIST_COMMAND) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + } + + return kortex_driver::SendTwistCommand::Response(); +} + +kortex_driver::PlayJointTrajectory::Response KortexArmSimulation::PlayJointTrajectory(const kortex_driver::PlayJointTrajectory::Request& req) +{ + auto constrained_joint_angles = req.input; + kortex_driver::Action action; + action.name = "PlayJointTrajectory"; + action.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES; + action.oneof_action_parameters.reach_joint_angles.push_back(constrained_joint_angles); + + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + + return kortex_driver::PlayJointTrajectory::Response(); +} + +kortex_driver::SendJointSpeedsCommand::Response KortexArmSimulation::SendJointSpeedsCommand(const kortex_driver::SendJointSpeedsCommand::Request& req) +{ + auto joint_speeds = req.input; + kortex_driver::Action action; + action.name = "SendJointSpeedsCommand"; + action.handle.action_type = kortex_driver::ActionType::SEND_JOINT_SPEEDS; + action.oneof_action_parameters.send_joint_speeds.push_back(joint_speeds); + + // Fill the velocity commands vector + int n = 0; + std::generate(m_velocity_commands.begin(), + m_velocity_commands.end(), + [this, &action, &n]() -> double + { + return m_math_util.toRad(action.oneof_action_parameters.send_joint_speeds[0].joint_speeds[n++].value); + }); + + // If we are already executing joint speed control, don't cancel the thread + if (m_current_action_type != kortex_driver::ActionType::SEND_JOINT_SPEEDS) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + } + + return kortex_driver::SendJointSpeedsCommand::Response(); +} + +kortex_driver::SendGripperCommand::Response KortexArmSimulation::SendGripperCommand(const kortex_driver::SendGripperCommand::Request& req) +{ + auto gripper_command = req.input; + kortex_driver::Action action; + action.name = "GripperCommand"; + action.handle.action_type = kortex_driver::ActionType::SEND_GRIPPER_COMMAND; + action.oneof_action_parameters.send_gripper_command.push_back(gripper_command); + + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + m_action_executor_thread = std::thread(&KortexArmSimulation::PlayAction, this, action); + + return kortex_driver::SendGripperCommand::Response(); +} + +kortex_driver::Stop::Response KortexArmSimulation::Stop(const kortex_driver::Stop::Request& req) +{ + // If an action is ongoing, cancel it first + if (m_is_action_being_executed.load()) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + } + m_follow_joint_trajectory_action_client->cancelAllGoals(); + if (IsGripperPresent()) + { + m_gripper_action_client->cancelAllGoals(); + } + return kortex_driver::Stop::Response(); +} + +kortex_driver::ApplyEmergencyStop::Response KortexArmSimulation::ApplyEmergencyStop(const kortex_driver::ApplyEmergencyStop::Request& req) +{ + // If an action is ongoing, cancel it first + if (m_is_action_being_executed.load()) + { + JoinThreadAndCancelAction(); // this will block until the thread is joined and current action finished + } + m_follow_joint_trajectory_action_client->cancelAllGoals(); + if (IsGripperPresent()) + { + m_gripper_action_client->cancelAllGoals(); + } + return kortex_driver::ApplyEmergencyStop::Response(); +} + +void KortexArmSimulation::cb_joint_states(const sensor_msgs::JointState& state) +{ + const std::lock_guard lock(m_state_mutex); + m_first_state_received = true; + m_current_state = state; +} + +void KortexArmSimulation::CreateDefaultActions() +{ + kortex_driver::Action retract, home, zero; + kortex_driver::ConstrainedJointAngles retract_angles, home_angles, zero_angles; + // Retract + retract.handle.identifier = 1; + retract.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES; + retract.handle.permission = 7; + retract.name = "Retract"; + for (int i = 0; i < m_degrees_of_freedom; i++) + { + kortex_driver::JointAngle a; + a.joint_identifier = i; + auto named_target = m_moveit_arm_interface->getNamedTargetValues("retract"); + double moveit_angle = named_target["joint_"+std::to_string(i+1)]; // rad + a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle)); + retract_angles.joint_angles.joint_angles.push_back(a); + } + retract.oneof_action_parameters.reach_joint_angles.push_back(retract_angles); + // Home + home.handle.identifier = 2; + home.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES; + home.handle.permission = 7; + home.name = "Home"; + for (int i = 0; i < m_degrees_of_freedom; i++) + { + kortex_driver::JointAngle a; + a.joint_identifier = i; + auto named_target = m_moveit_arm_interface->getNamedTargetValues("home"); + double moveit_angle = named_target["joint_"+std::to_string(i+1)]; // rad + a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle)); + home_angles.joint_angles.joint_angles.push_back(a); + } + home.oneof_action_parameters.reach_joint_angles.push_back(home_angles); + // Zero + zero.handle.identifier = 3; + zero.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES; + zero.handle.permission = 7; + zero.name = "Zero"; + for (int i = 0; i < m_degrees_of_freedom; i++) + { + kortex_driver::JointAngle a; + a.joint_identifier = i; + auto named_target = m_moveit_arm_interface->getNamedTargetValues("vertical"); + double moveit_angle = named_target["joint_"+std::to_string(i+1)]; // rad + a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle)); + zero_angles.joint_angles.joint_angles.push_back(a); + } + zero.oneof_action_parameters.reach_joint_angles.push_back(zero_angles); + // Add actions + m_map_actions.emplace(std::make_pair(retract.handle.identifier, retract)); + m_map_actions.emplace(std::make_pair(home.handle.identifier, home)); + m_map_actions.emplace(std::make_pair(zero.handle.identifier, zero)); +} + +bool KortexArmSimulation::SwitchControllerType(ControllerType new_type) +{ + bool success = true; + controller_manager_msgs::SwitchController service; + service.request.strictness = service.request.STRICT; + if (m_active_controller_type != new_type) + { + // Set the controllers we want to switch to + switch (new_type) + { + case ControllerType::kTrajectory: + service.request.start_controllers = m_trajectory_controllers_list; + service.request.stop_controllers = m_position_controllers_list; + break; + case ControllerType::kIndividual: + service.request.start_controllers = m_position_controllers_list; + service.request.stop_controllers = m_trajectory_controllers_list; + break; + default: + ROS_ERROR("Kortex arm simulator : Unsupported controller type %d", int(new_type)); + return false; + } + + // Call the service + if (!m_client_switch_controllers.call(service)) + { + ROS_ERROR("Failed to call the service for switching controllers"); + success = false; + } + else + { + success = service.response.ok; + } + + // Update active type if the switch was successful + if (success) + { + m_active_controller_type = new_type; + } + } + + return success; +} + +kortex_driver::KortexError KortexArmSimulation::FillKortexError(uint32_t code, uint32_t subCode, const std::string& description) const +{ + kortex_driver::KortexError error; + error.code = code; + error.subCode = subCode; + error.description = description; + return error; +} + +void KortexArmSimulation::JoinThreadAndCancelAction() +{ + // Tell the thread to stop and join it + m_action_preempted = true; + if (m_action_executor_thread.joinable()) + { + m_action_executor_thread.join(); + } + m_current_action_type = 0; + m_action_preempted = false; +} + +void KortexArmSimulation::PlayAction(const kortex_driver::Action& action) +{ + auto action_result = FillKortexError(kortex_driver::ErrorCodes::ERROR_NONE, kortex_driver::SubErrorCodes::SUB_ERROR_NONE); + + // Notify action started + kortex_driver::ActionNotification start_notif; + start_notif.handle = action.handle; + start_notif.action_event = kortex_driver::ActionEvent::ACTION_START; + m_pub_action_topic.publish(start_notif); + m_is_action_being_executed = true; + m_current_action_type = action.handle.action_type; + + // Switch executor on the action type + switch (action.handle.action_type) + { + case kortex_driver::ActionType::REACH_JOINT_ANGLES: + action_result = ExecuteReachJointAngles(action); + break; + case kortex_driver::ActionType::REACH_POSE: + action_result = ExecuteReachPose(action); + break; + case kortex_driver::ActionType::SEND_JOINT_SPEEDS: + action_result = ExecuteSendJointSpeeds(action); + break; + case kortex_driver::ActionType::SEND_TWIST_COMMAND: + action_result = ExecuteSendTwist(action); + break; + case kortex_driver::ActionType::SEND_GRIPPER_COMMAND: + action_result = ExecuteSendGripperCommand(action); + break; + case kortex_driver::ActionType::TIME_DELAY: + action_result = ExecuteTimeDelay(action); + break; + default: + action_result = FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, kortex_driver::SubErrorCodes::UNSUPPORTED_ACTION); + break; + } + + // Oddly enough, gripper actions don't send notifications through Kortex API when they end + if (action.handle.action_type != kortex_driver::ActionType::SEND_GRIPPER_COMMAND) + { + kortex_driver::ActionNotification end_notif; + end_notif.handle = action.handle; + // Action was cancelled by user and is not a velocity command + if (m_action_preempted.load() && action.handle.action_type != kortex_driver::ActionType::SEND_JOINT_SPEEDS) + { + // Notify ACTION_ABORT + end_notif.action_event = kortex_driver::ActionEvent::ACTION_ABORT; + ROS_WARN("Action was aborted by user."); + } + // Action ended on its own + else + { + if (action_result.code != kortex_driver::ErrorCodes::ERROR_NONE) + { + // Notify ACTION_ABORT + end_notif.action_event = kortex_driver::ActionEvent::ACTION_ABORT; + end_notif.abort_details = action_result.subCode; + ROS_WARN("Action was failed : \nError code is %d\nSub-error code is %d\nError description is : %s", + action_result.code, + action_result.subCode, + action_result.description.c_str()); + } + else + { + // Notify ACTION_END + end_notif.action_event = kortex_driver::ActionEvent::ACTION_END; + } + } + m_pub_action_topic.publish(end_notif); + } + + m_is_action_being_executed = false; +} + +kortex_driver::KortexError KortexArmSimulation::ExecuteReachJointAngles(const kortex_driver::Action& action) +{ + auto result = FillKortexError(kortex_driver::ErrorCodes::ERROR_NONE, kortex_driver::SubErrorCodes::SUB_ERROR_NONE); + if (action.oneof_action_parameters.reach_joint_angles.size() != 1) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing joint angles action : action is malformed."); + } + auto constrained_joint_angles = action.oneof_action_parameters.reach_joint_angles[0]; + if (constrained_joint_angles.joint_angles.joint_angles.size() != GetDOF()) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing joint angles action : action contains " + std::to_string(constrained_joint_angles.joint_angles.joint_angles.size()) + " joint angles but arm has " + std::to_string(GetDOF())); + } + + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kTrajectory)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing joint angles action : simulated trajectory controller could not be switched to."); + } + + // Initialize trajectory object + trajectory_msgs::JointTrajectory traj; + traj.header.frame_id = m_prefix + "base_link"; + for (int i = 0; i < constrained_joint_angles.joint_angles.joint_angles.size(); i++) + { + const std::string joint_name = m_prefix + "joint_" + std::to_string(i+1); //joint names are 1-based + traj.joint_names.push_back(joint_name); + } + + // Get current position + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Transform kortex structure to trajectory_msgs to fill endpoint structure + trajectory_msgs::JointTrajectoryPoint endpoint; + for (int i = 0; i < constrained_joint_angles.joint_angles.joint_angles.size(); i++) + { + // If the current actuator has turned on itself many times, we need the endpoint to follow that trend too + int n_turns = 0; + m_math_util.wrapRadiansFromMinusPiToPi(current.position[m_first_arm_joint_index + i], n_turns); + const double rad_wrapped_goal = m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(constrained_joint_angles.joint_angles.joint_angles[i].value)); + endpoint.positions.push_back(rad_wrapped_goal + double(n_turns) * 2.0 * M_PI); + endpoint.velocities.push_back(0.0); + endpoint.accelerations.push_back(0.0); + } + + // Calculate velocity profiles to know how much time this trajectory must last + switch (constrained_joint_angles.constraint.type) + { + // If the duration is supplied, set the duration of the velocity profiles with that value + case kortex_driver::JointTrajectoryConstraintType::JOINT_CONSTRAINT_DURATION: + { + // Error check on the given duration + if (constrained_joint_angles.constraint.value <= 0.0f) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Invalid duration constraint : it has to be higher than 0.0!"); + } + // Set the velocity profiles + for (int i = 0; i < GetDOF(); i++) + { + m_velocity_trap_profiles[i].SetProfileDuration(current.position[m_first_arm_joint_index + i], endpoint.positions[i], constrained_joint_angles.constraint.value); + } + endpoint.time_from_start = ros::Duration(constrained_joint_angles.constraint.value); + ROS_DEBUG("Using supplied duration : %2.2f", constrained_joint_angles.constraint.value); + break; + } + // If a max velocity is supplied for each joint, we need to find the limiting duration with this velocity constraint + case kortex_driver::JointTrajectoryConstraintType::JOINT_CONSTRAINT_SPEED: + { + // Error check on the given velocity + float max_velocity = m_math_util.toRad(constrained_joint_angles.constraint.value); + if (max_velocity <= 0.0f) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Invalid velocity constraint : it has to be higher than 0.0!"); + } + // Find the limiting duration with given velocity + double max_duration = 0.0; + for (int i = 0; i < GetDOF(); i++) + { + double velocity_ratio = std::min(1.0, double(max_velocity)/m_arm_velocity_max_limits[i]); + m_velocity_trap_profiles[i].SetProfileVelocity(current.position[m_first_arm_joint_index + i], endpoint.positions[i], velocity_ratio); + max_duration = std::max(max_duration, m_velocity_trap_profiles[i].Duration()); + ROS_DEBUG("Joint %d moving from %2.2f to %2.2f gives duration %2.2f", i, current.position[m_first_arm_joint_index + i], endpoint.positions[i], m_velocity_trap_profiles[i].Duration()); + } + ROS_DEBUG("max_duration is : %2.2f", max_duration); + // Set the velocity profiles + for (int i = 0; i < GetDOF(); i++) + { + m_velocity_trap_profiles[i].SetProfileDuration(current.position[m_first_arm_joint_index + i], endpoint.positions[i], max_duration); + } + endpoint.time_from_start = ros::Duration(max_duration); + break; + } + default: + { + // Find the optimal duration based on actual velocity and acceleration limits + double optimal_duration = 0.0; + for (int i = 0; i < GetDOF(); i++) + { + m_velocity_trap_profiles[i].SetProfile(current.position[m_first_arm_joint_index + i], endpoint.positions[i]); + optimal_duration = std::max(optimal_duration, m_velocity_trap_profiles[i].Duration()); + ROS_DEBUG("Joint %d moving from %2.2f to %2.2f gives duration %2.2f", i, current.position[m_first_arm_joint_index + i], endpoint.positions[i], m_velocity_trap_profiles[i].Duration()); + } + ROS_DEBUG("optimal_duration is : %2.2f", optimal_duration); + // Set the velocity profiles + for (int i = 0; i < GetDOF(); i++) + { + m_velocity_trap_profiles[i].SetProfileDuration(current.position[m_first_arm_joint_index + i], endpoint.positions[i], optimal_duration); + } + endpoint.time_from_start = ros::Duration(optimal_duration); + break; + } + } + + // Copy velocity profile data into trajectory using JOINT_TRAJECTORY_TIMESTEP_SECONDS timesteps + // For each timestep + for (double t = JOINT_TRAJECTORY_TIMESTEP_SECONDS; t < m_velocity_trap_profiles[0].Duration(); t += JOINT_TRAJECTORY_TIMESTEP_SECONDS) + { + // Create trajectory point + trajectory_msgs::JointTrajectoryPoint p; + p.time_from_start = ros::Duration(t); + // Add position, velocity, acceleration from each velocity profile + for (int i = 0; i < GetDOF(); i++) + { + p.positions.push_back(m_velocity_trap_profiles[i].Pos(t)); + p.velocities.push_back(m_velocity_trap_profiles[i].Vel(t)); + p.accelerations.push_back(m_velocity_trap_profiles[i].Acc(t)); + } + // Add trajectory point to goal + traj.points.push_back(p); + } + // Finally, add endpoint to trajectory + // Add position, velocity, acceleration from each velocity profile + trajectory_msgs::JointTrajectoryPoint p; + p.time_from_start = ros::Duration(m_velocity_trap_profiles[0].Duration()); + for (int i = 0; i < GetDOF(); i++) + { + p.positions.push_back(m_velocity_trap_profiles[i].Pos(m_velocity_trap_profiles[i].Duration())); + p.velocities.push_back(m_velocity_trap_profiles[i].Vel(m_velocity_trap_profiles[i].Duration())); + p.accelerations.push_back(m_velocity_trap_profiles[i].Acc(m_velocity_trap_profiles[i].Duration())); + } + // Add trajectory point to goal + traj.points.push_back(p); + + // Verify if goal has been cancelled before sending it + if (m_action_preempted.load()) + { + return result; + } + + // Send goal + control_msgs::FollowJointTrajectoryActionGoal goal; + traj.header.stamp = ros::Time::now(); + goal.goal.trajectory = traj; + m_follow_joint_trajectory_action_client->sendGoal(goal.goal); + + // Wait for goal to be done, or for preempt to be called (check every 100ms) + while(!m_action_preempted.load()) + { + if (m_follow_joint_trajectory_action_client->waitForResult(ros::Duration(0.1f))) + { + // Sometimes an error is thrown related to a bad cast in a ros::time structure inside the SimpleActionClient + // See https://answers.ros.org/question/209452/exception-thrown-while-processing-service-call-time-is-out-of-dual-32-bit-range/ + // If this error happens here we just send the goal again with an updated timestamp + auto status = m_follow_joint_trajectory_action_client->getResult(); + if (status->error_string == "Time is out of dual 32-bit range") + { + traj.header.stamp = ros::Time::now(); + goal.goal.trajectory = traj; + m_follow_joint_trajectory_action_client->sendGoal(goal.goal); + } + else + { + break; + } + } + } + + // If we got out of the loop because we're preempted, cancel the goal before returning + if (m_action_preempted.load()) + { + m_follow_joint_trajectory_action_client->cancelAllGoals(); + } + // Fill result depending on action final status if user didn't cancel + else + { + auto status = m_follow_joint_trajectory_action_client->getResult(); + if (status->error_code != status->SUCCESSFUL) + { + result = FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + status->error_string); + } + } + return result; +} + +kortex_driver::KortexError KortexArmSimulation::ExecuteReachPose(const kortex_driver::Action& action) +{ + kortex_driver::KortexError result; + result.code = kortex_driver::ErrorCodes::ERROR_NONE; + result.subCode = kortex_driver::SubErrorCodes::SUB_ERROR_NONE; + if (action.oneof_action_parameters.reach_pose.size() != 1) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing pose action : action is malformed."); + } + auto constrained_pose = action.oneof_action_parameters.reach_pose[0]; + + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kTrajectory)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing pose action : simulated trajectory controller could not be switched to."); + } + + // Get current position + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Get Start frame + // For the Rotation part : ThetaX = gamma, ThetaY = beta, ThetaZ = alpha + auto start = KDL::Frame(); + Eigen::VectorXd positions_eigen(m_degrees_of_freedom); + for (int i = 0; i < GetDOF(); i++) + { + positions_eigen[i] = current.position[m_first_arm_joint_index + i]; + } + KDL::JntArray current_kdl(GetDOF()); + current_kdl.data = positions_eigen; + m_fk_solver->JntToCart(current_kdl, start); + + { + ROS_DEBUG("START FRAME :"); + ROS_DEBUG("X=%2.4f Y=%2.4f Z=%2.4f", start.p[0], start.p[1], start.p[2]); + double sa, sb, sg; start.M.GetEulerZYX(sa, sb, sg); + ROS_DEBUG("ALPHA=%2.4f BETA=%2.4f GAMMA=%2.4f", m_math_util.toDeg(sa), m_math_util.toDeg(sb), m_math_util.toDeg(sg)); + KDL::Vector axis; + ROS_DEBUG("start rot = %2.4f", start.M.GetRotAngle(axis)); + } + + // Get End frame + auto end_pos = KDL::Vector(constrained_pose.target_pose.x, constrained_pose.target_pose.y, constrained_pose.target_pose.z); + auto end_rot = KDL::Rotation::EulerZYX(m_math_util.toRad(constrained_pose.target_pose.theta_z), m_math_util.toRad(constrained_pose.target_pose.theta_y), m_math_util.toRad(constrained_pose.target_pose.theta_x)); + KDL::Frame end(end_rot, end_pos); + + { + ROS_DEBUG("END FRAME :"); + ROS_DEBUG("X=%2.4f Y=%2.4f Z=%2.4f", end_pos[0], end_pos[1], end_pos[2]); + double ea, eb, eg; end_rot.GetEulerZYX(ea, eb, eg); + ROS_DEBUG("ALPHA=%2.4f BETA=%2.4f GAMMA=%2.4f", m_math_util.toDeg(ea), m_math_util.toDeg(eb), m_math_util.toDeg(eg)); + KDL::Vector axis; + ROS_DEBUG("end rot = %2.4f", end_rot.GetRotAngle(axis)); + } + + // If different speed limits than the default ones are provided, use them instead + float translation_speed_limit = m_max_cartesian_twist_linear; + float rotation_speed_limit = m_max_cartesian_twist_angular; + if (!constrained_pose.constraint.oneof_type.speed.empty()) + { + // If a max velocity is supplied for each joint, we need to find the limiting duration with this velocity constraint + translation_speed_limit = std::min(constrained_pose.constraint.oneof_type.speed[0].translation, translation_speed_limit); + rotation_speed_limit = std::min(constrained_pose.constraint.oneof_type.speed[0].orientation, rotation_speed_limit); + } + + // Calculate norm of translation movement and minimum duration to move this amount given max translation speed + double delta_pos = (end_pos - start.p).Norm(); + double minimum_translation_duration = delta_pos / m_max_cartesian_twist_linear; // in seconds + + // Calculate angle variation of rotation movement and minimum duration to move this amount given max rotation speed + KDL::Vector axis; // we need to create this variable to access the RotAngle for start and end frames'rotation components + KDL::Rotation dR = end_rot * start.M.Inverse(); + double delta_rot = dR.GetRotAngle(axis); + double minimum_rotation_duration = delta_rot / m_max_cartesian_twist_angular; // in seconds + + ROS_INFO("trans : %2.4f rot : %2.4f", minimum_translation_duration, minimum_rotation_duration); + + // The default value for the duration will be the longer duration of the two + double duration = std::max(minimum_translation_duration, minimum_rotation_duration); + + // eq_radius is chosen here to make it so translations and rotations are normalised + // Here is a good explanation for it : https://github.com/zakharov/BRICS_RN/blob/master/navigation_trajectory_common/include/navigation_trajectory_common/Conversions.h#L358-L382 + float eq_radius = translation_speed_limit / rotation_speed_limit; + + // Create Path_Line object + // I know this is ugly but the RotationalInterpolation object is mandatory and needs to be created as such + KDL::Path_Line line(start, end, new KDL::RotationalInterpolation_SingleAxis(), eq_radius); + + // Create a trapezoidal velocity profile for the Cartesian trajectory to parametrize it in time + KDL::VelocityProfile_Trap velocity_profile(std::min(translation_speed_limit, rotation_speed_limit), m_max_cartesian_acceleration_linear); + velocity_profile.SetProfile(0.0, line.PathLength()); + duration = std::max(duration, velocity_profile.Duration()); + + // If duration is not supplied, use the one we just calculated + // If the duration is supplied, simply use it + if (!constrained_pose.constraint.oneof_type.duration.empty()) + { + double supplied_duration = constrained_pose.constraint.oneof_type.duration[0]; + if (duration > supplied_duration) + { + ROS_WARN("Cannot use supplied duration %2.4f because the minimum duration based on velocity limits is %2.4f", + supplied_duration, + duration); + } + duration = std::max(duration, supplied_duration); + } + + // Set the velocity profile duration + velocity_profile.SetProfileDuration(0.0, line.PathLength(), duration); + KDL::Trajectory_Segment segment(&line, &velocity_profile, false); + ROS_DEBUG("Duration of trajectory will be %2.4f seconds", duration); + + // Initialize trajectory object + trajectory_msgs::JointTrajectory traj; + traj.header.frame_id = m_prefix + "base_link"; + traj.header.stamp = ros::Time::now(); + for (int i = 0; i < GetDOF(); i++) + { + const std::string joint_name = m_prefix + "joint_" + std::to_string(i+1); //joint names are 1-based + traj.joint_names.push_back(joint_name); + } + + // Fill trajectory object + KDL::JntArray previous = current_kdl; // Position i - 1, initialise to starting angles + KDL::JntArray current_joints(GetDOF()); // Position i + for (float t = JOINT_TRAJECTORY_TIMESTEP_SECONDS; t < duration; t += JOINT_TRAJECTORY_TIMESTEP_SECONDS) + { + // First get the next Cartesian position and twists + auto pos = segment.Pos(t); + + // Position is enough to have a smooth trajectory it seems but if eventually vel and acc are useful somehow this is how to get them: + // auto vel = segment.Vel(t); + // auto acc = segment.Acc(t); + + // Create trajectory point + trajectory_msgs::JointTrajectoryPoint p; + p.time_from_start = ros::Duration(t); + + // Use inverse IK solver + int code = m_ik_pos_solver->CartToJnt(previous, pos, current_joints); + if (code != m_ik_pos_solver->E_NOERROR) + { + ROS_ERROR("IK ERROR CODE = %d", code); + } + + for (int i = 0; i < GetDOF(); i++) + { + p.positions.push_back(current_joints(i)); + } + + // Add trajectory point to goal + traj.points.push_back(p); + previous = current_joints; + } + + // Add last point + trajectory_msgs::JointTrajectoryPoint p; + p.time_from_start = ros::Duration(segment.Duration()); + auto pos = segment.Pos(segment.Duration()); + int code = m_ik_pos_solver->CartToJnt(previous, pos, current_joints); + for (int i = 0; i < GetDOF(); i++) + { + p.positions.push_back(current_joints(i)); + } + + // Add trajectory point to goal + traj.points.push_back(p); + + // Verify if goal has been cancelled before sending it + if (m_action_preempted.load()) + { + return result; + } + + // Send goal + control_msgs::FollowJointTrajectoryActionGoal goal; + goal.goal.trajectory = traj; + m_follow_joint_trajectory_action_client->sendGoal(goal.goal); + + // Wait for goal to be done, or for preempt to be called (check every 10ms) + while(!m_action_preempted.load() && !m_follow_joint_trajectory_action_client->waitForResult(ros::Duration(0.01f))) {} + + // If we got out of the loop because we're preempted, cancel the goal before returning + if (m_action_preempted.load()) + { + m_follow_joint_trajectory_action_client->cancelAllGoals(); + } + // Fill result depending on action final status if user didn't cancel + else + { + auto status = m_follow_joint_trajectory_action_client->getResult(); + if (status->error_code != status->SUCCESSFUL) + { + result = FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + status->error_string); + } + } + return result; +} + +kortex_driver::KortexError KortexArmSimulation::ExecuteSendJointSpeeds(const kortex_driver::Action& action) +{ + kortex_driver::KortexError result; + result.code = kortex_driver::ErrorCodes::ERROR_NONE; + result.subCode = kortex_driver::SubErrorCodes::SUB_ERROR_NONE; + if (action.oneof_action_parameters.send_joint_speeds.size() != 1) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing joints speeds : action is malformed."); + } + auto joint_speeds = action.oneof_action_parameters.send_joint_speeds[0]; + if (joint_speeds.joint_speeds.size() != GetDOF()) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing joint speeds action : action contains " + std::to_string(joint_speeds.joint_speeds.size()) + " joint speeds but arm has " + std::to_string(GetDOF())); + } + + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kIndividual)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing joint speeds action : simulated positions controllers could not be switched to."); + } + + // Get current position + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Initialise commands + std::vector commands(GetDOF(), 0.0); // in rad + for (int i = 0; i < GetDOF(); i++) + { + commands[i] = current.position[m_first_arm_joint_index + i]; + } + std::vector previous_commands = commands; // in rad + std::vector velocity_commands(GetDOF(), 0.0); // in rad/s + std::vector previous_velocity_commands(GetDOF(), 0.0); // in rad/s + std::vector stopped(GetDOF(), false); + + // While we're not done + while (true) + { + // If action is preempted, set the velocities to 0 + if (m_action_preempted.load()) + { + std::fill(m_velocity_commands.begin(), m_velocity_commands.end(), 0.0); + } + // For each joint + for (int i = 0; i < GetDOF(); i++) + { + // Calculate real position increment + // This helps to know if we hit joint limits or if we stopped + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Calculate permitted velocity command because we don't have infinite acceleration + double vel_delta = m_velocity_commands[i] - previous_velocity_commands[i]; + double max_delta = std::copysign(m_arm_acceleration_max_limits[i] * JOINT_TRAJECTORY_TIMESTEP_SECONDS, vel_delta); + + // If the velocity change is within acceleration limits for this timestep + double velocity_command; + if (fabs(vel_delta) < fabs(max_delta)) + { + velocity_command = m_velocity_commands[i]; + } + // If we cannot instantly accelerate to this velocity + else + { + velocity_command = previous_velocity_commands[i] + max_delta; + } + + // Cap to the velocity limit for the joint + velocity_command = std::copysign(std::min(fabs(velocity_command), double(fabs(m_arm_velocity_max_limits[i]))), velocity_command); + + // Check if velocity command is in fact too small + if (fabs(velocity_command) < MINIMUM_JOINT_VELOCITY_RAD_PER_SECONDS) + { + velocity_command = 0.0; + commands[i] = current.position[m_first_arm_joint_index + i]; + stopped[i] = true; + } + // Else calculate the position increment and send it + else + { + commands[i] = previous_commands[i] + velocity_command * JOINT_TRAJECTORY_TIMESTEP_SECONDS; + stopped[i] = false; + + // Cap the command to the joint limit + if (m_arm_joint_limits_min[i] != 0.0 && commands[i] < m_arm_joint_limits_min[i]) + { + commands[i] = m_arm_joint_limits_min[i]; + velocity_command = std::max(velocity_command, 0.0); + } + else if (m_arm_joint_limits_max[i] != 0.0 && commands[i] > m_arm_joint_limits_max[i]) + { + commands[i] = m_arm_joint_limits_max[i]; + velocity_command = std::min(velocity_command, 0.0); + } + + // Send the position increments to the controllers + std_msgs::Float64 message; + message.data = commands[i]; + m_pub_position_controllers[i].publish(message); + } + + // Remember actual command as previous and actual velocity command as previous + previous_commands[i] = commands[i]; + previous_velocity_commands[i] = velocity_command; + } + + // Sleep for TIMESTEP + std::this_thread::sleep_for(std::chrono::milliseconds(int(1000*JOINT_TRAJECTORY_TIMESTEP_SECONDS))); + + // If the action is preempted and we're back to zero velocity, we're done here + if (m_action_preempted.load()) + { + // Check if all joints are stopped and break if yes + if (std::all_of(stopped.begin(), stopped.end(), [](bool b){return b;})) + { + break; + } + } + } + + return result; +} + +kortex_driver::KortexError KortexArmSimulation::ExecuteSendTwist(const kortex_driver::Action& action) +{ + kortex_driver::KortexError result; + result.code = kortex_driver::ErrorCodes::ERROR_NONE; + result.subCode = kortex_driver::SubErrorCodes::SUB_ERROR_NONE; + if (action.oneof_action_parameters.send_twist_command.size() != 1) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing twist action : action is malformed."); + } + auto twist = action.oneof_action_parameters.send_twist_command[0]; + + // Switch to trajectory controller + if (!SwitchControllerType(ControllerType::kIndividual)) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "Error playing joint speeds action : simulated positions controllers could not be switched to."); + } + + // Only mixed frame is supported in simulation + if (twist.reference_frame != kortex_driver::CartesianReferenceFrame::CARTESIAN_REFERENCE_FRAME_MIXED) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing twist action : only mixed frame is supported in simulation."); + } + + // Get current position + sensor_msgs::JointState current; + { + const std::lock_guard lock(m_state_mutex); + current = m_current_state; + } + + // Initialise commands + std::vector commands(GetDOF(), 0.0); // in rad + for (int i = 0; i < GetDOF(); i++) + { + commands[i] = current.position[m_first_arm_joint_index + i]; + } + std::vector previous_commands = commands; // in rad + std::vector previous_velocity_commands(GetDOF(), 0.0); // in rad/s + std::vector stopped(GetDOF(), false); + kortex_driver::Twist twist_command = m_twist_command; + kortex_driver::Twist previous_twist_command; + + // While we're not done + while (ros::ok()) + { + // If action is preempted, set the velocities to 0 + if (m_action_preempted.load()) + { + m_twist_command = kortex_driver::Twist(); + } + + // Calculate actual twist command considering max linear and angular accelerations + double max_linear_twist_delta = JOINT_TRAJECTORY_TIMESTEP_SECONDS * m_max_cartesian_acceleration_linear; + double max_angular_twist_delta = JOINT_TRAJECTORY_TIMESTEP_SECONDS * m_max_cartesian_acceleration_angular; + kortex_driver::Twist delta_twist = m_math_util.substractTwists(m_twist_command, previous_twist_command); + + // If the velocity change is within acceleration limits for this timestep + if (fabs(delta_twist.linear_x) < fabs(max_linear_twist_delta)) + { + twist_command.linear_x = m_twist_command.linear_x; + } + // If we cannot instantly accelerate to this velocity + else + { + twist_command.linear_x = previous_twist_command.linear_x + std::copysign(max_linear_twist_delta, delta_twist.linear_x); + } + // same for linear_y + if (fabs(delta_twist.linear_y) < fabs(max_linear_twist_delta)) + { + twist_command.linear_y = m_twist_command.linear_y; + } + else + { + twist_command.linear_y = previous_twist_command.linear_y + std::copysign(max_linear_twist_delta, delta_twist.linear_y); + } + // same for linear_z + if (fabs(delta_twist.linear_z) < fabs(max_linear_twist_delta)) + { + twist_command.linear_z = m_twist_command.linear_z; + } + else + { + twist_command.linear_z = previous_twist_command.linear_z + std::copysign(max_linear_twist_delta, delta_twist.linear_z); + } + // same for angular_x + if (fabs(delta_twist.angular_x) < fabs(max_angular_twist_delta)) + { + twist_command.angular_x = m_twist_command.angular_x; + } + else + { + twist_command.angular_x = previous_twist_command.angular_x + std::copysign(max_angular_twist_delta, delta_twist.angular_x); + } + // same for angular_y + if (fabs(delta_twist.angular_y) < fabs(max_angular_twist_delta)) + { + twist_command.angular_y = m_twist_command.angular_y; + } + else + { + twist_command.angular_y = previous_twist_command.angular_y + std::copysign(max_angular_twist_delta, delta_twist.angular_y); + } + // same for angular_z + if (fabs(delta_twist.angular_z) < fabs(max_angular_twist_delta)) + { + twist_command.angular_z = m_twist_command.angular_z; + } + else + { + twist_command.angular_z = previous_twist_command.angular_z + std::copysign(max_angular_twist_delta, delta_twist.angular_z); + } + + // Cap to the velocity limit + twist_command.linear_x = std::copysign(std::min(fabs(twist_command.linear_x), fabs(m_max_cartesian_twist_linear)), twist_command.linear_x); + twist_command.linear_y = std::copysign(std::min(fabs(twist_command.linear_y), fabs(m_max_cartesian_twist_linear)), twist_command.linear_y); + twist_command.linear_z = std::copysign(std::min(fabs(twist_command.linear_z), fabs(m_max_cartesian_twist_linear)), twist_command.linear_z); + twist_command.angular_x = std::copysign(std::min(fabs(twist_command.angular_x), fabs(m_max_cartesian_twist_angular)), twist_command.angular_x); + twist_command.angular_y = std::copysign(std::min(fabs(twist_command.angular_y), fabs(m_max_cartesian_twist_angular)), twist_command.angular_y); + twist_command.angular_z = std::copysign(std::min(fabs(twist_command.angular_z), fabs(m_max_cartesian_twist_angular)), twist_command.angular_z); + + // Fill current joint position commands KDL structure + KDL::JntArray commands_kdl(GetDOF()); + Eigen::VectorXd commands_eigen(GetDOF()); + for (int i = 0; i < GetDOF(); i++) + { + commands_eigen[i] = commands[i]; + } + commands_kdl.data = commands_eigen; + + // Fill KDL Twist structure with Kortex twist + KDL::Twist twist_kdl = KDL::Twist(KDL::Vector(twist_command.linear_x, twist_command.linear_y, twist_command.linear_z), + KDL::Vector(twist_command.angular_x, twist_command.angular_y, twist_command.angular_z)); + + // Call IK and fill joint velocity commands + KDL::JntArray joint_velocities(GetDOF()); + int ik_result = m_ik_vel_solver->CartToJnt(commands_kdl, twist_kdl, joint_velocities); + if (ik_result != m_ik_vel_solver->E_NOERROR) + { + ROS_WARN("IK ERROR = %d", ik_result); + } + + // We need to know if the joint velocities have to be adjusted, and by what ratio + double ratio = 1.0; + for (int i = 0; i < GetDOF(); i++) + { + // Calculate permitted velocity command because we don't have infinite acceleration + double vel_delta = joint_velocities(i) - previous_velocity_commands[i]; + double max_delta = std::copysign(m_arm_acceleration_max_limits[i] * JOINT_TRAJECTORY_TIMESTEP_SECONDS, vel_delta); + + // If we cannot instantly accelerate to this velocity + if (fabs(vel_delta) > fabs(max_delta)) + { + ratio = std::max(ratio, fabs(vel_delta / max_delta)); + } + } + + // Command the velocities + // For each joint + for (int i = 0; i < GetDOF(); i++) + { + // Calculate position increment + commands[i] = previous_commands[i] + joint_velocities(i) / ratio * JOINT_TRAJECTORY_TIMESTEP_SECONDS; + + // Cap the command to the joint limit + if (m_arm_joint_limits_min[i] != 0.0 && commands[i] < 0.0) + { + commands[i] = std::max(m_arm_joint_limits_min[i], commands[i]); + } + else if (m_arm_joint_limits_max[i] != 0.0 && commands[i] > 0.0) + { + commands[i] = std::min(m_arm_joint_limits_max[i], commands[i]); + } + + // Send the position increments to the controllers + std_msgs::Float64 message; + message.data = commands[i]; + m_pub_position_controllers[i].publish(message); + + // Check if joint is stopped or not + stopped[i] = fabs(joint_velocities(i)) < MINIMUM_JOINT_VELOCITY_RAD_PER_SECONDS; + + // Remember actual command as previous + previous_commands[i] = commands[i]; + previous_velocity_commands[i] = joint_velocities(i); + } + + // Put current values to previous + previous_twist_command = twist_command; + + // Sleep for TIMESTEP + std::this_thread::sleep_for(std::chrono::milliseconds(int(1000*JOINT_TRAJECTORY_TIMESTEP_SECONDS))); + + // If the action is preempted and we're back to zero velocity, we're done here + if (m_action_preempted.load()) + { + // Check if all joints are stopped and break if yes + if (std::all_of(stopped.begin(), stopped.end(), [](bool b){return b;})) + { + break; + } + } + } + + return result; +} + +kortex_driver::KortexError KortexArmSimulation::ExecuteSendGripperCommand(const kortex_driver::Action& action) +{ + kortex_driver::KortexError result; + result.code = kortex_driver::ErrorCodes::ERROR_NONE; + result.subCode = kortex_driver::SubErrorCodes::SUB_ERROR_NONE; + if (action.oneof_action_parameters.send_gripper_command.size() != 1) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing gripper command action : action is malformed."); + } + auto gripper_command = action.oneof_action_parameters.send_gripper_command[0]; + + if (gripper_command.gripper.finger.size() != 1) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::INVALID_PARAM, + "Error playing gripper command action : there must be exactly one finger"); + } + + if (gripper_command.mode != kortex_driver::GripperMode::GRIPPER_POSITION) + { + return FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::UNSUPPORTED_ACTION, + "Error playing gripper command action : gripper mode " + std::to_string(gripper_command.mode) + " is not supported; only position is."); + } + + // The incoming command is relative [0,1] and we need to put it in absolute unit [m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0]]: + double absolute_gripper_command = m_math_util.absolute_position_from_relative(gripper_command.gripper.finger[0].value, m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0]); + + // Create the goal + control_msgs::GripperCommandGoal goal; + goal.command.position = absolute_gripper_command; + + // Verify if goal has been cancelled before sending it + if (m_action_preempted.load()) + { + return result; + } + + // Send goal + m_gripper_action_client->sendGoal(goal); + + // Wait for goal to be done, or for preempt to be called (check every 10ms) + while(!m_action_preempted.load() && !m_gripper_action_client->waitForResult(ros::Duration(0.01f))) {} + + // If we got out of the loop because we're preempted, cancel the goal before returning + if (m_action_preempted.load()) + { + m_gripper_action_client->cancelAllGoals(); + } + // Fill result depending on action final status if user didn't cancel + else + { + auto status = m_gripper_action_client->getResult(); + + if (!status->reached_goal) + { + result = FillKortexError(kortex_driver::ErrorCodes::ERROR_DEVICE, + kortex_driver::SubErrorCodes::METHOD_FAILED, + "The gripper command failed during execution."); + } + } + return result; +} + +kortex_driver::KortexError KortexArmSimulation::ExecuteTimeDelay(const kortex_driver::Action& action) +{ + auto result = FillKortexError(kortex_driver::ErrorCodes::ERROR_NONE, + kortex_driver::SubErrorCodes::SUB_ERROR_NONE); + if (!action.oneof_action_parameters.delay.empty()) + { + auto start = std::chrono::system_clock::now(); + uint32_t delay_seconds = action.oneof_action_parameters.delay[0].duration; + // While not preempted and duration not elapsed + while (!m_action_preempted.load() && (std::chrono::system_clock::now() - start) < std::chrono::seconds(delay_seconds)) + { + // sleep a bit + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + else + { + result.code = kortex_driver::ErrorCodes::ERROR_DEVICE; + result.subCode = kortex_driver::SubErrorCodes::INVALID_PARAM; + result.description = "Error playing time delay action : action is malformed."; + } + return result; +} + +void KortexArmSimulation::new_joint_speeds_cb(const kortex_driver::Base_JointSpeeds& joint_speeds) +{ + kortex_driver::SendJointSpeedsCommandRequest req; + req.input = joint_speeds; + SendJointSpeedsCommand(req); +} + +void KortexArmSimulation::new_twist_cb(const kortex_driver::TwistCommand& twist) +{ + // TODO Implement +} + +void KortexArmSimulation::clear_faults_cb(const std_msgs::Empty& empty) +{ + // does nothing +} + +void KortexArmSimulation::stop_cb(const std_msgs::Empty& empty) +{ + Stop(kortex_driver::StopRequest()); +} + +void KortexArmSimulation::emergency_stop_cb(const std_msgs::Empty& empty) +{ + ApplyEmergencyStop(kortex_driver::ApplyEmergencyStopRequest()); +} diff --git a/ros_kortex/kortex_driver/src/non-generated/driver/kortex_math_util.cpp b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_math_util.cpp new file mode 100644 index 0000000..e89552b --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_math_util.cpp @@ -0,0 +1,113 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/kortex_math_util.h" + +double KortexMathUtil::toRad(double degree) +{ + return degree * M_PI / 180.0; +} + +double KortexMathUtil::toDeg(double rad) +{ + return rad * 180.0 / M_PI; +} + +int KortexMathUtil::getNumberOfTurns(double rad_not_wrapped) +{ + // it is between + return 0; +} + +double KortexMathUtil::wrapRadiansFromMinusPiToPi(double rad_not_wrapped) +{ + int n; + return wrapRadiansFromMinusPiToPi(rad_not_wrapped, n); +} + +double KortexMathUtil::wrapRadiansFromMinusPiToPi(double rad_not_wrapped, int& number_of_turns) +{ + bool properly_wrapped = false; + number_of_turns = 0; + do + { + if (rad_not_wrapped > M_PI) + { + number_of_turns += 1; + rad_not_wrapped -= 2.0*M_PI; + } + else if (rad_not_wrapped < -M_PI) + { + number_of_turns -= 1; + rad_not_wrapped += 2.0*M_PI; + } + else + { + properly_wrapped = true; + } + } while(!properly_wrapped); + return rad_not_wrapped; +} + +double KortexMathUtil::wrapDegreesFromZeroTo360(double deg_not_wrapped) +{ + int n; + return wrapDegreesFromZeroTo360(deg_not_wrapped, n); +} + +double KortexMathUtil::wrapDegreesFromZeroTo360(double deg_not_wrapped, int& number_of_turns) +{ + bool properly_wrapped = false; + number_of_turns = 0; + do + { + if (deg_not_wrapped > 360.0) + { + number_of_turns += 1; + deg_not_wrapped -= 360.0; + } + else if (deg_not_wrapped < 0.0) + { + number_of_turns -= 1; + deg_not_wrapped += 360.0; + } + else + { + properly_wrapped = true; + } + } while(!properly_wrapped); + return deg_not_wrapped; +} + +double KortexMathUtil::relative_position_from_absolute(double absolute_position, double min_value, double max_value) +{ + double range = max_value - min_value; + return (absolute_position - min_value) / range; +} + +double KortexMathUtil::absolute_position_from_relative(double relative_position, double min_value, double max_value) +{ + double range = max_value - min_value; + return relative_position * range + min_value; +} + +kortex_driver::Twist KortexMathUtil::substractTwists(const kortex_driver::Twist& a, const kortex_driver::Twist& b) +{ + kortex_driver::Twist c; + c.linear_x = a.linear_x - b.linear_x; + c.linear_y = a.linear_y - b.linear_y; + c.linear_z = a.linear_z - b.linear_z; + c.angular_x = a.angular_x - b.angular_x; + c.angular_y = a.angular_y - b.angular_y; + c.angular_z = a.angular_z - b.angular_z; + return c; +} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/src/non-generated/driver/kortex_subscribers.cpp b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_subscribers.cpp new file mode 100644 index 0000000..22e1f6b --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/driver/kortex_subscribers.cpp @@ -0,0 +1,148 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2020 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/kortex_subscribers.h" + +KortexSubscribers::KortexSubscribers(ros::NodeHandle& node_handle, Kinova::Api::Base::BaseClient* base): +m_node_handle(node_handle), m_base(base) +{ + std::string robot_name; + ros::param::get("~robot_name", robot_name); + m_joint_speeds_sub = m_node_handle.subscribe("in/joint_velocity", 1, &KortexSubscribers::new_joint_speeds_cb, this); + m_twist_sub = m_node_handle.subscribe("in/cartesian_velocity", 1, &KortexSubscribers::new_twist_cb, this); + m_clear_faults_sub = m_node_handle.subscribe("in/clear_faults", 1, &KortexSubscribers::clear_faults_cb, this); + m_stop_sub = m_node_handle.subscribe("in/stop", 1, &KortexSubscribers::stop_cb, this); + m_emergency_stop_sub = m_node_handle.subscribe("in/emergency_stop", 1, &KortexSubscribers::emergency_stop_cb, this); +} + +KortexSubscribers::~KortexSubscribers() +{ +} + +void KortexSubscribers::new_joint_speeds_cb(const kortex_driver::Base_JointSpeeds& joint_speeds) +{ + Kinova::Api::Base::JointSpeeds speeds; + kortex_driver::Base_JointSpeeds joint_speeds_in_rad(joint_speeds); // Since joint_speeds is const we need this copy + + // Convert radians in degrees + for (unsigned int i = 0; i < joint_speeds.joint_speeds.size(); i++) + { + joint_speeds_in_rad.joint_speeds[i].value = KortexMathUtil::toDeg(joint_speeds.joint_speeds[i].value); + } + ToProtoData(joint_speeds_in_rad, &speeds); + + try + { + m_base->SendJointSpeedsCommand(speeds); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while sending joint speeds"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } + catch (std::runtime_error& ex_runtime) + { + ROS_DEBUG("Runtime exception detected while sending joint speeds!"); + ROS_DEBUG("%s", ex_runtime.what()); + } +} + +void KortexSubscribers::new_twist_cb(const kortex_driver::TwistCommand& twist) +{ + Kinova::Api::Base::TwistCommand twist_command; + ToProtoData(twist, &twist_command); + + // Convert radians to degrees + twist_command.mutable_twist()->set_angular_x(KortexMathUtil::toDeg(twist_command.twist().angular_x())); + twist_command.mutable_twist()->set_angular_y(KortexMathUtil::toDeg(twist_command.twist().angular_y())); + twist_command.mutable_twist()->set_angular_z(KortexMathUtil::toDeg(twist_command.twist().angular_z())); + + try + { + m_base->SendTwistCommand(twist_command); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while sending twist command"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } + catch (std::runtime_error& ex_runtime) + { + ROS_DEBUG("Runtime exception detected while sending twist command!"); + ROS_DEBUG("%s", ex_runtime.what()); + } +} + +void KortexSubscribers::clear_faults_cb(const std_msgs::Empty& dummy) +{ + try + { + m_base->ClearFaults(); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while clearing the faults"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } + catch (std::runtime_error& ex_runtime) + { + ROS_DEBUG("Runtime exception detected while clearing the faults!"); + ROS_DEBUG("%s", ex_runtime.what()); + } +} + +void KortexSubscribers::stop_cb(const std_msgs::Empty& dummy) +{ + try + { + m_base->Stop(); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while clearing the faults"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } + catch (std::runtime_error& ex_runtime) + { + ROS_DEBUG("Runtime exception detected while clearing the faults!"); + ROS_DEBUG("%s", ex_runtime.what()); + } +} + +void KortexSubscribers::emergency_stop_cb(const std_msgs::Empty& dummy) +{ + try + { + m_base->ApplyEmergencyStop(); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_WARN("Kortex exception while clearing the faults"); + ROS_WARN("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_WARN("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_WARN("Error description: %s\n", ex.what()); + } + catch (std::runtime_error& ex_runtime) + { + ROS_DEBUG("Runtime exception detected while clearing the faults!"); + ROS_DEBUG("%s", ex_runtime.what()); + } +} + diff --git a/ros_kortex/kortex_driver/src/non-generated/driver/pre_computed_joint_trajectory_action_server.cpp b/ros_kortex/kortex_driver/src/non-generated/driver/pre_computed_joint_trajectory_action_server.cpp new file mode 100644 index 0000000..1092321 --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/driver/pre_computed_joint_trajectory_action_server.cpp @@ -0,0 +1,543 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/pre_computed_joint_trajectory_action_server.h" +#include +#include + +PreComputedJointTrajectoryActionServer::PreComputedJointTrajectoryActionServer(const std::string& server_name, ros::NodeHandle& nh, Kinova::Api::Base::BaseClient* base, Kinova::Api::BaseCyclic::BaseCyclicClient* base_cyclic): + m_server_name(server_name), + m_node_handle(nh), + m_server(nh, server_name, boost::bind(&PreComputedJointTrajectoryActionServer::goal_received_callback, this, _1), boost::bind(&PreComputedJointTrajectoryActionServer::preempt_received_callback, this, _1), false), + m_base(base), + m_base_cyclic(base_cyclic), + m_server_state(ActionServerState::INITIALIZING) +{ + // Get the ROS params + if (!ros::param::get("~default_goal_time_tolerance", m_default_goal_time_tolerance)) + { + ROS_WARN("Parameter default_goal_time_tolerance was not specified; assuming 0.5 as default value."); + m_default_goal_time_tolerance = 0.5; + } + if (!ros::param::get("~default_goal_tolerance", m_default_goal_tolerance)) + { + ROS_WARN("Parameter default_goal_tolerance was not specified; assuming 0.005 as default value."); + m_default_goal_tolerance = 0.005; + } + if (!ros::param::get("~prefix", m_prefix)) + { + std::string error_string = "Prefix name was not specified in the launch file, shutting down the node..."; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + if (!ros::param::get("~joint_names", m_joint_names)) + { + std::string error_string = "Parameter joint_names was not specified"; + ROS_ERROR("%s", error_string.c_str()); + throw new std::runtime_error(error_string); + } + + // Subscribe to the arm's Action Notifications + m_sub_action_notif_handle = m_base->OnNotificationActionTopic(std::bind(&PreComputedJointTrajectoryActionServer::action_notif_callback, this, std::placeholders::_1), Kinova::Api::Common::NotificationOptions()); + + // Ready to receive goal + m_server.start(); + set_server_state(ActionServerState::IDLE); +} + +PreComputedJointTrajectoryActionServer::~PreComputedJointTrajectoryActionServer() +{ + m_base->Unsubscribe(m_sub_action_notif_handle); +} + +void PreComputedJointTrajectoryActionServer::goal_received_callback(actionlib::ActionServer::GoalHandle new_goal_handle) +{ + ROS_INFO("New goal received."); + if (!is_goal_acceptable(new_goal_handle)) + { + ROS_ERROR("Joint Trajectory Goal is rejected."); + new_goal_handle.setRejected(); + return; + } + + if (m_server_state != ActionServerState::IDLE) + { + ROS_WARN("There is already an active goal. It is being cancelled."); + // We have to call Stop after having received the ACTION_START notification from the arm + stop_all_movement(); + } + + // Make sure to clear the faults before moving the robot + m_base->ClearFaults(); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + + // Accept the goal + ROS_INFO("Joint Trajectory Goal is accepted."); + m_goal = new_goal_handle; + m_goal.setAccepted(); + + // Check if we are already there physically + if (is_goal_tolerance_respected(false, false)) + { + ROS_INFO("We already reached the goal position : nothing to do."); + m_goal.setSucceeded(); + return; + } + + // Construct the Protobuf object trajectory + trajectory_msgs::JointTrajectory ros_trajectory = m_goal.getGoal()->trajectory; + + Kinova::Api::Base::PreComputedJointTrajectory proto_trajectory; + + // For logging purposes + std::ofstream myfile; + myfile.open ("moveit_trajectory.csv"); + + // Set the continuity mode + proto_trajectory.set_mode(Kinova::Api::Base::TrajectoryContinuityMode::TRAJECTORY_CONTINUITY_MODE_POSITION); + + // Copy the trajectory points from the ROS structure to the Protobuf structure + for (auto traj_point : m_goal.getGoal()->trajectory.points) + { + Kinova::Api::Base::PreComputedJointTrajectoryElement* proto_element = proto_trajectory.add_trajectory_elements(); + myfile << traj_point.time_from_start.toSec() << ","; + for (auto position : traj_point.positions) + { + proto_element->add_joint_angles(m_math_util.toDeg(position)); + myfile << position << ","; + } + for (auto velocity : traj_point.velocities) + { + proto_element->add_joint_speeds(m_math_util.toDeg(velocity)); + myfile << velocity << ","; + } + for (auto acceleration : traj_point.accelerations) + { + proto_element->add_joint_accelerations(m_math_util.toDeg(acceleration)); + myfile << acceleration << ","; + } + myfile << "\n"; + proto_element->set_time_from_start(traj_point.time_from_start.toSec()); + } + + myfile.close(); + + // Send the trajectory to the robot + try + { + m_base->PlayPreComputedJointTrajectory(proto_trajectory); + set_server_state(ActionServerState::PRE_PROCESSING_PENDING); + } + catch (Kinova::Api::KDetailedException& ex) + { + ROS_ERROR("Kortex exception while sending the trajectory"); + ROS_ERROR("Error code: %s\n", Kinova::Api::ErrorCodes_Name(ex.getErrorInfo().getError().error_code()).c_str()); + ROS_ERROR("Error sub code: %s\n", Kinova::Api::SubErrorCodes_Name(Kinova::Api::SubErrorCodes(ex.getErrorInfo().getError().error_sub_code())).c_str()); + ROS_ERROR("Error description: %s\n", ex.what()); + m_goal.setAborted(); + } + catch (std::runtime_error& ex_runtime) + { + ROS_ERROR("Runtime exception detected while sending the trajectory"); + ROS_ERROR("%s", ex_runtime.what()); + m_goal.setAborted(); + } + catch (std::future_error& ex_future) + { + ROS_ERROR("Future exception detected while getting feedback"); + ROS_ERROR("%s", ex_future.what()); + m_goal.setAborted(); + } +} + +// Called in a separate thread when a preempt request comes in from the Action Client +void PreComputedJointTrajectoryActionServer::preempt_received_callback(actionlib::ActionServer::GoalHandle goal_handle) +{ + if (m_server_state == ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS) + { + stop_all_movement(); + } +} + +// Called in a separate thread when a notification comes in +void PreComputedJointTrajectoryActionServer::action_notif_callback(Kinova::Api::Base::ActionNotification notif) +{ + Kinova::Api::Base::ActionEvent event = notif.action_event(); + Kinova::Api::Base::ActionHandle handle = notif.handle(); + Kinova::Api::Base::ActionType type = handle.action_type(); + ROS_DEBUG("Action notification received of type %s", Kinova::Api::Base::ActionEvent_Name(event).c_str()); + std::lock_guard guard(m_action_notification_thread_lock); + + control_msgs::FollowJointTrajectoryResult result; + std::ostringstream oss; + + if (type == Kinova::Api::Base::ActionType::PLAY_PRE_COMPUTED_TRAJECTORY) + { + switch (event) + { + // The pre-processing is starting in the arm + case Kinova::Api::Base::ActionEvent::ACTION_PREPROCESS_START: + // It should be starting + if (m_server_state == ActionServerState::PRE_PROCESSING_PENDING) + { + ROS_INFO("Preprocessing has started in the arm."); + set_server_state(ActionServerState::PRE_PROCESSING_IN_PROGRESS); + } + // We should not have received that + else + { + ROS_ERROR("Notification mismatch : received ACTION_PREPROCESS_START but we are in %s", actionServerStateNames[int(m_server_state)]); + } + break; + + // The pre-processing has ended successfully in the arm + case Kinova::Api::Base::ActionEvent::ACTION_PREPROCESS_END: + // It was ongoing and now it ended + if (m_server_state == ActionServerState::PRE_PROCESSING_PENDING || + m_server_state == ActionServerState::PRE_PROCESSING_IN_PROGRESS) + { + ROS_INFO("Preprocessing has finished in the arm and goal has been accepted."); + set_server_state(ActionServerState::TRAJECTORY_EXECUTION_PENDING); + } + // FIXME KOR-3563 Sometimes the notifications arrive in the wrong order so it is possible to receive + // a ACTION_PREPROCESS_END notification after the ACTION_START + // When this bug will be fixed this else if can be removed + else if (m_server_state == ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS) + { + ROS_DEBUG("Notification order mismatch : We received the ACTION_PREPROCESS_END after the ACTION_START"); + break; + } + // We should not have received that + else + { + ROS_ERROR("Notification mismatch : received ACTION_PREPROCESS_END but we are in %s", actionServerStateNames[int(m_server_state)]); + } + break; + + // The pre-processing has failed in the arm + case Kinova::Api::Base::ActionEvent::ACTION_PREPROCESS_ABORT: + // It was ongoing and now it ended (and failed) + if ((m_server_state == ActionServerState::PRE_PROCESSING_IN_PROGRESS)) + { + ROS_ERROR("Preprocessing has finished in the arm and goal has been rejected. Fetching the error report from the arm..."); + + result.error_code = result.INVALID_GOAL; + + // Get the error report and show errors here + Kinova::Api::Base::TrajectoryErrorReport report = m_base->GetTrajectoryErrorReport(); + oss << "Error report has been fetched and error elements are listed below : " << std::endl; + int i = 1; + for (auto error_element : report.trajectory_error_elements()) + { + oss << "-----------------------------" << std::endl; + oss << "Error #" << i << std::endl; + oss << "Type : " << Kinova::Api::Base::TrajectoryErrorType_Name(error_element.error_type()) << std::endl; + oss << "Identifier : " << Kinova::Api::Base::TrajectoryErrorIdentifier_Name(error_element.error_identifier()) << std::endl; + oss << "Actuator : " << error_element.index()+1 << std::endl; + oss << "Erroneous value is " << error_element.error_value() << " but minimum permitted is " << error_element.min_value() << " and maximum permitted is " << error_element.max_value() << std::endl; + if (error_element.message() != "") + { + oss << "Additional message is : " << error_element.message() << std::endl; + } + oss << "-----------------------------" << std::endl; + + i++; + } + + ROS_ERROR("%s", oss.str().c_str()); + + result.error_string = oss.str(); + m_goal.setAborted(result); + + set_server_state(ActionServerState::IDLE); + } + // We should not have received that + else + { + ROS_ERROR("Notification mismatch : received ACTION_PREPROCESS_ABORT but we are in %s", actionServerStateNames[int(m_server_state)]); + } + break; + + // The arm is starting to move + case Kinova::Api::Base::ActionEvent::ACTION_START: + // The preprocessing was done and the goal is still active (not preempted) + if ((m_server_state == ActionServerState::TRAJECTORY_EXECUTION_PENDING || + m_server_state == ActionServerState::PRE_PROCESSING_IN_PROGRESS) && // FIXME KOR-3563 this happens if we received a ACTION_START before a ACTION_PREPROCESS_END + m_goal.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE) + { + ROS_INFO("Trajectory has started."); + set_server_state(ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS); + // Remember when the trajectory started + m_trajectory_start_time = std::chrono::system_clock::now(); + } + // The preprocessing was done but the goal put to "PREEMPTING" by the client while preprocessing + // The stop_all_movement() call will trigger a ACTION_ABORT notification + else if ((m_server_state == ActionServerState::TRAJECTORY_EXECUTION_PENDING) && + m_goal.getGoalStatus().status == actionlib_msgs::GoalStatus::PREEMPTING) + { + ROS_INFO("Trajectory has started but goal was cancelled : stopping all movement."); + stop_all_movement(); + } + // We should not have received that + else + { + ROS_ERROR("Notification mismatch : received ACTION_START but we are in %s", actionServerStateNames[int(m_server_state)]); + } + break; + + // The action was started in the arm, but it aborted + case Kinova::Api::Base::ActionEvent::ACTION_ABORT: + // The goal is still active, but we received a ABORT before starting, or during execution + if (m_goal.getGoalStatus().status == actionlib_msgs::GoalStatus::ACTIVE && + (m_server_state == ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS || + m_server_state == ActionServerState::TRAJECTORY_EXECUTION_PENDING)) + { + ROS_ERROR("Trajectory has been aborted."); + + result.error_code = result.PATH_TOLERANCE_VIOLATED; + oss << "Trajectory execution failed in the arm with sub error code " << notif.abort_details() << std::endl; + if (notif.abort_details() == Kinova::Api::SubErrorCodes::CONTROL_WRONG_STARTING_POINT) + { + oss << "The starting point for the trajectory did not match the actual commanded joint angles." << std::endl; + } + else if (notif.abort_details() == Kinova::Api::SubErrorCodes::CONTROL_MANUAL_STOP) + { + oss << "The speed while executing the trajectory was too damn high and caused the robot to stop." << std::endl; + } + result.error_string = oss.str(); + m_goal.setAborted(result); + + ROS_ERROR("%s", oss.str().c_str()); + set_server_state(ActionServerState::IDLE); + } + // The goal was cancelled and we received a ACTION_ABORT : this means the trajectory was cancelled successfully in the arm + else if (m_goal.getGoalStatus().status == actionlib_msgs::GoalStatus::PREEMPTING && + (m_server_state == ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS || + m_server_state == ActionServerState::TRAJECTORY_EXECUTION_PENDING)) + { + ROS_INFO("Trajectory has been cancelled successfully in the arm."); + m_goal.setCanceled(); + set_server_state(ActionServerState::IDLE); + } + // We should not have received that + else + { + ROS_ERROR("Notification mismatch : received ACTION_ABORT but we are in %s", actionServerStateNames[int(m_server_state)]); + } + break; + + // The trajectory just ended + case Kinova::Api::Base::ActionEvent::ACTION_END: + { + // The trajectory was ongoing + if ((m_server_state == ActionServerState::TRAJECTORY_EXECUTION_IN_PROGRESS)) + { + ROS_INFO("Trajectory has finished in the arm."); + m_trajectory_end_time = std::chrono::system_clock::now(); + bool is_tolerance_respected = is_goal_tolerance_respected(true, true); + if (is_tolerance_respected) + { + result.error_code = result.SUCCESSFUL; + ROS_INFO("Trajectory execution succeeded."); + m_goal.setSucceeded(result); + } + else + { + result.error_code = result.PATH_TOLERANCE_VIOLATED; + oss << "After validation, trajectory execution failed in the arm with sub error code " << Kinova::Api::SubErrorCodes_Name(notif.abort_details()); + result.error_string = oss.str(); + + ROS_ERROR("%s", oss.str().c_str()); + m_goal.setAborted(result); + } + set_server_state(ActionServerState::IDLE); + } + // We should not have received that + else + { + ROS_ERROR("Notification mismatch : received ACTION_END but we are in %s", actionServerStateNames[int(m_server_state)]); + } + break; + } + + case Kinova::Api::Base::ActionEvent::ACTION_PAUSE: + ROS_WARN("Action pause event was just received and this should never happen."); + break; + + default: + ROS_WARN("Unknown action event was just received and this should never happen."); + break; + } + } + // Wrong action type. Rejecting the notification. Action server state unchanged. + else + { + return; + } + + oss.flush(); +} + +bool PreComputedJointTrajectoryActionServer::is_goal_acceptable(actionlib::ActionServer::GoalHandle goal_handle) +{ + // First check if goal is valid + if (!goal_handle.isValid()) + { + ROS_ERROR("Invalid goal."); + return false; + } + + // Retrieve the goal + control_msgs::FollowJointTrajectoryGoalConstPtr goal = goal_handle.getGoal(); + + // Goal does not command the right number of actuators + if (goal->trajectory.joint_names.size() != m_joint_names.size()) + { + ROS_ERROR("Goal commands %lu actuators, but arm has %lu.", goal->trajectory.joint_names.size(), m_joint_names.size()); + return false; + } + + // Goal does not command the right actuators + if (m_joint_names != goal->trajectory.joint_names) + { + ROS_ERROR("There is a mismatch between the goal's joint names and the action server's joint names."); + ROS_INFO("Action server joint names are :"); + for (auto j : m_joint_names) + { + std::cout << j << ", "; + } + std::cout << std::endl; + ROS_INFO("Goal joint names are :"); + for (auto j : goal->trajectory.joint_names) + { + std::cout << j << ", "; + } + std::cout << std::endl; + return false; + } + + // Goal needs to have 1msec timesteps intervals between all trajectory points to not be rejected + double difference = 0.0; + bool result = true; + trajectory_msgs::JointTrajectoryPoint traj_point; + for (int i = 1; i < goal->trajectory.points.size() && result; i++) + { + difference = goal->trajectory.points.at(i).time_from_start.toSec() - goal->trajectory.points.at(i-1).time_from_start.toSec(); + if (i > 0 && i < goal->trajectory.points.size()-1) + { + result = (fabs(difference-0.001) < 10.0*FLT_EPSILON); + } + } + if(!result) + { + ROS_ERROR("Insufficient point spacing."); + } + return result; +} + +bool PreComputedJointTrajectoryActionServer::is_goal_tolerance_respected(bool enable_prints, bool check_time_tolerance) +{ + // Get feedback from arm + bool is_goal_respected = true; + Kinova::Api::BaseCyclic::Feedback feedback = m_base_cyclic->RefreshFeedback(); + auto goal = m_goal.getGoal(); + + // Check the goal_time_tolerance for trajectory execution + if (check_time_tolerance) + { + double actual_trajectory_duration = std::chrono::duration(m_trajectory_end_time - m_trajectory_start_time).count(); + double desired_trajectory_duration = goal->trajectory.points.at(goal->trajectory.points.size()-1).time_from_start.toSec(); + double time_tolerance = goal->goal_time_tolerance.toSec() == 0.0 ? m_default_goal_time_tolerance : goal->goal_time_tolerance.toSec(); + if (actual_trajectory_duration > desired_trajectory_duration + time_tolerance ) + { + if (enable_prints) + ROS_ERROR("Goal duration tolerance was exceeded. Maximum desired duration was %f seconds and actual duration was %f", desired_trajectory_duration + time_tolerance, actual_trajectory_duration); + return false; + } + else if (actual_trajectory_duration < desired_trajectory_duration - time_tolerance) + { + if (enable_prints) + ROS_ERROR("Goal duration threshold was not reached. Minimum desired duration was %f seconds and actual duration was %f", desired_trajectory_duration - time_tolerance, actual_trajectory_duration); + return false; + } + } + + // If position tolerances were specified, use them. + // If the goal->goal_tolerance vector is empty, fill it with default values + std::vector goal_tolerances; + if (goal->goal_tolerance.empty()) + { + ROS_DEBUG("Goal did not specify tolerances, using default tolerance of %f radians for every joint.", m_default_goal_tolerance); + for (int i = 0; i < m_joint_names.size(); i++) + { + goal_tolerances.push_back(m_default_goal_tolerance); + } + } + else + { + for (auto tol : goal->goal_tolerance) + { + goal_tolerances.push_back(tol.position); + } + } + + // Check the joint tolerances on the goal's end position + int current_index = 0; + for (auto act: feedback.actuators()) + { + double actual_position = act.position(); // in degrees + double desired_position = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(goal->trajectory.points.at(goal->trajectory.points.size()-1).positions[current_index])); + double tolerance = 0.0; + + if (goal_tolerances[current_index] == -1.0) + { + current_index++; + continue; // no tolerance set for this joint + } + else + { + tolerance = m_math_util.toDeg(goal_tolerances[current_index]); + } + + double error = m_math_util.wrapDegreesFromZeroTo360(std::min(fabs(actual_position - desired_position), fabs(fabs(actual_position - desired_position) - 360.0))); + if (error > tolerance) + { + is_goal_respected = false; + if (enable_prints) + ROS_ERROR("The tolerance for joint %u was not met. Desired position is %f and actual position is %f", current_index + 1, desired_position, actual_position); + } + current_index++; + } + + return is_goal_respected; +} + +void PreComputedJointTrajectoryActionServer::stop_all_movement() +{ + ROS_INFO("Calling Stop on the robot."); + try + { + m_base->Stop(); + } + catch(const Kinova::Api::KBasicException& e) + { + ROS_WARN("Stop failed : %s", e.what()); + } +} + +void PreComputedJointTrajectoryActionServer::set_server_state(ActionServerState s) +{ + std::lock_guard guard(m_server_state_lock); + ActionServerState old_state = m_server_state; + m_server_state = s; + ROS_INFO("State changed from %s to %s\n", actionServerStateNames[int(old_state)], actionServerStateNames[int(s)]); +} diff --git a/ros_kortex/kortex_driver/src/non-generated/driver/robotiq_gripper_command_action_server.cpp b/ros_kortex/kortex_driver/src/non-generated/driver/robotiq_gripper_command_action_server.cpp new file mode 100644 index 0000000..962e8ae --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/driver/robotiq_gripper_command_action_server.cpp @@ -0,0 +1,217 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/robotiq_gripper_command_action_server.h" + +RobotiqGripperCommandActionServer::RobotiqGripperCommandActionServer(const std::string& server_name, const std::string& gripper_joint_name, double gripper_joint_limit_min, double gripper_joint_limit_max, ros::NodeHandle& nh, Kinova::Api::Base::BaseClient* base, Kinova::Api::BaseCyclic::BaseCyclicClient* base_cyclic): + m_server_name(server_name), + m_gripper_joint_name(gripper_joint_name), + m_gripper_joint_limit_min(gripper_joint_limit_min), + m_gripper_joint_limit_max(gripper_joint_limit_max), + m_node_handle(nh), + m_server(nh, server_name, boost::bind(&RobotiqGripperCommandActionServer::goal_received_callback, this, _1), boost::bind(&RobotiqGripperCommandActionServer::preempt_received_callback, this, _1), false), + m_base(base), + m_base_cyclic(base_cyclic), + m_is_trajectory_running(false) +{ + // Construct cancel gripper command now so we can just send it whenever we need to + m_cancel_gripper_command.set_mode(Kinova::Api::Base::GripperMode::GRIPPER_SPEED); + auto g = m_cancel_gripper_command.mutable_gripper(); + auto f = g->add_finger(); + f->set_finger_identifier(0); + f->set_value(0); + + // Ready to receive goal + m_server.start(); +} + +RobotiqGripperCommandActionServer::~RobotiqGripperCommandActionServer() +{ + join_polling_thread(); +} + +void RobotiqGripperCommandActionServer::goal_received_callback(actionlib::ActionServer::GoalHandle new_goal_handle) +{ + ROS_INFO("New goal received."); + if (!is_goal_acceptable(new_goal_handle)) + { + ROS_ERROR("Gripper Command Goal is rejected."); + new_goal_handle.setRejected(); + return; + } + + // Deal with active goals + if (m_is_trajectory_running) + { + ROS_WARN("There is already an active goal. It is being cancelled."); + stop_all_movement(); + } + + // Accept the goal + m_goal = new_goal_handle; + m_goal.setAccepted(); + + // Construct the Protobuf gripper command + control_msgs::GripperCommand ros_gripper_command = m_goal.getGoal()->command; + Kinova::Api::Base::GripperCommand proto_gripper_command; + + proto_gripper_command.set_mode(Kinova::Api::Base::GripperMode::GRIPPER_POSITION); + auto gripper = proto_gripper_command.mutable_gripper(); + // Position for a finger must be between relative (between 0 and 1), but position is absolute in the Goal coming from ROS + double relative_position = m_math_util.relative_position_from_absolute(ros_gripper_command.position, m_gripper_joint_limit_min, m_gripper_joint_limit_max); + auto finger = gripper->add_finger(); + finger->set_finger_identifier(0); + finger->set_value(relative_position); + + // Send the gripper command to the robot + m_base->SendGripperCommand(proto_gripper_command); + m_is_trajectory_running_lock.lock(); + m_is_trajectory_running = true; + m_is_trajectory_running_lock.unlock(); + + // Start the thread to monitor the position + join_polling_thread(); + m_gripper_position_polling_thread = std::thread(&RobotiqGripperCommandActionServer::gripper_position_polling_thread, this); +} + +// Called in a separate thread when a preempt request comes in from the Action Client +void RobotiqGripperCommandActionServer::preempt_received_callback(actionlib::ActionServer::GoalHandle goal_handle) +{ + ROS_WARN("Preempt received from client"); + if (m_is_trajectory_running) + { + stop_all_movement(); + } + else + { + ROS_WARN("Trajectory is not running but we received a pre-empt request from client."); + } +} + +// Called in a separate thread when a notification comes in +void RobotiqGripperCommandActionServer::gripper_position_polling_thread() +{ + std::chrono::system_clock::time_point now = m_trajectory_start_time = std::chrono::system_clock::now(); + Kinova::Api::BaseCyclic::Feedback feedback = m_base_cyclic->RefreshFeedback(); + //TODO When position feedback will be between 0 and 1, remove the *100 ot /100 in this file + double previous_gripper_position = feedback.interconnect().gripper_feedback().motor(0).position() / 100.0; + double actual_gripper_position; + int n_stuck = 0; + + // Break the loop if the trajectory is not running or if the trajectory lasted more than the timeout limit + while(m_is_trajectory_running && (std::chrono::duration(now - m_trajectory_start_time).count() < GRIPPER_TRAJECTORY_TIME_LIMIT)) + { + // Every 50ms + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + + // Get gripper position and find if we're stuck + feedback = m_base_cyclic->RefreshFeedback(); + actual_gripper_position = feedback.interconnect().gripper_feedback().motor(0).position() / 100.0; + if (fabs(actual_gripper_position - previous_gripper_position) > MAX_CONSECUTIVE_POSITION_DIFFERENCE) + { + n_stuck = 0; + } + else + { + n_stuck++; + } + previous_gripper_position = actual_gripper_position; + + // If we're stuck, the trajectory is over + if (n_stuck >= MAX_CONSECUTIVE_IDENTICAL_POSITIONS) // 200ms in the same position + { + m_is_trajectory_running_lock.lock(); + m_is_trajectory_running = false; + m_is_trajectory_running_lock.unlock(); + } + } + + // We got out this loop, meaning the trajectory is over or the time is up + // The trajectory is not running, meaning it's finished or it was stopped + if (!m_is_trajectory_running) + { + if (is_goal_tolerance_respected()) + { + m_goal.setSucceeded(); + } + else + { + ROS_ERROR("we're finished"); + m_goal.setAborted(); + } + } + + // Timeout was reached + else + { + ROS_ERROR("BANG timeout"); + m_goal.setAborted(); + } + + return; +} + +bool RobotiqGripperCommandActionServer::is_goal_acceptable(actionlib::ActionServer::GoalHandle goal_handle) +{ + // First check if goal is valid + if (!goal_handle.isValid()) + { + return false; + } + + // Retrieve the goal + control_msgs::GripperCommandGoalConstPtr goal = goal_handle.getGoal(); + + // If the position is not in the joint limits range, reject the goal + double relative_position = m_math_util.relative_position_from_absolute(goal_handle.getGoal()->command.position, m_gripper_joint_limit_min, m_gripper_joint_limit_max); + if (relative_position > 1 || relative_position < 0) + { + return false; + } + + return true; +} + +bool RobotiqGripperCommandActionServer::is_goal_tolerance_respected() +{ + Kinova::Api::BaseCyclic::Feedback feedback = m_base_cyclic->RefreshFeedback(); + double actual_gripper_position = feedback.interconnect().gripper_feedback().motor(0).position() / 100.0; + double goal_as_relative_position = m_math_util.relative_position_from_absolute(m_goal.getGoal()->command.position, m_gripper_joint_limit_min, m_gripper_joint_limit_max); + + ROS_INFO("%f and %f", actual_gripper_position, goal_as_relative_position); + + return fabs(actual_gripper_position - goal_as_relative_position) < MAX_GRIPPER_RELATIVE_ERROR; +} + +void RobotiqGripperCommandActionServer::join_polling_thread() +{ + if (m_gripper_position_polling_thread.joinable()) + { + m_gripper_position_polling_thread.join(); + } +} + +void RobotiqGripperCommandActionServer::stop_all_movement() +{ + ROS_INFO("Sending zero-speed Gripper Command on the robot."); + try + { + m_base->SendGripperCommand(m_cancel_gripper_command); + m_is_trajectory_running_lock.lock(); + m_is_trajectory_running = false; + m_is_trajectory_running_lock.unlock(); + } + catch(const Kinova::Api::KBasicException& e) + { + ROS_ERROR("Sending a gripper speed of 0 failed : %s", e.what()); + } +} diff --git a/ros_kortex/kortex_driver/src/non-generated/main.cpp b/ros_kortex/kortex_driver/src/non-generated/main.cpp new file mode 100644 index 0000000..ed1c2f8 --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/main.cpp @@ -0,0 +1,30 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +#include "kortex_driver/non-generated/kortex_arm_driver.h" + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "kortex_arm_driver"); + + // if(ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) ) { + // ros::console::notifyLoggerLevelsChanged(); + // } + + ros::NodeHandle n; + + KortexArmDriver kortex_arm_driver(n); + + ros::spin(); + + return 1; +} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/src/non-generated/tests/kortex_arm_driver_func_tests.cc b/ros_kortex/kortex_driver/src/non-generated/tests/kortex_arm_driver_func_tests.cc new file mode 100644 index 0000000..60ec3c5 --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/tests/kortex_arm_driver_func_tests.cc @@ -0,0 +1,56 @@ +#include +#include +#include +#include + +class KortexDriverTest : public ::testing::Test { + protected: + + void SetUp() override + { + } + + void TearDown() override + { + } + + ros::NodeHandle n; + +}; + +// Wait for is_initialized to become true or until we reach the 10 seconds timeout +TEST_F(KortexDriverTest, initializeDriver) +{ + bool is_initialized = false; + const int max_attempts = 20; + for (int i = 0; i < max_attempts && is_initialized == false; i++) + { + ros::param::get("is_initialized", is_initialized); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + } + ASSERT_TRUE(is_initialized); +} + +// Check for all MoveIt services +// If they're advertised, then MoveIt started correctly +TEST_F(KortexDriverTest, initializeMoveIt) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(10000)); + + ASSERT_TRUE(ros::service::waitForService("apply_planning_scene", 30)); + ASSERT_TRUE(ros::service::waitForService("clear_octomap", 30)); + ASSERT_TRUE(ros::service::waitForService("compute_cartesian_path", 30)); + ASSERT_TRUE(ros::service::waitForService("compute_fk", 30)); + ASSERT_TRUE(ros::service::waitForService("compute_ik", 30)); + ASSERT_TRUE(ros::service::waitForService("get_planning_scene", 30)); + ASSERT_TRUE(ros::service::waitForService("plan_kinematic_path", 30)); + ASSERT_TRUE(ros::service::waitForService("query_planner_interface", 30)); + ASSERT_TRUE(ros::service::waitForService("check_state_validity", 30)); +} + +// Make sure the robot_description is parsable +TEST_F(KortexDriverTest, parseURDF) +{ + urdf::Model model; + ASSERT_TRUE(model.initParam("robot_description")); +} diff --git a/ros_kortex/kortex_driver/src/non-generated/tests/kortex_simulator_unit_tests.cc b/ros_kortex/kortex_driver/src/non-generated/tests/kortex_simulator_unit_tests.cc new file mode 100644 index 0000000..9b05c1f --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/tests/kortex_simulator_unit_tests.cc @@ -0,0 +1,508 @@ +#include +#include +#include +#include +#include +#include "kortex_driver/ActionEvent.h" +#include "kortex_driver/CartesianReferenceFrame.h" +#include "kortex_driver/GripperMode.h" + +class KortexSimulatorTest : public ::testing::Test { + protected: + + void SetUp() override + { + // Create Simulator + m_simulator.reset(new KortexArmSimulation(n)); + + // Create dummy action + dummy_action.name = "MyDummyAction"; + dummy_action.handle.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES; + dummy_action.handle.permission = 7; + kortex_driver::ConstrainedJointAngles angles; + for (int i = 0; i < m_simulator->GetDOF(); i++) + { + kortex_driver::JointAngle angle; + angle.joint_identifier = i; + angle.value = 10.0f*i; + angles.joint_angles.joint_angles.push_back(angle); + } + dummy_action.oneof_action_parameters.reach_joint_angles.push_back(angles); + + // Create action topic subscriber + m_action_topic_sub = n.subscribe("action_topic", 5, &KortexSimulatorTest::ActionTopicHandler, this); + m_received_notifications.clear(); + } + + void TearDown() override + { + } + + void CompareReachJointAnglesActions(const kortex_driver::Action& a1, const kortex_driver::Action& a2, bool same) + { + ASSERT_EQ(a1.oneof_action_parameters.reach_joint_angles.size(), a2.oneof_action_parameters.reach_joint_angles.size()); + auto angles1 = a1.oneof_action_parameters.reach_joint_angles[0]; + auto angles2 = a2.oneof_action_parameters.reach_joint_angles[0]; + ASSERT_EQ(angles1.joint_angles.joint_angles.size(), angles2.joint_angles.joint_angles.size()); + for (int i = 0; i < angles1.joint_angles.joint_angles.size() && same; i++) + { + ASSERT_EQ(same, angles1.joint_angles.joint_angles.at(i) == angles2.joint_angles.joint_angles.at(i)); + } + } + + void ActionTopicHandler(const kortex_driver::ActionNotification& notif) + { + m_received_notifications.push_back(notif); + } + + kortex_driver::Action dummy_action; + ros::NodeHandle n; + std::unique_ptr m_simulator; + ros::Subscriber m_action_topic_sub; + std::vector m_received_notifications; +}; + +// Make sure after initialisation the default actions are +// Tests ReadAllActions at the same time +TEST_F(KortexSimulatorTest, DefaultActions) +{ + auto actions = m_simulator->GetActionsMap(); + bool retract, home, zero, other = false; + for (auto a : actions) + { + if (a.second.name == "Retract") retract = true; + else if (a.second.name == "Home") home = true; + else if (a.second.name == "Zero") zero = true; + else other = true; + } + ASSERT_TRUE(retract); + ASSERT_TRUE(home); + ASSERT_TRUE(zero); + ASSERT_FALSE(other); +} + +// Tests DeleteAction so default actions are not deleted +TEST_F(KortexSimulatorTest, DeleteDefaultActions) +{ + static const std::vector DEFAULT_ACTIONS_IDENTIFIERS{1,2,3}; + // Make sure the action can be deleted properly + kortex_driver::DeleteAction::Request req; + kortex_driver::ActionHandle handle; + for (unsigned int i : DEFAULT_ACTIONS_IDENTIFIERS) + { + handle.identifier = i; + req.input = handle; + m_simulator->DeleteAction(req); + auto actions_map = m_simulator->GetActionsMap(); + ASSERT_EQ(actions_map.count(i), 1); + } +} + +// Tests UpdateAction so default actions are not updated +TEST_F(KortexSimulatorTest, UpdateDefaultActions) +{ + static const std::vector DEFAULT_ACTIONS_IDENTIFIERS{1,2,3}; + // Make sure the action cannot be updated + kortex_driver::UpdateAction::Request req; + for (unsigned int i : DEFAULT_ACTIONS_IDENTIFIERS) + { + dummy_action.handle.identifier = i; + req.input = dummy_action; + m_simulator->UpdateAction(req); + auto actions_map = m_simulator->GetActionsMap(); + ASSERT_EQ(actions_map.count(i), 1); + CompareReachJointAnglesActions(actions_map[i], dummy_action, false); + } +} + +// Tests ReadAllActions +TEST_F(KortexSimulatorTest, ReadAllActions) +{ + // Test for 3 known actions (default) of this type in the map + kortex_driver::ReadAllActions::Request req; + kortex_driver::RequestedActionType type; + type.action_type = kortex_driver::ActionType::REACH_JOINT_ANGLES; + req.input = type; + auto res = m_simulator->ReadAllActions(req); + auto action_list = res.output; + ASSERT_EQ(action_list.action_list.size(), 3); // Number of default actions + + // Test for 0 known actions of this type in the map + type.action_type = kortex_driver::ActionType::REACH_POSE; + req.input = type; + res = m_simulator->ReadAllActions(req); + action_list = res.output; + ASSERT_TRUE(action_list.action_list.empty()); +} + +// Tests CreateAction handler for a supported Action, and DeleteAction +TEST_F(KortexSimulatorTest, CreateSupportedAction) +{ + static const std::string name = "MyNewAction"; + + kortex_driver::CreateAction::Request req; + dummy_action.name = name; + req.input = dummy_action; + auto res = m_simulator->CreateAction(req); + auto handle = res.output; + auto actions_map = m_simulator->GetActionsMap(); + + // Make sure the action was added to the map + ASSERT_EQ(actions_map.count(handle.identifier), 1); + ASSERT_EQ(actions_map[handle.identifier].name, name); + ASSERT_EQ(actions_map[handle.identifier].handle.action_type, kortex_driver::ActionType::REACH_JOINT_ANGLES); + + // Make sure the action can be deleted properly + kortex_driver::DeleteAction::Request del_req; + del_req.input = handle; + m_simulator->DeleteAction(del_req); + actions_map = m_simulator->GetActionsMap(); + ASSERT_EQ(actions_map.count(handle.identifier), 0); +} + +// Tests CreateAction handler for an unsupported Action +TEST_F(KortexSimulatorTest, CreateUnsupportedAction) +{ + kortex_driver::CreateAction::Request req; + dummy_action.oneof_action_parameters.reach_joint_angles.clear(); + dummy_action.handle.action_type = kortex_driver::ActionType::SEND_JOINT_SPEEDS; + kortex_driver::Base_JointSpeeds speeds; + for (int i = 0; i < m_simulator->GetDOF(); i++) + { + kortex_driver::JointSpeed speed; + speed.joint_identifier = i; + speed.value = 10.0f*i; + speeds.joint_speeds.push_back(speed); + } + dummy_action.oneof_action_parameters.send_joint_speeds.push_back(speeds); + req.input = dummy_action; + auto res = m_simulator->CreateAction(req); + auto handle = res.output; + auto actions_map = m_simulator->GetActionsMap(); + + // Make sure the action was added to the map + ASSERT_EQ(actions_map.count(handle.identifier), 0); +} + +// Tests UpdateAction on existing and non-existing actions +TEST_F(KortexSimulatorTest, UpdateAction) +{ + // Create Action at first + kortex_driver::CreateAction::Request req; + req.input = dummy_action; + auto res = m_simulator->CreateAction(req); + auto handle = res.output; + auto actions_map = m_simulator->GetActionsMap(); + + // Make sure the action was added to the map + ASSERT_EQ(actions_map.count(handle.identifier), 1); + ASSERT_EQ(actions_map[handle.identifier].handle.action_type, kortex_driver::ActionType::REACH_JOINT_ANGLES); + + // Modify and update the Action + dummy_action.name = "MyUpdatedName"; + dummy_action.handle.identifier = handle.identifier; + dummy_action.oneof_action_parameters.reach_joint_angles[0].joint_angles.joint_angles[3].value = 0.0f; + kortex_driver::UpdateAction::Request update_req; + update_req.input = dummy_action; + m_simulator->UpdateAction(update_req); + actions_map = m_simulator->GetActionsMap(); + ASSERT_EQ(actions_map.count(handle.identifier), 1); + ASSERT_EQ(dummy_action.name, actions_map[handle.identifier].name); + CompareReachJointAnglesActions(dummy_action, actions_map[handle.identifier], true); + + // Modify and update the Action with a different type + kortex_driver::Action wrong_type_action; + wrong_type_action.name = "WrongType"; + wrong_type_action.handle.identifier = handle.identifier; + wrong_type_action.handle.action_type = kortex_driver::ActionType::SEND_JOINT_SPEEDS; + wrong_type_action.oneof_action_parameters.reach_joint_angles.clear(); + wrong_type_action.oneof_action_parameters.send_joint_speeds.push_back(kortex_driver::Base_JointSpeeds()); + update_req.input = wrong_type_action; + m_simulator->UpdateAction(update_req); + actions_map = m_simulator->GetActionsMap(); + ASSERT_EQ(actions_map.count(handle.identifier), 1); + ASSERT_EQ(dummy_action.name, actions_map[handle.identifier].name); + ASSERT_EQ(kortex_driver::ActionType::REACH_JOINT_ANGLES, actions_map[handle.identifier].handle.action_type); +} + +// This uses a TIME_DELAY action to test execution +TEST_F(KortexSimulatorTest, ExecuteAction) +{ + static constexpr uint32_t SLEEP_DURATION_SECONDS = 4; + + dummy_action.oneof_action_parameters.reach_joint_angles.clear(); + dummy_action.handle.action_type = kortex_driver::ActionType::TIME_DELAY; + kortex_driver::Delay delay; + delay.duration = SLEEP_DURATION_SECONDS; + dummy_action.oneof_action_parameters.delay.push_back(delay); + kortex_driver::ExecuteAction::Request req; + req.input = dummy_action; + + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->ExecuteAction(req); + std::this_thread::sleep_for(std::chrono::seconds(2)); + // Make sure after a couple seconds we received the ACTION_START + ASSERT_EQ(m_received_notifications.size(), 1); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + std::this_thread::sleep_for(std::chrono::seconds(3)); + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +// This uses a TIME_DELAY action to test execution from reference +TEST_F(KortexSimulatorTest, ExecuteActionFromReference) +{ + static constexpr uint32_t SLEEP_DURATION_SECONDS = 4; + + // Create the Delay action + dummy_action.oneof_action_parameters.reach_joint_angles.clear(); + dummy_action.handle.action_type = kortex_driver::ActionType::TIME_DELAY; + kortex_driver::Delay delay; + delay.duration = SLEEP_DURATION_SECONDS; + dummy_action.oneof_action_parameters.delay.push_back(delay); + kortex_driver::CreateAction::Request req; + req.input = dummy_action; + auto res = m_simulator->CreateAction(req); + dummy_action.handle = res.output; + auto actions_map = m_simulator->GetActionsMap(); + ASSERT_EQ(actions_map.count(dummy_action.handle.identifier), 1); + + // Execute the Delay action by reference + ASSERT_EQ(m_received_notifications.size(), 0); + kortex_driver::ExecuteActionFromReference::Request execute_req; + execute_req.input = dummy_action.handle; + m_simulator->ExecuteActionFromReference(execute_req); + std::this_thread::sleep_for(std::chrono::seconds(2)); + // Make sure after a couple seconds we received the ACTION_START + ASSERT_EQ(m_received_notifications.size(), 1); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + std::this_thread::sleep_for(std::chrono::seconds(3)); + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +// This uses a TIME_DELAY action to test aborting +TEST_F(KortexSimulatorTest, StopAction) +{ + static constexpr uint32_t SLEEP_DURATION_SECONDS = 4; + + // Create delay action object + dummy_action.oneof_action_parameters.reach_joint_angles.clear(); + dummy_action.handle.action_type = kortex_driver::ActionType::TIME_DELAY; + kortex_driver::Delay delay; + delay.duration = SLEEP_DURATION_SECONDS; + dummy_action.oneof_action_parameters.delay.push_back(delay); + kortex_driver::ExecuteAction::Request req; + req.input = dummy_action; + + // Prepare StopAction request + kortex_driver::StopAction::Request stop_req; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->ExecuteAction(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // Make sure after one second we received the ACTION_START + ASSERT_EQ(m_received_notifications.size(), 1); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + + // Abort the action now + m_simulator->StopAction(stop_req); + + // Wait a biut and make sure we received the ACTION_ABORT + std::this_thread::sleep_for(std::chrono::seconds(1)); + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_ABORT); +} + +TEST_F(KortexSimulatorTest, PlayCartesianTrajectory) +{ + kortex_driver::PlayCartesianTrajectory::Request req; + kortex_driver::ConstrainedPose pose; + pose.target_pose.x = 0.1; + pose.target_pose.y = 0.1; + pose.target_pose.z = 0.1; + pose.target_pose.theta_x = 0.1; + pose.target_pose.theta_y = 0.1; + pose.target_pose.theta_z = 0.1; + req.input = pose; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->PlayCartesianTrajectory(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // TODO Change when implementation is filled + // Make sure after one second we received the ACTION_START and ACTION_END + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +TEST_F(KortexSimulatorTest, SendTwistCommand) +{ + kortex_driver::SendTwistCommand::Request req; + kortex_driver::TwistCommand twist_command; + twist_command.reference_frame = kortex_driver::CartesianReferenceFrame::CARTESIAN_REFERENCE_FRAME_BASE; + twist_command.twist.linear_x = 0.1; + twist_command.twist.linear_y = 0.1; + twist_command.twist.linear_z = 0.1; + twist_command.twist.angular_x = 0.1; + twist_command.twist.angular_y = 0.1; + twist_command.twist.angular_z = 0.1; + req.input = twist_command; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->SendTwistCommand(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // TODO Change when implementation is filled + // Make sure after one second we received the ACTION_START and ACTION_END + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +TEST_F(KortexSimulatorTest, PlayJointTrajectory) +{ + kortex_driver::PlayJointTrajectory::Request req; + kortex_driver::ConstrainedJointAngles constrained_joint_angles; + for (int i = 0; i < m_simulator->GetDOF(); i++) + { + kortex_driver::JointAngle angle; + angle.joint_identifier = i; + angle.value = i*10.0f; + constrained_joint_angles.joint_angles.joint_angles.push_back(angle); + } + req.input = constrained_joint_angles; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->PlayJointTrajectory(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // TODO Change when implementation is filled + // Make sure after one second we received the ACTION_START and ACTION_END + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +TEST_F(KortexSimulatorTest, SendJointSpeedsCommand) +{ + kortex_driver::SendJointSpeedsCommand::Request req; + kortex_driver::Base_JointSpeeds joint_speeds; + for (int i = 0; i < m_simulator->GetDOF(); i++) + { + kortex_driver::JointSpeed speed; + speed.joint_identifier = i; + speed.value = i*10.0f; + joint_speeds.joint_speeds.push_back(speed); + } + req.input = joint_speeds; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->SendJointSpeedsCommand(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // TODO Change when implementation is filled + // Make sure after one second we received the ACTION_START and ACTION_END + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +TEST_F(KortexSimulatorTest, SendGripperCommand) +{ + kortex_driver::SendGripperCommand::Request req; + kortex_driver::GripperCommand gripper_command; + gripper_command.mode = kortex_driver::GripperMode::GRIPPER_POSITION; + kortex_driver::Finger finger; + finger.finger_identifier = 0; + finger.value = 10.0f; + gripper_command.gripper.finger.push_back(finger); + req.input = gripper_command; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->SendGripperCommand(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // TODO Change when implementation is filled + // Make sure after one second we received the ACTION_START and ACTION_END + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_END); +} + +// Use a TIME_DELAY action to test the Stop RPC +TEST_F(KortexSimulatorTest, Stop) +{ + static constexpr uint32_t SLEEP_DURATION_SECONDS = 4; + + // Create delay action object + dummy_action.oneof_action_parameters.reach_joint_angles.clear(); + dummy_action.handle.action_type = kortex_driver::ActionType::TIME_DELAY; + kortex_driver::Delay delay; + delay.duration = SLEEP_DURATION_SECONDS; + dummy_action.oneof_action_parameters.delay.push_back(delay); + kortex_driver::ExecuteAction::Request req; + req.input = dummy_action; + + // Prepare Stop request + kortex_driver::Stop::Request stop_req; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->ExecuteAction(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // Make sure after one second we received the ACTION_START + ASSERT_EQ(m_received_notifications.size(), 1); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + + // Abort the action now + m_simulator->Stop(stop_req); + + // Wait a biut and make sure we received the ACTION_ABORT + std::this_thread::sleep_for(std::chrono::seconds(1)); + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_ABORT); +} + +TEST_F(KortexSimulatorTest, ApplyEmergencyStop) +{ + static constexpr uint32_t SLEEP_DURATION_SECONDS = 4; + + // Create delay action object + dummy_action.oneof_action_parameters.reach_joint_angles.clear(); + dummy_action.handle.action_type = kortex_driver::ActionType::TIME_DELAY; + kortex_driver::Delay delay; + delay.duration = SLEEP_DURATION_SECONDS; + dummy_action.oneof_action_parameters.delay.push_back(delay); + kortex_driver::ExecuteAction::Request req; + req.input = dummy_action; + + // Prepare Stop request + kortex_driver::ApplyEmergencyStop::Request stop_req; + + // Execute the action + ASSERT_EQ(m_received_notifications.size(), 0); + m_simulator->ExecuteAction(req); + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // Make sure after one second we received the ACTION_START + ASSERT_EQ(m_received_notifications.size(), 1); + ASSERT_EQ(m_received_notifications[0].action_event, kortex_driver::ActionEvent::ACTION_START); + + // Abort the action now + m_simulator->ApplyEmergencyStop(stop_req); + + // Wait a biut and make sure we received the ACTION_ABORT + std::this_thread::sleep_for(std::chrono::seconds(1)); + ASSERT_EQ(m_received_notifications.size(), 2); + ASSERT_EQ(m_received_notifications[1].action_event, kortex_driver::ActionEvent::ACTION_ABORT); +} diff --git a/ros_kortex/kortex_driver/src/non-generated/tests/main.cc b/ros_kortex/kortex_driver/src/non-generated/tests/main.cc new file mode 100644 index 0000000..d330136 --- /dev/null +++ b/ros_kortex/kortex_driver/src/non-generated/tests/main.cc @@ -0,0 +1,15 @@ +#include +#include +#include + +int main(int argc, char** argv){ + ros::init(argc, argv, "TestNode"); + testing::InitGoogleTest(&argc, argv); + + std::thread t([]{while(ros::ok()) ros::spin();}); + + auto res = RUN_ALL_TESTS(); + + ros::shutdown(); + return res; +} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/ActuatorConfig_ClearFaults.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/ActuatorConfig_ClearFaults.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/ActuatorConfig_ClearFaults.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/ActuatorConfig_GetControlMode.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/ActuatorConfig_GetControlMode.srv new file mode 100644 index 0000000..e6993e1 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/ActuatorConfig_GetControlMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +ActuatorConfig_ControlModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetActivatedControlLoop.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetActivatedControlLoop.srv new file mode 100644 index 0000000..a19e213 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetActivatedControlLoop.srv @@ -0,0 +1,3 @@ +Empty input +--- +ControlLoop output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetAxisOffsets.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetAxisOffsets.srv new file mode 100644 index 0000000..4735b95 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetAxisOffsets.srv @@ -0,0 +1,3 @@ +Empty input +--- +AxisOffsets output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetCoggingFeedforwardMode.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetCoggingFeedforwardMode.srv new file mode 100644 index 0000000..9fe719d --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetCoggingFeedforwardMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +CoggingFeedforwardModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetCommandMode.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetCommandMode.srv new file mode 100644 index 0000000..bdfef0a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetCommandMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +CommandModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetControlLoopParameters.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetControlLoopParameters.srv new file mode 100644 index 0000000..d999a54 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetControlLoopParameters.srv @@ -0,0 +1,3 @@ +LoopSelection input +--- +ControlLoopParameters output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetSelectedCustomData.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetSelectedCustomData.srv new file mode 100644 index 0000000..cdc7309 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetSelectedCustomData.srv @@ -0,0 +1,3 @@ +Empty input +--- +CustomDataSelection output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetServoing.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetServoing.srv new file mode 100644 index 0000000..d4a6734 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetServoing.srv @@ -0,0 +1,3 @@ +Empty input +--- +Servoing output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/GetTorqueOffset.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetTorqueOffset.srv new file mode 100644 index 0000000..f8d55a7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/GetTorqueOffset.srv @@ -0,0 +1,3 @@ +Empty input +--- +TorqueOffset output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/MoveToPosition.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/MoveToPosition.srv new file mode 100644 index 0000000..bca986c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/MoveToPosition.srv @@ -0,0 +1,3 @@ +PositionCommand input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SelectCustomData.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SelectCustomData.srv new file mode 100644 index 0000000..0bf1dfa --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SelectCustomData.srv @@ -0,0 +1,3 @@ +CustomDataSelection input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetActivatedControlLoop.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetActivatedControlLoop.srv new file mode 100644 index 0000000..14dbadc --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetActivatedControlLoop.srv @@ -0,0 +1,3 @@ +ControlLoop input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetAxisOffsets.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetAxisOffsets.srv new file mode 100644 index 0000000..0060243 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetAxisOffsets.srv @@ -0,0 +1,3 @@ +AxisPosition input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetCoggingFeedforwardMode.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetCoggingFeedforwardMode.srv new file mode 100644 index 0000000..5766f76 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetCoggingFeedforwardMode.srv @@ -0,0 +1,3 @@ +CoggingFeedforwardModeInformation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetCommandMode.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetCommandMode.srv new file mode 100644 index 0000000..9ba28a5 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetCommandMode.srv @@ -0,0 +1,3 @@ +CommandModeInformation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetControlLoopParameters.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetControlLoopParameters.srv new file mode 100644 index 0000000..8f7419a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetControlLoopParameters.srv @@ -0,0 +1,3 @@ +ControlLoopParameters input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetControlMode.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetControlMode.srv new file mode 100644 index 0000000..679458c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetControlMode.srv @@ -0,0 +1,3 @@ +ActuatorConfig_ControlModeInformation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetServoing.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetServoing.srv new file mode 100644 index 0000000..3eb8801 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetServoing.srv @@ -0,0 +1,3 @@ +Servoing input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/actuator_config/SetTorqueOffset.srv b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetTorqueOffset.srv new file mode 100644 index 0000000..6f2857b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/actuator_config/SetTorqueOffset.srv @@ -0,0 +1,3 @@ +TorqueOffset input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ActivateMap.srv b/ros_kortex/kortex_driver/srv/generated/base/ActivateMap.srv new file mode 100644 index 0000000..e6b9a56 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ActivateMap.srv @@ -0,0 +1,3 @@ +ActivateMapHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/AddSequenceTasks.srv b/ros_kortex/kortex_driver/srv/generated/base/AddSequenceTasks.srv new file mode 100644 index 0000000..2bce3e5 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/AddSequenceTasks.srv @@ -0,0 +1,3 @@ +SequenceTasksConfiguration input +--- +SequenceTasksRange output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/AddWifiConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/AddWifiConfiguration.srv new file mode 100644 index 0000000..48a3c35 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/AddWifiConfiguration.srv @@ -0,0 +1,3 @@ +WifiConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ApplyEmergencyStop.srv b/ros_kortex/kortex_driver/srv/generated/base/ApplyEmergencyStop.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ApplyEmergencyStop.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/Base_ClearFaults.srv b/ros_kortex/kortex_driver/srv/generated/base/Base_ClearFaults.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/Base_ClearFaults.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/Base_GetCapSenseConfig.srv b/ros_kortex/kortex_driver/srv/generated/base/Base_GetCapSenseConfig.srv new file mode 100644 index 0000000..7e64acd --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/Base_GetCapSenseConfig.srv @@ -0,0 +1,3 @@ +Empty input +--- +Base_CapSenseConfig output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/Base_GetControlMode.srv b/ros_kortex/kortex_driver/srv/generated/base/Base_GetControlMode.srv new file mode 100644 index 0000000..7a9f0ad --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/Base_GetControlMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +Base_ControlModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/Base_SetCapSenseConfig.srv b/ros_kortex/kortex_driver/srv/generated/base/Base_SetCapSenseConfig.srv new file mode 100644 index 0000000..0e2e726 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/Base_SetCapSenseConfig.srv @@ -0,0 +1,3 @@ +Base_CapSenseConfig input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/Base_Unsubscribe.srv b/ros_kortex/kortex_driver/srv/generated/base/Base_Unsubscribe.srv new file mode 100644 index 0000000..403ee3b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/Base_Unsubscribe.srv @@ -0,0 +1,3 @@ +NotificationHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ChangePassword.srv b/ros_kortex/kortex_driver/srv/generated/base/ChangePassword.srv new file mode 100644 index 0000000..f9fceed --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ChangePassword.srv @@ -0,0 +1,3 @@ +PasswordChange input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ConnectWifi.srv b/ros_kortex/kortex_driver/srv/generated/base/ConnectWifi.srv new file mode 100644 index 0000000..4e1a65a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ConnectWifi.srv @@ -0,0 +1,3 @@ +Ssid input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/CreateAction.srv b/ros_kortex/kortex_driver/srv/generated/base/CreateAction.srv new file mode 100644 index 0000000..25d11da --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/CreateAction.srv @@ -0,0 +1,3 @@ +Action input +--- +ActionHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/CreateMap.srv b/ros_kortex/kortex_driver/srv/generated/base/CreateMap.srv new file mode 100644 index 0000000..93c9e1d --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/CreateMap.srv @@ -0,0 +1,3 @@ +Map input +--- +MapHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/CreateMapping.srv b/ros_kortex/kortex_driver/srv/generated/base/CreateMapping.srv new file mode 100644 index 0000000..241110b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/CreateMapping.srv @@ -0,0 +1,3 @@ +Mapping input +--- +MappingHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/CreateProtectionZone.srv b/ros_kortex/kortex_driver/srv/generated/base/CreateProtectionZone.srv new file mode 100644 index 0000000..12c649a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/CreateProtectionZone.srv @@ -0,0 +1,3 @@ +ProtectionZone input +--- +ProtectionZoneHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/CreateSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/CreateSequence.srv new file mode 100644 index 0000000..884f87c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/CreateSequence.srv @@ -0,0 +1,3 @@ +Sequence input +--- +SequenceHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/CreateUserProfile.srv b/ros_kortex/kortex_driver/srv/generated/base/CreateUserProfile.srv new file mode 100644 index 0000000..9b5dbd6 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/CreateUserProfile.srv @@ -0,0 +1,3 @@ +FullUserProfile input +--- +UserProfileHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteAction.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteAction.srv new file mode 100644 index 0000000..6668d04 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteAction.srv @@ -0,0 +1,3 @@ +ActionHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteAllSequenceTasks.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteAllSequenceTasks.srv new file mode 100644 index 0000000..00e870c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteAllSequenceTasks.srv @@ -0,0 +1,3 @@ +SequenceHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteMap.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteMap.srv new file mode 100644 index 0000000..1e16cb8 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteMap.srv @@ -0,0 +1,3 @@ +MapHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteMapping.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteMapping.srv new file mode 100644 index 0000000..ea8df28 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteMapping.srv @@ -0,0 +1,3 @@ +MappingHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteProtectionZone.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteProtectionZone.srv new file mode 100644 index 0000000..bc933b5 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteProtectionZone.srv @@ -0,0 +1,3 @@ +ProtectionZoneHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteSequence.srv new file mode 100644 index 0000000..00e870c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteSequence.srv @@ -0,0 +1,3 @@ +SequenceHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteSequenceTask.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteSequenceTask.srv new file mode 100644 index 0000000..b4170eb --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteSequenceTask.srv @@ -0,0 +1,3 @@ +SequenceTaskHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteUserProfile.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteUserProfile.srv new file mode 100644 index 0000000..e5c214e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteUserProfile.srv @@ -0,0 +1,3 @@ +UserProfileHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DeleteWifiConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/DeleteWifiConfiguration.srv new file mode 100644 index 0000000..4e1a65a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DeleteWifiConfiguration.srv @@ -0,0 +1,3 @@ +Ssid input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DisableBridge.srv b/ros_kortex/kortex_driver/srv/generated/base/DisableBridge.srv new file mode 100644 index 0000000..70f1c9f --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DisableBridge.srv @@ -0,0 +1,3 @@ +BridgeIdentifier input +--- +BridgeResult output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DisconnectWifi.srv b/ros_kortex/kortex_driver/srv/generated/base/DisconnectWifi.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DisconnectWifi.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DuplicateMap.srv b/ros_kortex/kortex_driver/srv/generated/base/DuplicateMap.srv new file mode 100644 index 0000000..399961a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DuplicateMap.srv @@ -0,0 +1,3 @@ +MapHandle input +--- +MapHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/DuplicateMapping.srv b/ros_kortex/kortex_driver/srv/generated/base/DuplicateMapping.srv new file mode 100644 index 0000000..7b51d73 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/DuplicateMapping.srv @@ -0,0 +1,3 @@ +MappingHandle input +--- +MappingHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/EnableBridge.srv b/ros_kortex/kortex_driver/srv/generated/base/EnableBridge.srv new file mode 100644 index 0000000..59fca2a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/EnableBridge.srv @@ -0,0 +1,3 @@ +BridgeConfig input +--- +BridgeResult output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ExecuteAction.srv b/ros_kortex/kortex_driver/srv/generated/base/ExecuteAction.srv new file mode 100644 index 0000000..c74f124 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ExecuteAction.srv @@ -0,0 +1,3 @@ +Action input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ExecuteActionFromReference.srv b/ros_kortex/kortex_driver/srv/generated/base/ExecuteActionFromReference.srv new file mode 100644 index 0000000..6668d04 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ExecuteActionFromReference.srv @@ -0,0 +1,3 @@ +ActionHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetActuatorCount.srv b/ros_kortex/kortex_driver/srv/generated/base/GetActuatorCount.srv new file mode 100644 index 0000000..cb92302 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetActuatorCount.srv @@ -0,0 +1,3 @@ +Empty input +--- +ActuatorInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllConfiguredWifis.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllConfiguredWifis.srv new file mode 100644 index 0000000..7a64466 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllConfiguredWifis.srv @@ -0,0 +1,3 @@ +Empty input +--- +WifiConfigurationList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllConnectedControllers.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllConnectedControllers.srv new file mode 100644 index 0000000..2397aaf --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllConnectedControllers.srv @@ -0,0 +1,3 @@ +Empty input +--- +ControllerList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllControllerConfigurations.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllControllerConfigurations.srv new file mode 100644 index 0000000..f541490 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllControllerConfigurations.srv @@ -0,0 +1,3 @@ +Empty input +--- +ControllerConfigurationList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsSpeedHardLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsSpeedHardLimitation.srv new file mode 100644 index 0000000..2725503 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsSpeedHardLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +JointsLimitationsList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsSpeedSoftLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsSpeedSoftLimitation.srv new file mode 100644 index 0000000..2725503 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsSpeedSoftLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +JointsLimitationsList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsTorqueHardLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsTorqueHardLimitation.srv new file mode 100644 index 0000000..2725503 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsTorqueHardLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +JointsLimitationsList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsTorqueSoftLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsTorqueSoftLimitation.srv new file mode 100644 index 0000000..2725503 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAllJointsTorqueSoftLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +JointsLimitationsList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetArmState.srv b/ros_kortex/kortex_driver/srv/generated/base/GetArmState.srv new file mode 100644 index 0000000..9c9bcd8 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetArmState.srv @@ -0,0 +1,3 @@ +Empty input +--- +ArmStateInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetAvailableWifi.srv b/ros_kortex/kortex_driver/srv/generated/base/GetAvailableWifi.srv new file mode 100644 index 0000000..be8692f --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetAvailableWifi.srv @@ -0,0 +1,3 @@ +Empty input +--- +WifiInformationList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetBridgeConfig.srv b/ros_kortex/kortex_driver/srv/generated/base/GetBridgeConfig.srv new file mode 100644 index 0000000..9c546ec --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetBridgeConfig.srv @@ -0,0 +1,3 @@ +BridgeIdentifier input +--- +BridgeConfig output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetBridgeList.srv b/ros_kortex/kortex_driver/srv/generated/base/GetBridgeList.srv new file mode 100644 index 0000000..2da2a77 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetBridgeList.srv @@ -0,0 +1,3 @@ +Empty input +--- +BridgeList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetConfiguredWifi.srv b/ros_kortex/kortex_driver/srv/generated/base/GetConfiguredWifi.srv new file mode 100644 index 0000000..76f8d17 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetConfiguredWifi.srv @@ -0,0 +1,3 @@ +Ssid input +--- +WifiConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetConnectedWifiInformation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetConnectedWifiInformation.srv new file mode 100644 index 0000000..deced6e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetConnectedWifiInformation.srv @@ -0,0 +1,3 @@ +Empty input +--- +WifiInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetControllerConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/GetControllerConfiguration.srv new file mode 100644 index 0000000..6f58bbf --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetControllerConfiguration.srv @@ -0,0 +1,3 @@ +ControllerHandle input +--- +ControllerConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetControllerConfigurationMode.srv b/ros_kortex/kortex_driver/srv/generated/base/GetControllerConfigurationMode.srv new file mode 100644 index 0000000..6232371 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetControllerConfigurationMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +ControllerConfigurationMode output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetControllerState.srv b/ros_kortex/kortex_driver/srv/generated/base/GetControllerState.srv new file mode 100644 index 0000000..5596f9e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetControllerState.srv @@ -0,0 +1,3 @@ +ControllerHandle input +--- +ControllerState output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetFirmwareBundleVersions.srv b/ros_kortex/kortex_driver/srv/generated/base/GetFirmwareBundleVersions.srv new file mode 100644 index 0000000..8bcabb6 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetFirmwareBundleVersions.srv @@ -0,0 +1,3 @@ +Empty input +--- +FirmwareBundleVersions output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetIPv4Configuration.srv b/ros_kortex/kortex_driver/srv/generated/base/GetIPv4Configuration.srv new file mode 100644 index 0000000..1515ce2 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetIPv4Configuration.srv @@ -0,0 +1,3 @@ +NetworkHandle input +--- +IPv4Configuration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetIPv4Information.srv b/ros_kortex/kortex_driver/srv/generated/base/GetIPv4Information.srv new file mode 100644 index 0000000..5b5a39c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetIPv4Information.srv @@ -0,0 +1,3 @@ +NetworkHandle input +--- +IPv4Information output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredCartesianPose.srv b/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredCartesianPose.srv new file mode 100644 index 0000000..a79dc7e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredCartesianPose.srv @@ -0,0 +1,3 @@ +Empty input +--- +Pose output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredGripperMovement.srv b/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredGripperMovement.srv new file mode 100644 index 0000000..1311aa7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredGripperMovement.srv @@ -0,0 +1,3 @@ +GripperRequest input +--- +Gripper output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredJointAngles.srv b/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredJointAngles.srv new file mode 100644 index 0000000..bc24fba --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetMeasuredJointAngles.srv @@ -0,0 +1,3 @@ +Empty input +--- +JointAngles output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetOperatingMode.srv b/ros_kortex/kortex_driver/srv/generated/base/GetOperatingMode.srv new file mode 100644 index 0000000..d836452 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetOperatingMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +OperatingModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetProductConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/GetProductConfiguration.srv new file mode 100644 index 0000000..9d34ae4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetProductConfiguration.srv @@ -0,0 +1,3 @@ +Empty input +--- +CompleteProductConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetServoingMode.srv b/ros_kortex/kortex_driver/srv/generated/base/GetServoingMode.srv new file mode 100644 index 0000000..345f256 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetServoingMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +ServoingModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetTrajectoryErrorReport.srv b/ros_kortex/kortex_driver/srv/generated/base/GetTrajectoryErrorReport.srv new file mode 100644 index 0000000..6fc9f2c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetTrajectoryErrorReport.srv @@ -0,0 +1,3 @@ +Empty input +--- +TrajectoryErrorReport output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetTwistHardLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetTwistHardLimitation.srv new file mode 100644 index 0000000..57c7808 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetTwistHardLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +TwistLimitation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetTwistSoftLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetTwistSoftLimitation.srv new file mode 100644 index 0000000..57c7808 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetTwistSoftLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +TwistLimitation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetWifiCountryCode.srv b/ros_kortex/kortex_driver/srv/generated/base/GetWifiCountryCode.srv new file mode 100644 index 0000000..5e7f98f --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetWifiCountryCode.srv @@ -0,0 +1,3 @@ +Empty input +--- +CountryCode output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetWifiInformation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetWifiInformation.srv new file mode 100644 index 0000000..9208c10 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetWifiInformation.srv @@ -0,0 +1,3 @@ +Ssid input +--- +WifiInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetWrenchHardLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetWrenchHardLimitation.srv new file mode 100644 index 0000000..ff151a9 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetWrenchHardLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +WrenchLimitation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/GetWrenchSoftLimitation.srv b/ros_kortex/kortex_driver/srv/generated/base/GetWrenchSoftLimitation.srv new file mode 100644 index 0000000..ff151a9 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/GetWrenchSoftLimitation.srv @@ -0,0 +1,3 @@ +Empty input +--- +WrenchLimitation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/IsCommunicationInterfaceEnable.srv b/ros_kortex/kortex_driver/srv/generated/base/IsCommunicationInterfaceEnable.srv new file mode 100644 index 0000000..a3ad49c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/IsCommunicationInterfaceEnable.srv @@ -0,0 +1,3 @@ +NetworkHandle input +--- +CommunicationInterfaceConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/MoveSequenceTask.srv b/ros_kortex/kortex_driver/srv/generated/base/MoveSequenceTask.srv new file mode 100644 index 0000000..781d09a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/MoveSequenceTask.srv @@ -0,0 +1,3 @@ +SequenceTasksPair input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationActionTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationActionTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationActionTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationArmStateTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationArmStateTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationArmStateTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationConfigurationChangeTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationConfigurationChangeTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationConfigurationChangeTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationControlModeTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationControlModeTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationControlModeTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationControllerTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationControllerTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationControllerTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationFactoryTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationFactoryTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationFactoryTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationMappingInfoTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationMappingInfoTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationMappingInfoTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationNetworkTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationNetworkTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationNetworkTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationOperatingModeTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationOperatingModeTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationOperatingModeTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationProtectionZoneTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationProtectionZoneTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationProtectionZoneTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationRobotEventTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationRobotEventTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationRobotEventTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationSequenceInfoTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationSequenceInfoTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationSequenceInfoTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationServoingModeTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationServoingModeTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationServoingModeTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/OnNotificationUserTopic.srv b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationUserTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/OnNotificationUserTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PauseAction.srv b/ros_kortex/kortex_driver/srv/generated/base/PauseAction.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PauseAction.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PauseSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/PauseSequence.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PauseSequence.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlayAdvancedSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/PlayAdvancedSequence.srv new file mode 100644 index 0000000..151aa31 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlayAdvancedSequence.srv @@ -0,0 +1,3 @@ +AdvancedSequenceHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectory.srv b/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectory.srv new file mode 100644 index 0000000..1a64dd4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectory.srv @@ -0,0 +1,3 @@ +ConstrainedPose input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectoryOrientation.srv b/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectoryOrientation.srv new file mode 100644 index 0000000..5bac981 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectoryOrientation.srv @@ -0,0 +1,3 @@ +ConstrainedOrientation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectoryPosition.srv b/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectoryPosition.srv new file mode 100644 index 0000000..68c1748 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlayCartesianTrajectoryPosition.srv @@ -0,0 +1,3 @@ +ConstrainedPosition input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlayJointTrajectory.srv b/ros_kortex/kortex_driver/srv/generated/base/PlayJointTrajectory.srv new file mode 100644 index 0000000..2d17f3c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlayJointTrajectory.srv @@ -0,0 +1,3 @@ +ConstrainedJointAngles input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlayPreComputedJointTrajectory.srv b/ros_kortex/kortex_driver/srv/generated/base/PlayPreComputedJointTrajectory.srv new file mode 100644 index 0000000..264c3b0 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlayPreComputedJointTrajectory.srv @@ -0,0 +1,3 @@ +PreComputedJointTrajectory input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlaySelectedJointTrajectory.srv b/ros_kortex/kortex_driver/srv/generated/base/PlaySelectedJointTrajectory.srv new file mode 100644 index 0000000..b6dfbaa --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlaySelectedJointTrajectory.srv @@ -0,0 +1,3 @@ +ConstrainedJointAngle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/PlaySequence.srv b/ros_kortex/kortex_driver/srv/generated/base/PlaySequence.srv new file mode 100644 index 0000000..00e870c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/PlaySequence.srv @@ -0,0 +1,3 @@ +SequenceHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAction.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAction.srv new file mode 100644 index 0000000..f9d93fb --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAction.srv @@ -0,0 +1,3 @@ +ActionHandle input +--- +Action output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllActions.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllActions.srv new file mode 100644 index 0000000..3f1d6d4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllActions.srv @@ -0,0 +1,3 @@ +RequestedActionType input +--- +ActionList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllMappings.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllMappings.srv new file mode 100644 index 0000000..06aba6a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllMappings.srv @@ -0,0 +1,3 @@ +Empty input +--- +MappingList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllMaps.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllMaps.srv new file mode 100644 index 0000000..30e520c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllMaps.srv @@ -0,0 +1,3 @@ +MappingHandle input +--- +MapList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllProtectionZones.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllProtectionZones.srv new file mode 100644 index 0000000..31307fb --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllProtectionZones.srv @@ -0,0 +1,3 @@ +Empty input +--- +ProtectionZoneList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllSequenceTasks.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllSequenceTasks.srv new file mode 100644 index 0000000..7f83e4c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllSequenceTasks.srv @@ -0,0 +1,3 @@ +SequenceHandle input +--- +SequenceTasks output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllSequences.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllSequences.srv new file mode 100644 index 0000000..146a255 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllSequences.srv @@ -0,0 +1,3 @@ +Empty input +--- +SequenceList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllUserProfiles.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllUserProfiles.srv new file mode 100644 index 0000000..46d8141 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllUserProfiles.srv @@ -0,0 +1,3 @@ +Empty input +--- +UserProfileList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadAllUsers.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadAllUsers.srv new file mode 100644 index 0000000..7ffb2d0 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadAllUsers.srv @@ -0,0 +1,3 @@ +Empty input +--- +UserList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadMap.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadMap.srv new file mode 100644 index 0000000..b250efb --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadMap.srv @@ -0,0 +1,3 @@ +MapHandle input +--- +Map output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadMapping.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadMapping.srv new file mode 100644 index 0000000..27349a2 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadMapping.srv @@ -0,0 +1,3 @@ +MappingHandle input +--- +Mapping output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadProtectionZone.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadProtectionZone.srv new file mode 100644 index 0000000..bc7600b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadProtectionZone.srv @@ -0,0 +1,3 @@ +ProtectionZoneHandle input +--- +ProtectionZone output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadSequence.srv new file mode 100644 index 0000000..f7fb91c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadSequence.srv @@ -0,0 +1,3 @@ +SequenceHandle input +--- +Sequence output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadSequenceTask.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadSequenceTask.srv new file mode 100644 index 0000000..727d451 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadSequenceTask.srv @@ -0,0 +1,3 @@ +SequenceTaskHandle input +--- +SequenceTask output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ReadUserProfile.srv b/ros_kortex/kortex_driver/srv/generated/base/ReadUserProfile.srv new file mode 100644 index 0000000..58fedf8 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ReadUserProfile.srv @@ -0,0 +1,3 @@ +UserProfileHandle input +--- +UserProfile output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/RestoreFactoryProductConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/RestoreFactoryProductConfiguration.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/RestoreFactoryProductConfiguration.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/RestoreFactorySettings.srv b/ros_kortex/kortex_driver/srv/generated/base/RestoreFactorySettings.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/RestoreFactorySettings.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ResumeAction.srv b/ros_kortex/kortex_driver/srv/generated/base/ResumeAction.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ResumeAction.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/ResumeSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/ResumeSequence.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/ResumeSequence.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendGripperCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendGripperCommand.srv new file mode 100644 index 0000000..f83e0fc --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendGripperCommand.srv @@ -0,0 +1,3 @@ +GripperCommand input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendJointSpeedsCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendJointSpeedsCommand.srv new file mode 100644 index 0000000..055bd54 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendJointSpeedsCommand.srv @@ -0,0 +1,3 @@ +Base_JointSpeeds input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendJointSpeedsJoystickCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendJointSpeedsJoystickCommand.srv new file mode 100644 index 0000000..055bd54 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendJointSpeedsJoystickCommand.srv @@ -0,0 +1,3 @@ +Base_JointSpeeds input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendSelectedJointSpeedCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendSelectedJointSpeedCommand.srv new file mode 100644 index 0000000..2cc3285 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendSelectedJointSpeedCommand.srv @@ -0,0 +1,3 @@ +JointSpeed input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendSelectedJointSpeedJoystickCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendSelectedJointSpeedJoystickCommand.srv new file mode 100644 index 0000000..2cc3285 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendSelectedJointSpeedJoystickCommand.srv @@ -0,0 +1,3 @@ +JointSpeed input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendTwistCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendTwistCommand.srv new file mode 100644 index 0000000..afa8aa1 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendTwistCommand.srv @@ -0,0 +1,3 @@ +TwistCommand input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendTwistJoystickCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendTwistJoystickCommand.srv new file mode 100644 index 0000000..afa8aa1 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendTwistJoystickCommand.srv @@ -0,0 +1,3 @@ +TwistCommand input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendWrenchCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendWrenchCommand.srv new file mode 100644 index 0000000..3d23b95 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendWrenchCommand.srv @@ -0,0 +1,3 @@ +WrenchCommand input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SendWrenchJoystickCommand.srv b/ros_kortex/kortex_driver/srv/generated/base/SendWrenchJoystickCommand.srv new file mode 100644 index 0000000..3d23b95 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SendWrenchJoystickCommand.srv @@ -0,0 +1,3 @@ +WrenchCommand input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetAdmittance.srv b/ros_kortex/kortex_driver/srv/generated/base/SetAdmittance.srv new file mode 100644 index 0000000..9e132b8 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetAdmittance.srv @@ -0,0 +1,3 @@ +Admittance input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetCommunicationInterfaceEnable.srv b/ros_kortex/kortex_driver/srv/generated/base/SetCommunicationInterfaceEnable.srv new file mode 100644 index 0000000..91007ce --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetCommunicationInterfaceEnable.srv @@ -0,0 +1,3 @@ +CommunicationInterfaceConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetControllerConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/SetControllerConfiguration.srv new file mode 100644 index 0000000..e785bdc --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetControllerConfiguration.srv @@ -0,0 +1,3 @@ +ControllerConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetControllerConfigurationMode.srv b/ros_kortex/kortex_driver/srv/generated/base/SetControllerConfigurationMode.srv new file mode 100644 index 0000000..9c3825a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetControllerConfigurationMode.srv @@ -0,0 +1,3 @@ +ControllerConfigurationMode input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetIPv4Configuration.srv b/ros_kortex/kortex_driver/srv/generated/base/SetIPv4Configuration.srv new file mode 100644 index 0000000..58ed27e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetIPv4Configuration.srv @@ -0,0 +1,3 @@ +FullIPv4Configuration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetOperatingMode.srv b/ros_kortex/kortex_driver/srv/generated/base/SetOperatingMode.srv new file mode 100644 index 0000000..a91aa07 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetOperatingMode.srv @@ -0,0 +1,3 @@ +OperatingModeInformation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetServoingMode.srv b/ros_kortex/kortex_driver/srv/generated/base/SetServoingMode.srv new file mode 100644 index 0000000..b8dc46d --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetServoingMode.srv @@ -0,0 +1,3 @@ +ServoingModeInformation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SetWifiCountryCode.srv b/ros_kortex/kortex_driver/srv/generated/base/SetWifiCountryCode.srv new file mode 100644 index 0000000..77d30c0 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SetWifiCountryCode.srv @@ -0,0 +1,3 @@ +CountryCode input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/StartTeaching.srv b/ros_kortex/kortex_driver/srv/generated/base/StartTeaching.srv new file mode 100644 index 0000000..b4170eb --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/StartTeaching.srv @@ -0,0 +1,3 @@ +SequenceTaskHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/StartWifiScan.srv b/ros_kortex/kortex_driver/srv/generated/base/StartWifiScan.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/StartWifiScan.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/Stop.srv b/ros_kortex/kortex_driver/srv/generated/base/Stop.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/Stop.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/StopAction.srv b/ros_kortex/kortex_driver/srv/generated/base/StopAction.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/StopAction.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/StopSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/StopSequence.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/StopSequence.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/StopTeaching.srv b/ros_kortex/kortex_driver/srv/generated/base/StopTeaching.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/StopTeaching.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/SwapSequenceTasks.srv b/ros_kortex/kortex_driver/srv/generated/base/SwapSequenceTasks.srv new file mode 100644 index 0000000..781d09a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/SwapSequenceTasks.srv @@ -0,0 +1,3 @@ +SequenceTasksPair input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/TakeSnapshot.srv b/ros_kortex/kortex_driver/srv/generated/base/TakeSnapshot.srv new file mode 100644 index 0000000..acc5a54 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/TakeSnapshot.srv @@ -0,0 +1,3 @@ +Snapshot input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateAction.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateAction.srv new file mode 100644 index 0000000..c74f124 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateAction.srv @@ -0,0 +1,3 @@ +Action input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateEndEffectorTypeConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateEndEffectorTypeConfiguration.srv new file mode 100644 index 0000000..52bb1c5 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateEndEffectorTypeConfiguration.srv @@ -0,0 +1,3 @@ +ProductConfigurationEndEffectorType input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateMap.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateMap.srv new file mode 100644 index 0000000..e58c7af --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateMap.srv @@ -0,0 +1,3 @@ +Map input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateMapping.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateMapping.srv new file mode 100644 index 0000000..98a8392 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateMapping.srv @@ -0,0 +1,3 @@ +Mapping input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateProtectionZone.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateProtectionZone.srv new file mode 100644 index 0000000..1b07d48 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateProtectionZone.srv @@ -0,0 +1,3 @@ +ProtectionZone input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateSequence.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateSequence.srv new file mode 100644 index 0000000..5805a3a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateSequence.srv @@ -0,0 +1,3 @@ +Sequence input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateSequenceTask.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateSequenceTask.srv new file mode 100644 index 0000000..ad95ec4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateSequenceTask.srv @@ -0,0 +1,3 @@ +SequenceTaskConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/base/UpdateUserProfile.srv b/ros_kortex/kortex_driver/srv/generated/base/UpdateUserProfile.srv new file mode 100644 index 0000000..bbd7d54 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/base/UpdateUserProfile.srv @@ -0,0 +1,3 @@ +UserProfile input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ControlConfig_GetControlMode.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ControlConfig_GetControlMode.srv new file mode 100644 index 0000000..345b6cf --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ControlConfig_GetControlMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +ControlConfig_ControlModeInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ControlConfig_Unsubscribe.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ControlConfig_Unsubscribe.srv new file mode 100644 index 0000000..403ee3b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ControlConfig_Unsubscribe.srv @@ -0,0 +1,3 @@ +NotificationHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetAllKinematicSoftLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetAllKinematicSoftLimits.srv new file mode 100644 index 0000000..7382c9e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetAllKinematicSoftLimits.srv @@ -0,0 +1,3 @@ +Empty input +--- +KinematicLimitsList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetCartesianReferenceFrame.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetCartesianReferenceFrame.srv new file mode 100644 index 0000000..918b627 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetCartesianReferenceFrame.srv @@ -0,0 +1,3 @@ +Empty input +--- +CartesianReferenceFrameInfo output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetDesiredSpeeds.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetDesiredSpeeds.srv new file mode 100644 index 0000000..922ffd4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetDesiredSpeeds.srv @@ -0,0 +1,3 @@ +Empty input +--- +DesiredSpeeds output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetGravityVector.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetGravityVector.srv new file mode 100644 index 0000000..2d7fb24 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetGravityVector.srv @@ -0,0 +1,3 @@ +Empty input +--- +GravityVector output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetKinematicHardLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetKinematicHardLimits.srv new file mode 100644 index 0000000..22633d7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetKinematicHardLimits.srv @@ -0,0 +1,3 @@ +Empty input +--- +KinematicLimits output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetKinematicSoftLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetKinematicSoftLimits.srv new file mode 100644 index 0000000..2a253c2 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetKinematicSoftLimits.srv @@ -0,0 +1,3 @@ +ControlConfig_ControlModeInformation input +--- +KinematicLimits output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetPayloadInformation.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetPayloadInformation.srv new file mode 100644 index 0000000..8ace35b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetPayloadInformation.srv @@ -0,0 +1,3 @@ +Empty input +--- +PayloadInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/GetToolConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/control_config/GetToolConfiguration.srv new file mode 100644 index 0000000..f7aad83 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/GetToolConfiguration.srv @@ -0,0 +1,3 @@ +Empty input +--- +ToolConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/OnNotificationControlConfigurationTopic.srv b/ros_kortex/kortex_driver/srv/generated/control_config/OnNotificationControlConfigurationTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/OnNotificationControlConfigurationTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetGravityVector.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetGravityVector.srv new file mode 100644 index 0000000..2d7fb24 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetGravityVector.srv @@ -0,0 +1,3 @@ +Empty input +--- +GravityVector output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetJointAccelerationSoftLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetJointAccelerationSoftLimits.srv new file mode 100644 index 0000000..72c58a0 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetJointAccelerationSoftLimits.srv @@ -0,0 +1,3 @@ +ControlConfig_ControlModeInformation input +--- +JointAccelerationSoftLimits output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetJointSpeedSoftLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetJointSpeedSoftLimits.srv new file mode 100644 index 0000000..1010cd8 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetJointSpeedSoftLimits.srv @@ -0,0 +1,3 @@ +ControlConfig_ControlModeInformation input +--- +JointSpeedSoftLimits output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetPayloadInformation.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetPayloadInformation.srv new file mode 100644 index 0000000..8ace35b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetPayloadInformation.srv @@ -0,0 +1,3 @@ +Empty input +--- +PayloadInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetToolConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetToolConfiguration.srv new file mode 100644 index 0000000..f7aad83 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetToolConfiguration.srv @@ -0,0 +1,3 @@ +Empty input +--- +ToolConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetTwistAngularSoftLimit.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetTwistAngularSoftLimit.srv new file mode 100644 index 0000000..78dcf95 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetTwistAngularSoftLimit.srv @@ -0,0 +1,3 @@ +ControlConfig_ControlModeInformation input +--- +TwistAngularSoftLimit output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/ResetTwistLinearSoftLimit.srv b/ros_kortex/kortex_driver/srv/generated/control_config/ResetTwistLinearSoftLimit.srv new file mode 100644 index 0000000..5ccca5e --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/ResetTwistLinearSoftLimit.srv @@ -0,0 +1,3 @@ +ControlConfig_ControlModeInformation input +--- +TwistLinearSoftLimit output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetCartesianReferenceFrame.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetCartesianReferenceFrame.srv new file mode 100644 index 0000000..9e68bf7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetCartesianReferenceFrame.srv @@ -0,0 +1,3 @@ +CartesianReferenceFrameInfo input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredAngularTwist.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredAngularTwist.srv new file mode 100644 index 0000000..e7ad9cc --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredAngularTwist.srv @@ -0,0 +1,3 @@ +AngularTwist input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredJointSpeeds.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredJointSpeeds.srv new file mode 100644 index 0000000..3df0702 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredJointSpeeds.srv @@ -0,0 +1,3 @@ +ControlConfig_JointSpeeds input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredLinearTwist.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredLinearTwist.srv new file mode 100644 index 0000000..fa9bff4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetDesiredLinearTwist.srv @@ -0,0 +1,3 @@ +LinearTwist input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetGravityVector.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetGravityVector.srv new file mode 100644 index 0000000..a8918bf --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetGravityVector.srv @@ -0,0 +1,3 @@ +GravityVector input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetJointAccelerationSoftLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetJointAccelerationSoftLimits.srv new file mode 100644 index 0000000..8c0bc27 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetJointAccelerationSoftLimits.srv @@ -0,0 +1,3 @@ +JointAccelerationSoftLimits input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetJointSpeedSoftLimits.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetJointSpeedSoftLimits.srv new file mode 100644 index 0000000..253a261 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetJointSpeedSoftLimits.srv @@ -0,0 +1,3 @@ +JointSpeedSoftLimits input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetPayloadInformation.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetPayloadInformation.srv new file mode 100644 index 0000000..961ff3a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetPayloadInformation.srv @@ -0,0 +1,3 @@ +PayloadInformation input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetToolConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetToolConfiguration.srv new file mode 100644 index 0000000..c076f1f --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetToolConfiguration.srv @@ -0,0 +1,3 @@ +ToolConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetTwistAngularSoftLimit.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetTwistAngularSoftLimit.srv new file mode 100644 index 0000000..643d91a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetTwistAngularSoftLimit.srv @@ -0,0 +1,3 @@ +TwistAngularSoftLimit input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/control_config/SetTwistLinearSoftLimit.srv b/ros_kortex/kortex_driver/srv/generated/control_config/SetTwistLinearSoftLimit.srv new file mode 100644 index 0000000..a07d696 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/control_config/SetTwistLinearSoftLimit.srv @@ -0,0 +1,3 @@ +TwistLinearSoftLimit input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/ClearAllSafetyStatus.srv b/ros_kortex/kortex_driver/srv/generated/device_config/ClearAllSafetyStatus.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/ClearAllSafetyStatus.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/ClearSafetyStatus.srv b/ros_kortex/kortex_driver/srv/generated/device_config/ClearSafetyStatus.srv new file mode 100644 index 0000000..a44abf7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/ClearSafetyStatus.srv @@ -0,0 +1,3 @@ +SafetyHandle input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/DeviceConfig_GetCapSenseConfig.srv b/ros_kortex/kortex_driver/srv/generated/device_config/DeviceConfig_GetCapSenseConfig.srv new file mode 100644 index 0000000..9502cbd --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/DeviceConfig_GetCapSenseConfig.srv @@ -0,0 +1,3 @@ +Empty input +--- +DeviceConfig_CapSenseConfig output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/DeviceConfig_SetCapSenseConfig.srv b/ros_kortex/kortex_driver/srv/generated/device_config/DeviceConfig_SetCapSenseConfig.srv new file mode 100644 index 0000000..94302cf --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/DeviceConfig_SetCapSenseConfig.srv @@ -0,0 +1,3 @@ +DeviceConfig_CapSenseConfig input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/ExecuteCalibration.srv b/ros_kortex/kortex_driver/srv/generated/device_config/ExecuteCalibration.srv new file mode 100644 index 0000000..bf707a7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/ExecuteCalibration.srv @@ -0,0 +1,3 @@ +Calibration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetAllSafetyConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetAllSafetyConfiguration.srv new file mode 100644 index 0000000..f60360f --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetAllSafetyConfiguration.srv @@ -0,0 +1,3 @@ +Empty input +--- +SafetyConfigurationList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetAllSafetyInformation.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetAllSafetyInformation.srv new file mode 100644 index 0000000..ccb6480 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetAllSafetyInformation.srv @@ -0,0 +1,3 @@ +Empty input +--- +SafetyInformationList output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetBootloaderVersion.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetBootloaderVersion.srv new file mode 100644 index 0000000..f9df34b --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetBootloaderVersion.srv @@ -0,0 +1,3 @@ +Empty input +--- +BootloaderVersion output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetCalibrationResult.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetCalibrationResult.srv new file mode 100644 index 0000000..b88c306 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetCalibrationResult.srv @@ -0,0 +1,3 @@ +CalibrationElement input +--- +CalibrationResult output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetDeviceType.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetDeviceType.srv new file mode 100644 index 0000000..841cafb --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetDeviceType.srv @@ -0,0 +1,3 @@ +Empty input +--- +DeviceType output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetFirmwareVersion.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetFirmwareVersion.srv new file mode 100644 index 0000000..f92f54c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetFirmwareVersion.srv @@ -0,0 +1,3 @@ +Empty input +--- +FirmwareVersion output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetIPv4Settings.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetIPv4Settings.srv new file mode 100644 index 0000000..dbe3ca4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetIPv4Settings.srv @@ -0,0 +1,3 @@ +Empty input +--- +IPv4Settings output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetMACAddress.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetMACAddress.srv new file mode 100644 index 0000000..8b79b41 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetMACAddress.srv @@ -0,0 +1,3 @@ +Empty input +--- +MACAddress output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetModelNumber.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetModelNumber.srv new file mode 100644 index 0000000..7d685d9 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetModelNumber.srv @@ -0,0 +1,3 @@ +Empty input +--- +ModelNumber output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetPartNumber.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetPartNumber.srv new file mode 100644 index 0000000..b4d0677 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetPartNumber.srv @@ -0,0 +1,3 @@ +Empty input +--- +PartNumber output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetPartNumberRevision.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetPartNumberRevision.srv new file mode 100644 index 0000000..dde505d --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetPartNumberRevision.srv @@ -0,0 +1,3 @@ +Empty input +--- +PartNumberRevision output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetRunMode.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetRunMode.srv new file mode 100644 index 0000000..0b17a75 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetRunMode.srv @@ -0,0 +1,3 @@ +Empty input +--- +RunMode output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyConfiguration.srv new file mode 100644 index 0000000..21b52ca --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyConfiguration.srv @@ -0,0 +1,3 @@ +SafetyHandle input +--- +SafetyConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyEnable.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyEnable.srv new file mode 100644 index 0000000..b095731 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyEnable.srv @@ -0,0 +1,3 @@ +SafetyHandle input +--- +SafetyEnable output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyInformation.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyInformation.srv new file mode 100644 index 0000000..2869681 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyInformation.srv @@ -0,0 +1,3 @@ +SafetyHandle input +--- +SafetyInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyStatus.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyStatus.srv new file mode 100644 index 0000000..c188202 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetSafetyStatus.srv @@ -0,0 +1,3 @@ +SafetyHandle input +--- +SafetyStatus output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/GetSerialNumber.srv b/ros_kortex/kortex_driver/srv/generated/device_config/GetSerialNumber.srv new file mode 100644 index 0000000..e1bc96c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/GetSerialNumber.srv @@ -0,0 +1,3 @@ +Empty input +--- +SerialNumber output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/OnNotificationSafetyTopic.srv b/ros_kortex/kortex_driver/srv/generated/device_config/OnNotificationSafetyTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/OnNotificationSafetyTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/RebootRequest.srv b/ros_kortex/kortex_driver/srv/generated/device_config/RebootRequest.srv new file mode 100644 index 0000000..25cc189 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/RebootRequest.srv @@ -0,0 +1,3 @@ +RebootRqst input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/ResetSafetyDefaults.srv b/ros_kortex/kortex_driver/srv/generated/device_config/ResetSafetyDefaults.srv new file mode 100644 index 0000000..4d7a11a --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/ResetSafetyDefaults.srv @@ -0,0 +1,3 @@ +Empty input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/SetIPv4Settings.srv b/ros_kortex/kortex_driver/srv/generated/device_config/SetIPv4Settings.srv new file mode 100644 index 0000000..a745cb1 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/SetIPv4Settings.srv @@ -0,0 +1,3 @@ +IPv4Settings input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/SetRunMode.srv b/ros_kortex/kortex_driver/srv/generated/device_config/SetRunMode.srv new file mode 100644 index 0000000..fc420a7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/SetRunMode.srv @@ -0,0 +1,3 @@ +RunMode input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyConfiguration.srv new file mode 100644 index 0000000..db370ae --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyConfiguration.srv @@ -0,0 +1,3 @@ +SafetyConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyEnable.srv b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyEnable.srv new file mode 100644 index 0000000..198bd12 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyEnable.srv @@ -0,0 +1,3 @@ +SafetyEnable input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyErrorThreshold.srv b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyErrorThreshold.srv new file mode 100644 index 0000000..04c3ade --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyErrorThreshold.srv @@ -0,0 +1,3 @@ +SafetyThreshold input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyWarningThreshold.srv b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyWarningThreshold.srv new file mode 100644 index 0000000..04c3ade --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/SetSafetyWarningThreshold.srv @@ -0,0 +1,3 @@ +SafetyThreshold input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_config/StopCalibration.srv b/ros_kortex/kortex_driver/srv/generated/device_config/StopCalibration.srv new file mode 100644 index 0000000..8fccb47 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_config/StopCalibration.srv @@ -0,0 +1,3 @@ +Calibration input +--- +CalibrationResult output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/device_manager/ReadAllDevices.srv b/ros_kortex/kortex_driver/srv/generated/device_manager/ReadAllDevices.srv new file mode 100644 index 0000000..8f01b62 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/device_manager/ReadAllDevices.srv @@ -0,0 +1,3 @@ +Empty input +--- +DeviceHandles output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetEthernetConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetEthernetConfiguration.srv new file mode 100644 index 0000000..222659c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetEthernetConfiguration.srv @@ -0,0 +1,3 @@ +EthernetDeviceIdentification input +--- +EthernetConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetGPIOConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetGPIOConfiguration.srv new file mode 100644 index 0000000..4674efd --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetGPIOConfiguration.srv @@ -0,0 +1,3 @@ +GPIOIdentification input +--- +GPIOConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetGPIOState.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetGPIOState.srv new file mode 100644 index 0000000..586a5f4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetGPIOState.srv @@ -0,0 +1,3 @@ +GPIOIdentification input +--- +GPIOState output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetI2CConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetI2CConfiguration.srv new file mode 100644 index 0000000..bc9ca67 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetI2CConfiguration.srv @@ -0,0 +1,3 @@ +I2CDeviceIdentification input +--- +I2CConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetUARTConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetUARTConfiguration.srv new file mode 100644 index 0000000..506bdf1 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/GetUARTConfiguration.srv @@ -0,0 +1,3 @@ +UARTDeviceIdentification input +--- +UARTConfiguration output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CRead.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CRead.srv new file mode 100644 index 0000000..c2fc6c4 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CRead.srv @@ -0,0 +1,3 @@ +I2CReadParameter input +--- +I2CData output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CReadRegister.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CReadRegister.srv new file mode 100644 index 0000000..5368c96 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CReadRegister.srv @@ -0,0 +1,3 @@ +I2CReadRegisterParameter input +--- +I2CData output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CWrite.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CWrite.srv new file mode 100644 index 0000000..bd9d0f2 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CWrite.srv @@ -0,0 +1,3 @@ +I2CWriteParameter input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CWriteRegister.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CWriteRegister.srv new file mode 100644 index 0000000..faab28f --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/I2CWriteRegister.srv @@ -0,0 +1,3 @@ +I2CWriteRegisterParameter input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetEthernetConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetEthernetConfiguration.srv new file mode 100644 index 0000000..f7e62e5 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetEthernetConfiguration.srv @@ -0,0 +1,3 @@ +EthernetConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetGPIOConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetGPIOConfiguration.srv new file mode 100644 index 0000000..0cefe47 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetGPIOConfiguration.srv @@ -0,0 +1,3 @@ +GPIOConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetGPIOState.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetGPIOState.srv new file mode 100644 index 0000000..b77f87d --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetGPIOState.srv @@ -0,0 +1,3 @@ +GPIOState input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetI2CConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetI2CConfiguration.srv new file mode 100644 index 0000000..c8e8419 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetI2CConfiguration.srv @@ -0,0 +1,3 @@ +I2CConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetUARTConfiguration.srv b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetUARTConfiguration.srv new file mode 100644 index 0000000..66e7f87 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/interconnect_config/SetUARTConfiguration.srv @@ -0,0 +1,3 @@ +UARTConfiguration input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/DoSensorFocusAction.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/DoSensorFocusAction.srv new file mode 100644 index 0000000..96d7baa --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/DoSensorFocusAction.srv @@ -0,0 +1,3 @@ +SensorFocusAction input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/GetExtrinsicParameters.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/GetExtrinsicParameters.srv new file mode 100644 index 0000000..c7705f1 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/GetExtrinsicParameters.srv @@ -0,0 +1,3 @@ +Empty input +--- +ExtrinsicParameters output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/GetIntrinsicParameters.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/GetIntrinsicParameters.srv new file mode 100644 index 0000000..706f2ab --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/GetIntrinsicParameters.srv @@ -0,0 +1,3 @@ +SensorIdentifier input +--- +IntrinsicParameters output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/GetIntrinsicParametersProfile.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/GetIntrinsicParametersProfile.srv new file mode 100644 index 0000000..66ec9a9 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/GetIntrinsicParametersProfile.srv @@ -0,0 +1,3 @@ +IntrinsicProfileIdentifier input +--- +IntrinsicParameters output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/GetOptionInformation.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/GetOptionInformation.srv new file mode 100644 index 0000000..995b3a8 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/GetOptionInformation.srv @@ -0,0 +1,3 @@ +OptionIdentifier input +--- +OptionInformation output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/GetOptionValue.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/GetOptionValue.srv new file mode 100644 index 0000000..be41673 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/GetOptionValue.srv @@ -0,0 +1,3 @@ +OptionIdentifier input +--- +OptionValue output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/GetSensorSettings.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/GetSensorSettings.srv new file mode 100644 index 0000000..c663698 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/GetSensorSettings.srv @@ -0,0 +1,3 @@ +SensorIdentifier input +--- +SensorSettings output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/OnNotificationVisionTopic.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/OnNotificationVisionTopic.srv new file mode 100644 index 0000000..43c15c7 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/OnNotificationVisionTopic.srv @@ -0,0 +1,3 @@ +NotificationOptions input +--- +NotificationHandle output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/SetExtrinsicParameters.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/SetExtrinsicParameters.srv new file mode 100644 index 0000000..6a05356 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/SetExtrinsicParameters.srv @@ -0,0 +1,3 @@ +ExtrinsicParameters input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/SetIntrinsicParameters.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/SetIntrinsicParameters.srv new file mode 100644 index 0000000..24db7c3 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/SetIntrinsicParameters.srv @@ -0,0 +1,3 @@ +IntrinsicParameters input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/SetOptionValue.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/SetOptionValue.srv new file mode 100644 index 0000000..3214d55 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/SetOptionValue.srv @@ -0,0 +1,3 @@ +OptionValue input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/generated/vision_config/SetSensorSettings.srv b/ros_kortex/kortex_driver/srv/generated/vision_config/SetSensorSettings.srv new file mode 100644 index 0000000..e5e5868 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/generated/vision_config/SetSensorSettings.srv @@ -0,0 +1,3 @@ +SensorSettings input +--- +Empty output \ No newline at end of file diff --git a/ros_kortex/kortex_driver/srv/non_generated/SetApiOptions.srv b/ros_kortex/kortex_driver/srv/non_generated/SetApiOptions.srv new file mode 100644 index 0000000..cab7c81 --- /dev/null +++ b/ros_kortex/kortex_driver/srv/non_generated/SetApiOptions.srv @@ -0,0 +1,3 @@ +ApiOptions input +--- + diff --git a/ros_kortex/kortex_driver/srv/non_generated/SetDeviceID.srv b/ros_kortex/kortex_driver/srv/non_generated/SetDeviceID.srv new file mode 100644 index 0000000..396957c --- /dev/null +++ b/ros_kortex/kortex_driver/srv/non_generated/SetDeviceID.srv @@ -0,0 +1,2 @@ +uint32 device_id +--- diff --git a/ros_kortex/kortex_driver/templates/proto_converter.cpp.jinja2 b/ros_kortex/kortex_driver/templates/proto_converter.cpp.jinja2 new file mode 100644 index 0000000..8ce16a7 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/proto_converter.cpp.jinja2 @@ -0,0 +1,75 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "{{current_header_filename}}" + +{% for detailed_message in package.messages -%} +int ToProtoData(kortex_driver::{{detailed_message.prepend_message_name}}{{detailed_message.name}} input, {{detailed_message.cpp_namespace}}::{{detailed_message.name}} *output) +{ + {% for field in detailed_message.message.field -%} + {%- if not field.HasField("oneof_index") -%} + {%- if field.label == 3 -%} {# REPEATED #} + {%- if field.type == 11 %} {# MESSAGE #} + output->clear_{{field.name|lower}}(); + for(int i = 0; i < input.{{field.name}}.size(); i++) + { + ToProtoData(input.{{field.name}}[i], output->add_{{field.name|lower}}()); + } + {%- elif field.type == 14 %} {# ENUM #} + output->clear_{{field.name|lower}}(); + for(int i = 0; i < input.{{field.name}}.size(); i++) + { + output->add_{{field.name}}(({{field.type_name|replace(".", "", 1)|replace(".", "::")}})input.{{field.name}}[i]); + } + {%- else %} + output->clear_{{field.name|lower}}(); + for(int i = 0; i < input.{{field.name}}.size(); i++) + { + output->add_{{field.name|lower}}(input.{{field.name}}[i]); + } + {%- endif -%} + {%- else -%} {# NOT REPEATED #} + {%- if field.type == 11 %} {# MESSAGE #} + ToProtoData(input.{{field.name}}, output->mutable_{{field.name}}()); + {%- elif field.type == 14 %}{# ENUM #} + output->set_{{field.name}}(({{field.type_name|replace(".", "", 1)|replace(".", "::")}})input.{{field.name}}); + {%- elif field.type == 12 %} + output->set_{{field.name}}(std::string(input.{{field.name}}.begin(), input.{{field.name}}.end())); + {%- else %} + output->set_{{field.name}}(input.{{field.name}}); + {%- endif -%} + {%- endif -%} + {%- endif -%} + {%- endfor -%} + + {% for detailed_one_of in detailed_message.one_of_list -%} + {%- for field in detailed_one_of.fields %} + if(input.oneof_{{detailed_one_of.name}}.{{field.name}}.size() > 0) + { + {%- if field.type == 11 %} + ToProtoData(input.oneof_{{detailed_one_of.name}}.{{field.name}}[0], output->mutable_{{field.name}}()); + {%- elif field.type == 14 %} + output->set_{{field.name}}(({{field.type_name|replace(".", "", 1)|replace(".", "::")}})input.oneof_{{detailed_one_of.name}}.{{field.name}}[0]); + {%- else %} + output->set_{{field.name|lower}}(input.oneof_{{detailed_one_of.name}}.{{field.name}}[0]); + {%- endif %} + } + {%- endfor -%} + {%- endfor %} + + return 0; +} +{% endfor %} diff --git a/ros_kortex/kortex_driver/templates/proto_converter.h.jinja2 b/ros_kortex/kortex_driver/templates/proto_converter.h.jinja2 new file mode 100644 index 0000000..ae6ae75 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/proto_converter.h.jinja2 @@ -0,0 +1,43 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_{{package.short_name.upper()}}_PROTO_CONVERTER_H_ +#define _KORTEX_{{package.short_name.upper()}}_PROTO_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include <{{package.short_name}}.pb.h> + +{% for file in include_file_names -%} +{%- if file != current_filename-%} +#include "{{file}}" +{% endif -%} +{%- endfor %} + +{% for detailed_message in package.messages -%} +#include "kortex_driver/{{detailed_message.prepend_message_name}}{{detailed_message.name}}.h" +{% endfor %} + +{% for detailed_message in package.messages -%} +int ToProtoData(kortex_driver::{{detailed_message.prepend_message_name}}{{detailed_message.name}} input, {{detailed_message.cpp_namespace}}::{{detailed_message.name}} *output); +{% endfor %} +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/templates/ros_converter.cpp.jinja2 b/ros_kortex/kortex_driver/templates/ros_converter.cpp.jinja2 new file mode 100644 index 0000000..538771d --- /dev/null +++ b/ros_kortex/kortex_driver/templates/ros_converter.cpp.jinja2 @@ -0,0 +1,79 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#include "{{current_header_filename}}" + +{% for detailed_message in package.messages -%} +int ToRosData({{detailed_message.cpp_namespace}}::{{detailed_message.name}} input, kortex_driver::{{detailed_message.prepend_message_name}}{{detailed_message.name}} &output) +{ + {% for field in detailed_message.message.field -%} + {%- if not field.HasField("oneof_index") -%} + {%- if field.label == 3 -%} {# REPEATED #} + {%- if field.type == 11 %} + output.{{field.name}}.clear(); + for(int i = 0; i < input.{{field.name|lower}}_size(); i++) + { + kortex_driver::{{field.type_name.split(".")[-1]}} temp; + ToRosData(input.{{field.name|lower}}(i), temp); + output.{{field.name}}.push_back(temp); + } + {%- else %} + output.{{field.name}}.clear(); + for(int i = 0; i < input.{{field.name|lower}}_size(); i++) + { + output.{{field.name}}.push_back(input.{{field.name|lower}}(i)); + } + {%- endif %} + {%- else %} + {%- if field.type == 11 %} + ToRosData(input.{{field.name}}(), output.{{field.name}}); + {%- elif field.type == 14 %} + output.{{field.name}} = input.{{field.name}}(); + {%- elif field.type == 12 %} + output.{{field.name}} = std::vector(input.{{field.name}}().begin(), input.{{field.name}}().end()); + {%- else %} + output.{{field.name}} = input.{{field.name}}(); + {%- endif %} + {%- endif %} + {%- endif %} + {%- endfor %} + + {% for detailed_one_of in detailed_message.one_of_list %} + auto oneof_type_{{detailed_one_of.name}} = input.{{detailed_one_of.name}}_case(); + switch(oneof_type_{{detailed_one_of.name}}) + { + {%- for field in detailed_one_of.fields %} + {%- if "_" in field.name -%} {%- set EnumName = field.name.replace("_", " ").title().replace(" ", "") -%} {# In case the field is in the form of "gripper_command" #} + {%- else -%} {%- set EnumName = field.name[0]|upper + field.name[1:] -%} {%- endif %} {# In case the field is in the form of "gripperCommand" #} + + case {{detailed_message.cpp_namespace}}::{{detailed_message.message.name}}::k{{EnumName}}: + { + {%- if field.type == 11 %} + decltype(output.oneof_{{detailed_one_of.name}}.{{field.name}})::value_type temp; + ToRosData(input.{{field.name}}(), temp); + output.oneof_{{detailed_one_of.name}}.{{field.name}}.push_back(temp); + {%- elif field.type == 14 %} + output.oneof_{{detailed_one_of.name}}.{{field.name}}.push_back(input.{{field.name}}()); + {% endif %} + break; + } + {%- endfor -%} + } + {%- endfor %} + + return 0; +} +{% endfor %} diff --git a/ros_kortex/kortex_driver/templates/ros_converter.h.jinja2 b/ros_kortex/kortex_driver/templates/ros_converter.h.jinja2 new file mode 100644 index 0000000..f2ddd2a --- /dev/null +++ b/ros_kortex/kortex_driver/templates/ros_converter.h.jinja2 @@ -0,0 +1,43 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_{{package.short_name.upper()}}_ROS_CONVERTER_H_ +#define _KORTEX_{{package.short_name.upper()}}_ROS_CONVERTER_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +#include <{{package.short_name}}.pb.h> + +{% for file in include_file_names -%} +{%- if file != current_filename-%} +#include "{{file}}" +{% endif -%} +{%- endfor %} + +{% for detailed_message in package.messages -%} +#include "kortex_driver/{{detailed_message.prepend_message_name}}{{detailed_message.name}}.h" +{% endfor %} + +{% for detailed_message in package.messages -%} +int ToRosData({{detailed_message.cpp_namespace}}::{{detailed_message.name}} input, kortex_driver::{{detailed_message.prepend_message_name}}{{detailed_message.name}} &output); +{% endfor %} +#endif \ No newline at end of file diff --git a/ros_kortex/kortex_driver/templates/ros_enum.msg.jinja2 b/ros_kortex/kortex_driver/templates/ros_enum.msg.jinja2 new file mode 100644 index 0000000..d358808 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/ros_enum.msg.jinja2 @@ -0,0 +1,3 @@ +{% for member in item.message.value %} +uint32 {{member.name}} = {{member.number}} +{% endfor %} diff --git a/ros_kortex/kortex_driver/templates/ros_message.msg.jinja2 b/ros_kortex/kortex_driver/templates/ros_message.msg.jinja2 new file mode 100644 index 0000000..45270bc --- /dev/null +++ b/ros_kortex/kortex_driver/templates/ros_message.msg.jinja2 @@ -0,0 +1,47 @@ +{%- for member in item.message.field -%} +{%- if not member.HasField("oneof_index") -%} +{%- if member.type == field_descriptor_class.TYPE_STRING %} +string{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_BYTES %} +uint8[] {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_DOUBLE %} +float64{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_FIXED32 %} +uint32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_FIXED64 %} +uint64{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_FLOAT %} +float32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_INT32 %} +int32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_INT64 %} +int64{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_SFIXED32 %} +int32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_SFIXED64 %} +int64{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_SINT32 %} +int32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_SINT64 %} +int64{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_UINT32 %} +uint32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_UINT64 %} +uint64{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_ENUM %} +uint32{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_BOOL %} +bool {{member.name}} +{%- elif member.type == field_descriptor_class.TYPE_MESSAGE %} +{% set split_message_type = member.type_name.split('.') -%} +{%- if split_message_type[-1] in item.duplicated_fields -%} +{{split_message_type[-2]}}_{{split_message_type[-1]}}{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- else -%} +{{split_message_type[-1]}}{%- if member.label == field_descriptor_class.LABEL_REPEATED -%}[]{% endif %} {{member.name}} +{%- endif %} +{%- endif -%} +{%- endif -%} +{%- endfor -%} +{% for one_of in item.one_of_list %} +{{item.prepend_message_name}}{{item.name}}_{{one_of.name}} oneof_{{one_of.name}} +{%- endfor -%} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/templates/ros_oneof.msg.jinja2 b/ros_kortex/kortex_driver/templates/ros_oneof.msg.jinja2 new file mode 100644 index 0000000..7569820 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/ros_oneof.msg.jinja2 @@ -0,0 +1,12 @@ +{% for field in detailed_one_of.fields %} +{% if field.type == field_descriptor_class.TYPE_MESSAGE %} +{%- set split_message_type = field.type_name.split('.') -%} +{%- if split_message_type[-1] in detailed_one_of.duplicated_fields -%} +{{split_message_type[-2]}}_{{split_message_type[-1]}}[] {{field.name}} +{%- else -%} +{{split_message_type[-1]}}[] {{field.name}} +{%- endif -%} +{%- else -%} +uint32[] {{field.name}} +{%- endif -%} +{% endfor %} \ No newline at end of file diff --git a/ros_kortex/kortex_driver/templates/ros_service.srv.jinja2 b/ros_kortex/kortex_driver/templates/ros_service.srv.jinja2 new file mode 100644 index 0000000..e6c85e0 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/ros_service.srv.jinja2 @@ -0,0 +1,3 @@ +{{item.ros_service_input_name}} input +--- +{{item.ros_service_output_name}} output diff --git a/ros_kortex/kortex_driver/templates/services_interface.h.jinja2 b/ros_kortex/kortex_driver/templates/services_interface.h.jinja2 new file mode 100644 index 0000000..9350d79 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/services_interface.h.jinja2 @@ -0,0 +1,74 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_{{package.short_name|upper}}_SERVICES_INTERFACE_H_ +#define _KORTEX_{{package.short_name|upper}}_SERVICES_INTERFACE_H_ + +#include "ros/ros.h" + +#include +#include +#include +#include +#include + +{%- for method in package.methods %} +#include "kortex_driver/{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}.h" +{%- if method.is_notification_rpc %} +#include "kortex_driver/{{method_prepend_rpc_package_name}}{{method.name|replace("Topic", "")}}Notification.h" +{%- endif %} +{%- endfor %} + +#include "kortex_driver/KortexError.h" +#include "kortex_driver/SetDeviceID.h" +#include "kortex_driver/SetApiOptions.h" +#include "kortex_driver/ApiOptions.h" + +using namespace std; + +class I{{package.short_name}}Services +{ + public: + I{{package.short_name}}Services(ros::NodeHandle& node_handle) : m_node_handle(node_handle) {} + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) = 0; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) = 0; +{%- for method in package.methods %} + virtual bool {{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}(kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Request &req, kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Response &res) = 0; +{%- if method.is_notification_rpc %} + virtual void cb_{{method.name}}({{method.notification_message_cpp_namespace}}::{{method.prepend_rpc_package_name}}{{method.name|replace("Topic", "")}}Notification notif) = 0; +{%- endif %} +{%- endfor %} + +protected: + ros::NodeHandle m_node_handle; + ros::Publisher m_pub_Error; + +{%- for method in package.methods %} +{%- if method.is_notification_rpc %} + ros::Publisher m_pub_{{method.name}}; + bool m_is_activated_{{method.name}}; +{%- endif %} +{%- endfor %} + + ros::ServiceServer m_serviceSetDeviceID; + ros::ServiceServer m_serviceSetApiOptions; +{% for method in package.methods %} + ros::ServiceServer m_service{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}; +{%- endfor %} +}; +#endif + diff --git a/ros_kortex/kortex_driver/templates/services_robot.cpp.jinja2 b/ros_kortex/kortex_driver/templates/services_robot.cpp.jinja2 new file mode 100644 index 0000000..d559de0 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/services_robot.cpp.jinja2 @@ -0,0 +1,133 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +{% for include_file_name in include_file_names -%} +#include "{{include_file_name}}" +{% endfor -%} +#include "{{current_header_filename}}" + +{{package.short_name}}RobotServices::{{package.short_name}}RobotServices(ros::NodeHandle& node_handle, {{package.cpp_namespace}}::{{package.short_name}}Client* {{package.short_name|lower}}, uint32_t device_id, uint32_t timeout_ms): + I{{package.short_name}}Services(node_handle), + m_{{package.short_name|lower}}({{package.short_name|lower}}), + m_current_device_id(device_id) +{ + m_api_options.timeout_ms = timeout_ms; + + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); +{%- for method in package.methods -%} +{%- if method.is_notification_rpc %} + m_pub_{{method.name}} = m_node_handle.advertise("{{method.name_lowercase_with_underscores}}", 1000); + m_is_activated_{{method.name}} = false; +{%- endif -%} +{%- endfor %} + + m_serviceSetDeviceID = m_node_handle.advertiseService("{{package.short_name_lowercase_with_underscores}}/set_device_id", &{{package.short_name}}RobotServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("{{package.short_name_lowercase_with_underscores}}/set_api_options", &{{package.short_name}}RobotServices::SetApiOptions, this); +{% for method in package.methods %} + m_service{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}} = m_node_handle.advertiseService("{{package.short_name_lowercase_with_underscores}}/{%- if method.prepend_on_notification -%}activate_publishing_of_{%- endif -%}{{method.name_lowercase_with_underscores}}", &{{package.short_name}}RobotServices::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}, this); +{%- endfor %} +} + +bool {{package.short_name}}RobotServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + m_current_device_id = req.device_id; + + return true; +} + +bool {{package.short_name}}RobotServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + m_api_options.timeout_ms = req.input.timeout_ms; + + return true; +} + +{% for method in package.methods %} +bool {{package.short_name}}RobotServices::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}(kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Request &req, kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Response &res) +{ + {% if method.is_rpc_deprecated -%} + ROS_WARN("The {{package.short_name_lowercase_with_underscores}}/{%- if method.prepend_on_notification -%}activate_publishing_of_{%- endif -%}{{method.name_lowercase_with_underscores}} service is now deprecated and will be removed in a future release."); + {% endif -%} + + {% if method.is_notification_rpc %} + // If the notification is already activated, don't activate multiple times + if (m_is_activated_{{method.name}}) + return true; + {%- endif %} + + {%- if not method.input_type_short_name == "Empty" %} + {{method.input_type_cpp_namespace}}::{{method.input_type_short_name}} input; + ToProtoData(req.input, &input); + {%- endif %} + {%- if not method.output_type_short_name == "Empty" %} + {{method.output_type_cpp_namespace}}::{{method.output_type_short_name}} output; + {% endif %} + kortex_driver::KortexError result_error; + + try + { + {%- if not method.output_type_short_name == "Empty" %} + {%- if not method.input_type_short_name == "Empty" %} + {%- if method.is_notification_rpc %} + std::function< void ({{method.notification_message_cpp_namespace}}::{{method.name|replace("Topic", "")}}Notification) > callback = std::bind(&{{package.short_name}}RobotServices::cb_{{method.name}}, this, std::placeholders::_1); + output = m_{{package.short_name|lower}}->{{method.prepend_on_notification}}{{method.name}}(callback, input, m_current_device_id); + m_is_activated_{{method.name}} = true; + {%- else %} + output = m_{{package.short_name|lower}}->{{method.name}}(input, m_current_device_id, m_api_options); + {%- endif %} + {%- else %} + output = m_{{package.short_name|lower}}->{{method.name}}(m_current_device_id, m_api_options); + {%- endif %} + {%- else %} + {%- if not method.input_type_short_name == "Empty" %} + m_{{package.short_name|lower}}->{{method.name}}(input, m_current_device_id, m_api_options); + {%- else %} + m_{{package.short_name|lower}}->{{method.name}}(m_current_device_id, m_api_options); + {%- endif %} + {%- endif %} + } + + catch (Kinova::Api::KDetailedException& ex) + { + result_error.subCode = ex.getErrorInfo().getError().error_sub_code(); + result_error.code = ex.getErrorInfo().getError().error_code(); + result_error.description = ex.toString(); + m_pub_Error.publish(result_error); + ROS_INFO("Kortex exception"); + ROS_INFO("KINOVA exception error code: %d\n", ex.getErrorInfo().getError().error_code()); + ROS_INFO("KINOVA exception error sub code: %d\n", ex.getErrorInfo().getError().error_sub_code()); + ROS_INFO("KINOVA exception description: %s\n", ex.what()); + return false; + } + catch (std::runtime_error& ex2) + { + ROS_INFO("%s", ex2.what()); + return false; + } + {%- if not method.output_type_short_name == "Empty" %} + ToRosData(output, res.output); + {%- endif %} + return true; +} +{%- if method.is_notification_rpc %} +void {{package.short_name}}RobotServices::cb_{{method.name}}({{method.notification_message_cpp_namespace}}::{{method.name|replace("Topic", "")}}Notification notif) +{ + kortex_driver::{{method.name|replace("Topic", "")}}Notification ros_msg; + ToRosData(notif, ros_msg); + m_pub_{{method.name}}.publish(ros_msg); +} +{%- endif %} +{% endfor -%} diff --git a/ros_kortex/kortex_driver/templates/services_robot.h.jinja2 b/ros_kortex/kortex_driver/templates/services_robot.h.jinja2 new file mode 100644 index 0000000..7a19498 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/services_robot.h.jinja2 @@ -0,0 +1,48 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_{{package.short_name|upper}}_ROBOT_SERVICES_H_ +#define _KORTEX_{{package.short_name|upper}}_ROBOT_SERVICES_H_ + +#include "{{current_interface_header_filename}}" + +#include <{{package.short_name}}.pb.h> +#include <{{package.short_name}}ClientRpc.h> + +using namespace std; + +class {{package.short_name}}RobotServices : public I{{package.short_name}}Services +{ + public: + {{package.short_name}}RobotServices(ros::NodeHandle& node_handle, {{package.cpp_namespace}}::{{package.short_name}}Client* {{package.short_name|lower}}, uint32_t device_id, uint32_t timeout_ms); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; +{%- for method in package.methods %} + virtual bool {{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}(kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Request &req, kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Response &res) override; +{%- if method.is_notification_rpc %} + virtual void cb_{{method.name}}({{method.notification_message_cpp_namespace}}::{{method.prepend_rpc_package_name}}{{method.name|replace("Topic", "")}}Notification notif) override; +{%- endif %} +{%- endfor %} + +private: + uint32_t m_current_device_id; + Kinova::Api::RouterClientSendOptions m_api_options; + + {{package.cpp_namespace}}::{{package.short_name}}Client* m_{{package.short_name|lower}}; +}; +#endif + diff --git a/ros_kortex/kortex_driver/templates/services_simulation.cpp.jinja2 b/ros_kortex/kortex_driver/templates/services_simulation.cpp.jinja2 new file mode 100644 index 0000000..6c47876 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/services_simulation.cpp.jinja2 @@ -0,0 +1,81 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +{% for include_file_name in include_file_names -%} +#include "{{include_file_name}}" +{% endfor -%} +#include "{{current_header_filename}}" + +{{package.short_name}}SimulationServices::{{package.short_name}}SimulationServices(ros::NodeHandle& node_handle): + I{{package.short_name}}Services(node_handle) +{ + m_pub_Error = m_node_handle.advertise("kortex_error", 1000); +{%- for method in package.methods -%} +{%- if method.is_notification_rpc %} + m_pub_{{method.name}} = m_node_handle.advertise("{{method.name_lowercase_with_underscores}}", 1000); + m_is_activated_{{method.name}} = false; +{%- endif -%} +{%- endfor %} + + m_serviceSetDeviceID = m_node_handle.advertiseService("{{package.short_name_lowercase_with_underscores}}/set_device_id", &{{package.short_name}}SimulationServices::SetDeviceID, this); + m_serviceSetApiOptions = m_node_handle.advertiseService("{{package.short_name_lowercase_with_underscores}}/set_api_options", &{{package.short_name}}SimulationServices::SetApiOptions, this); +{% for method in package.methods %} + m_service{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}} = m_node_handle.advertiseService("{{package.short_name_lowercase_with_underscores}}/{%- if method.prepend_on_notification -%}activate_publishing_of_{%- endif -%}{{method.name_lowercase_with_underscores}}", &{{package.short_name}}SimulationServices::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}, this); +{%- endfor %} +} + +bool {{package.short_name}}SimulationServices::SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +bool {{package.short_name}}SimulationServices::SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) +{ + ROS_WARN_ONCE("The SetDeviceID service is not implemented in simulation, and has no effect."); + return true; +} + +{% for method in package.methods %} +bool {{package.short_name}}SimulationServices::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}(kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Request &req, kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Response &res) +{ + {% if method.is_rpc_deprecated -%} + ROS_WARN("The {{package.short_name_lowercase_with_underscores}}/{%- if method.prepend_on_notification -%}activate_publishing_of_{%- endif -%}{{method.name_lowercase_with_underscores}} service is now deprecated and will be removed in a future release."); + {% endif -%} + + {%- if method.is_notification_rpc %} + m_is_activated_{{method.name}} = true; + {%- endif %} + + if ({{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}Handler) + { + res = {{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}Handler(req); + } + else + { + ROS_WARN_ONCE("The simulation handler for {{package.short_name_lowercase_with_underscores}}/{%- if method.prepend_on_notification -%}activate_publishing_of_{%- endif -%}{{method.name_lowercase_with_underscores}} is not implemented, so the service calls will return the default response."); + } + return true; +} +{%- if method.is_notification_rpc %} +void {{package.short_name}}SimulationServices::cb_{{method.name}}({{method.notification_message_cpp_namespace}}::{{method.name|replace("Topic", "")}}Notification notif) +{ + kortex_driver::{{method.name|replace("Topic", "")}}Notification ros_msg; + ToRosData(notif, ros_msg); + m_pub_{{method.name}}.publish(ros_msg); +} +{%- endif %} +{% endfor -%} diff --git a/ros_kortex/kortex_driver/templates/services_simulation.h.jinja2 b/ros_kortex/kortex_driver/templates/services_simulation.h.jinja2 new file mode 100644 index 0000000..c2ccd97 --- /dev/null +++ b/ros_kortex/kortex_driver/templates/services_simulation.h.jinja2 @@ -0,0 +1,41 @@ +/* +* KINOVA (R) KORTEX (TM) +* +* Copyright (c) 2019 Kinova inc. All rights reserved. +* +* This software may be modified and distributed under the +* terms of the BSD 3-Clause license. +* +* Refer to the LICENSE file for details. +* +*/ + +/* + * This file has been auto-generated and should not be modified. + */ + +#ifndef _KORTEX_{{package.short_name|upper}}_SIMULATION_SERVICES_H_ +#define _KORTEX_{{package.short_name|upper}}_SIMULATION_SERVICES_H_ + +#include "{{current_interface_header_filename}}" + +using namespace std; + +class {{package.short_name}}SimulationServices : public I{{package.short_name}}Services +{ + public: + {{package.short_name}}SimulationServices(ros::NodeHandle& node_handle); + + virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override; + virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override; +{%- for method in package.methods %} + std::function {{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}Handler = nullptr; + virtual bool {{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}(kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Request &req, kortex_driver::{{method.prepend_rpc_package_name}}{{method.prepend_on_notification}}{{method.name}}::Response &res) override; +{%- if method.is_notification_rpc %} + virtual void cb_{{method.name}}({{method.notification_message_cpp_namespace}}::{{method.prepend_rpc_package_name}}{{method.name|replace("Topic", "")}}Notification notif) override; +{%- endif %} +{%- endfor %} + +}; +#endif + diff --git a/ros_kortex/kortex_examples/CMakeLists.txt b/ros_kortex/kortex_examples/CMakeLists.txt new file mode 100644 index 0000000..378adbb --- /dev/null +++ b/ros_kortex/kortex_examples/CMakeLists.txt @@ -0,0 +1,64 @@ + +cmake_minimum_required(VERSION 2.8.3) +project(kortex_examples) + +add_compile_options(-std=c++11) +add_definitions(-D_OS_UNIX) + +## Find catkin and any catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation kortex_driver) + +## Declare a catkin package +catkin_package() +catkin_python_setup() + +include_directories(include ${catkin_INCLUDE_DIRS}) +include_directories(include ${PROJECT_SOURCE_DIR}/src) +include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/client) +include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/client_stubs) +include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/messages) +include_directories(include ${PROJECT_SOURCE_DIR}/../kortex_api/include/common) + +add_executable(example_actuator_configuration_cpp src/actuator_config/example_actuator_configuration.cpp) +add_dependencies(example_actuator_configuration_cpp ${catkin_EXPORTED_TARGETS}) +target_link_libraries(example_actuator_configuration_cpp ${catkin_LIBRARIES} ) + +add_executable(example_vision_configuration_cpp src/vision_config/example_vision_configuration.cpp) +add_dependencies(example_vision_configuration_cpp ${catkin_EXPORTED_TARGETS}) +target_link_libraries(example_vision_configuration_cpp ${catkin_LIBRARIES} ) + +add_executable(example_full_arm_movement_cpp src/full_arm/example_full_arm_movement.cpp) +add_dependencies(example_full_arm_movement_cpp ${catkin_EXPORTED_TARGETS}) +target_link_libraries(example_full_arm_movement_cpp ${catkin_LIBRARIES} ) + +add_executable(example_cartesian_poses_with_notifications_cpp src/full_arm/example_cartesian_poses_with_notifications.cpp) +add_dependencies(example_cartesian_poses_with_notifications_cpp ${catkin_EXPORTED_TARGETS}) +target_link_libraries(example_cartesian_poses_with_notifications_cpp ${catkin_LIBRARIES} ) + +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + catkin_add_gtest(kortex_examples_tests src/tests/kortex_examples_tests.cc) + target_link_libraries(kortex_examples_tests ${catkin_LIBRARIES}) +endif() + +# Install + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +catkin_install_python(PROGRAMS src/actuator_config/example_actuator_configuration.py + src/full_arm/example_cartesian_poses_with_notifications.py + src/full_arm/example_full_arm_movement.py + src/move_it/example_move_it_trajectories.py + src/vision_config/example_vision_configuration.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +## Mark executables and/or libraries for installation +install(TARGETS + example_actuator_configuration_cpp + example_vision_configuration_cpp + example_full_arm_movement_cpp + example_cartesian_poses_with_notifications_cpp + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/ros_kortex/kortex_examples/img/moveit.png b/ros_kortex/kortex_examples/img/moveit.png new file mode 100644 index 0000000..f7572df Binary files /dev/null and b/ros_kortex/kortex_examples/img/moveit.png differ diff --git a/ros_kortex/kortex_examples/img/services_real_arm.png b/ros_kortex/kortex_examples/img/services_real_arm.png new file mode 100644 index 0000000..7bf79ab Binary files /dev/null and b/ros_kortex/kortex_examples/img/services_real_arm.png differ diff --git a/ros_kortex/kortex_examples/img/services_sim.png b/ros_kortex/kortex_examples/img/services_sim.png new file mode 100644 index 0000000..75eda69 Binary files /dev/null and b/ros_kortex/kortex_examples/img/services_sim.png differ diff --git a/ros_kortex/kortex_examples/launch/actuator_config_cpp.launch b/ros_kortex/kortex_examples/launch/actuator_config_cpp.launch new file mode 100644 index 0000000..8554df3 --- /dev/null +++ b/ros_kortex/kortex_examples/launch/actuator_config_cpp.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/actuator_config_python.launch b/ros_kortex/kortex_examples/launch/actuator_config_python.launch new file mode 100644 index 0000000..1bbcd4e --- /dev/null +++ b/ros_kortex/kortex_examples/launch/actuator_config_python.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/cartesian_poses_with_notifications_cpp.launch b/ros_kortex/kortex_examples/launch/cartesian_poses_with_notifications_cpp.launch new file mode 100644 index 0000000..47b984c --- /dev/null +++ b/ros_kortex/kortex_examples/launch/cartesian_poses_with_notifications_cpp.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/cartesian_poses_with_notifications_python.launch b/ros_kortex/kortex_examples/launch/cartesian_poses_with_notifications_python.launch new file mode 100644 index 0000000..4979330 --- /dev/null +++ b/ros_kortex/kortex_examples/launch/cartesian_poses_with_notifications_python.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/full_arm_movement_cpp.launch b/ros_kortex/kortex_examples/launch/full_arm_movement_cpp.launch new file mode 100644 index 0000000..98c7998 --- /dev/null +++ b/ros_kortex/kortex_examples/launch/full_arm_movement_cpp.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/full_arm_movement_python.launch b/ros_kortex/kortex_examples/launch/full_arm_movement_python.launch new file mode 100644 index 0000000..9bab2b0 --- /dev/null +++ b/ros_kortex/kortex_examples/launch/full_arm_movement_python.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/moveit_example.launch b/ros_kortex/kortex_examples/launch/moveit_example.launch new file mode 100644 index 0000000..403f5bd --- /dev/null +++ b/ros_kortex/kortex_examples/launch/moveit_example.launch @@ -0,0 +1,10 @@ + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/run_all_examples.launch b/ros_kortex/kortex_examples/launch/run_all_examples.launch new file mode 100644 index 0000000..d20e6ed --- /dev/null +++ b/ros_kortex/kortex_examples/launch/run_all_examples.launch @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/vision_configuration_cpp.launch b/ros_kortex/kortex_examples/launch/vision_configuration_cpp.launch new file mode 100644 index 0000000..1624674 --- /dev/null +++ b/ros_kortex/kortex_examples/launch/vision_configuration_cpp.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/launch/vision_configuration_python.launch b/ros_kortex/kortex_examples/launch/vision_configuration_python.launch new file mode 100644 index 0000000..ac355d0 --- /dev/null +++ b/ros_kortex/kortex_examples/launch/vision_configuration_python.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_examples/package.xml b/ros_kortex/kortex_examples/package.xml new file mode 100644 index 0000000..6d9fbc5 --- /dev/null +++ b/ros_kortex/kortex_examples/package.xml @@ -0,0 +1,34 @@ + + + kortex_examples + 2.2.2 + Examples to show usage of core kortex_arm_driver services and topics. + + Hugo Lamontagne + Alexandre Vannobel + + + BSD + + catkin + roscpp + rospy + std_msgs + roscpp + rospy + std_msgs + roscpp + rospy + std_msgs + message_generation + kortex_driver + message_runtime + moveit_commander + moveit_commander + + + + + + + diff --git a/ros_kortex/kortex_examples/readme.md b/ros_kortex/kortex_examples/readme.md new file mode 100644 index 0000000..2083281 --- /dev/null +++ b/ros_kortex/kortex_examples/readme.md @@ -0,0 +1,146 @@ + + +# Kortex Examples + + + +1. [Before running an example](#first_of_all) +2. [Understanding the ways to use a Kortex arm with ROS](#the_ways) +3. [Actuator configuration examples](#actuator_config) +4. [Full arm movement examples](#full_arm) +5. [Vision module configuration examples](#vision_config) +6. [MoveIt! examples](#move_it) + + + + +## Before running an example + +Before you run any example, make sure : +- You have already built the packages using `catkin_make`. +- You are physically connected to an arm (or you are connected over Wi-Fi) and you have started the `kortex_driver` node by following the [instructions](../kortex_driver/readme.md), or you have started the arm in simulation following the [instructions](../kortex_gazebo/readme.md). +- The node started correctly and without errors. + + +## The ways to use a Kortex arm with ROS + +There are a couple ways to use a Kortex arm with ROS, may it be in simulation or with a real arm. + +1. Using the auto-generated services and topics + + The driver auto-generates ROS services based on the C++ Kortex API, so every API call has its ROS equivalent. Some topics (not auto-generated) are also offered for convenience. You can read more about services, topics and notifications [here](../kortex_driver/readme.md#services). + + **With a real arm**, the auto-generated wrapper translates ROS requests to Kortex API requests (Protobuf), and translated responses back to ROS structures. + + ![](./img/services_real_arm.png) + + **In simulation**, the same services and topics are advertised by the kortex_driver node, but instead of translating to Kortex API and forwarding to an arm, the message either goes through on our own simulator (if the handler for the given service is implemented) or a default response is sent back and a warning printed. + + ![](./img/services_sim.png) + + Only a couple "core" services handlers have been implemented in simulation (mostly the ones that make the robot move and stop), namely: + - PlayJointTrajectory and the REACH_JOINT_ANGLES action type (to reach an angular goal) + - PlayCartesianTrajectory and the REACH_POSE action type (to reach a Cartesian goal) + - SendGripperCommand and the SEND_GRIPPER_COMMAND action type (to actuate the gripper) + - SendJointSpeedsCommand (for joint velocity control) + - ApplyEmergencyStop and Stop (to stop the robot) + - The Actions interface (ExecuteAction, ExecuteActionFromReference, CreateAction, DeleteAction, UpdateAction, StopAction). + + It is also important to note that IK solutions for real arms and simulated arms may vary, as KDL is used in simulation and our own kinematics library is used in the arm's firmware. + + The simulated SendTwistCommand service has a POC implementation, we decided it is not stable enough to be activated by default. You can uncomment the kortex_arm_driver.cpp simulation handler to re-enable it and try it yourself. The same goes for the Cartesian velocity topic. + + There is no plan to add more simulated services for now, but any user can write his own implementation of a Kortex ROS Service and enable the handler for it (let's say you want to simulate an Interconnect Expansion GPIO device, or a Vision device). The kortex_arm_driver.cpp file should provide all guidelines as to how to define your handler, and you are welcome to open an issue if you want more information on simulation handlers. + +2. Using MoveIt + + The kortex_driver offers a FollowJointTrajectory Action Server and a GripperCommand Action Server (when a gripper is used) and the MoveIt configuration files are stored for all configurations in kortex_move_it_config. This enables users to use the MoveIt Commander, or the MoveIt Python or C++ interfaces to control the arm with the motion planning framework. + + The FollowJointTrajectory Action Server pipeline is illustrated below: + + ![](./img/moveit.png) + + **With a real arm**, the FollowJointTrajectory Action Server uses the Kortex API `PlayPreComputedJointTrajectory`. This call expects a full joint trajectory interpolated at a 1ms timestep, because the arm takes the trajectory as is, verifies it respects all velocity and acceleration constraints and then executes it as a low-level trajectory. Because of this timestep constraint, the MoveIt OMPL planning pipeline has an additional step which uses the `industrial_trajectory_filters/UniformSampleFilter` to interpolate the MoveIt output with a 1ms-timestep. Any timestep that provides a wrong velocity or acceleration causes the whole trajectory to be rejected. The velocity and acceleration limits in the configuration files have been tuned so no trajectory should yield such values, but if you experience trajectory rejection problems, you can tune down those parameters. + + **In simulation**, the FollowJointTrajectory and GripperCommand Action Servers are the ones spawned by the ros_controllers used with Gazebo. They don't need 1ms-timestep, but no option was added in MoveIt to switch between simulated or real action servers, so the same interpolator is used in simulation although it is not required. The Gen3 Intel Realsense camera is not simulated. + +3. Low-level control + + **With a real arm**, the low-level control functions have not been added to the Kortex API wrapper because the arm absolutely needs 1kHz control, otherwise it jerks. As ROS is not really real-time friendly, we chose not to offer those functions. + + **In simulation**, the ros_controllers used with Gazebo can be directly controlled with their associated topics if you prefer controlling the joints directly without using the simulation handlers, but be aware that this interface is not accessible with the real arm! The code you write that way will need to be changed significantly to be used with a real arm. + + + +## Actuator configuration examples +*Examples to show how to use actuator_config ROS services to configure a given actuator.* + +The examples look for advertised services in the **my_gen3** namespace by default and configures the first actuator. + +To run the C++ example: `roslaunch kortex_examples actuator_config_cpp.launch` + +To run the Python example: `roslaunch kortex_examples actuator_config_python.launch` + +If you started the `kortex_driver` node in another namespace (not **my_gen3**) or if you want to test the example on another actuator than the first one, you will have to supply node parameters in the command line (the syntax doesn't change if you run the C++ or Python example): + +`roslaunch kortex_examples actuator_config_cpp.launch robot_name:= device_id:=` + + +## Full arm examples +*Examples to show how to use the base ROS services to move and configure the arm.* + +The examples look for advertised services in the **my_gen3** namespace by default. + +- **Simple movement example**: + + - To run the C++ example: `roslaunch kortex_examples full_arm_movement_cpp.launch` + - To run the Python example: `roslaunch kortex_examples full_arm_movement_python.launch` + + If you started the `kortex_driver` node in another namespace (not **my_gen3**), you will have to supply the node a parameter in the command line (the syntax doesn't change if you run the C++ or Python example) : + + `roslaunch kortex_examples full_arm_movement_cpp.launch robot_name:=` + +- **Cartesian poses with notifications**: + + - To run the C++ example: `roslaunch kortex_examples cartesian_poses_with_notifications_cpp.launch` + - To run the Python example: `roslaunch kortex_examples cartesian_poses_with_notifications_python.launch` + + If you started the `kortex_driver` node in another namespace (not **my_gen3**), you will have to supply the node a parameter in the command line (the syntax doesn't change if you run the C++ or Python example) : + + `roslaunch kortex_examples cartesian_poses_with_notifications_cpp.launch robot_name:=` + + +## Vision module configuration examples +*Examples to show how to use the vision_config ROS services to configure the vision module.* + +The examples look for advertised services in the **my_gen3** namespace by default. + +To run the C++ example: `roslaunch kortex_examples vision_configuration_cpp.launch` + +To run the Python example: `roslaunch kortex_examples vision_configuration_python.launch` + +If you started the `kortex_driver` node in another namespace (not **my_gen3**), you will have to supply the node a parameter in the command line (the syntax doesn't change if you run the C++ or Python example) : + +`roslaunch kortex_examples vision_configuration_cpp.launch robot_name:=` + + +## MoveIt! example +*Example to show how to use the Python MoveIt! API to move the arm.* + +The example looks for advertised services and topics in the **my_gen3** namespace by default. + +To run the example: `roslaunch kortex_examples moveit_example.launch` + +If you started the `kortex_driver` node in a non-default namespace (not **my_gen3**), you will have to supply the node your own namespace in the command line : + +`roslaunch kortex_examples moveit_example.launch robot_name:=` diff --git a/ros_kortex/kortex_examples/setup.py b/ros_kortex/kortex_examples/setup.py new file mode 100644 index 0000000..a257e28 --- /dev/null +++ b/ros_kortex/kortex_examples/setup.py @@ -0,0 +1,7 @@ +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +setup(**generate_distutils_setup( + packages=['kortex_examples'], + package_dir={'': 'src'} +)) \ No newline at end of file diff --git a/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.cpp b/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.cpp new file mode 100644 index 0000000..7bd12b0 --- /dev/null +++ b/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.cpp @@ -0,0 +1,226 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2019 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +typedef kortex_driver::GetControlLoopParameters::Response::_output_type ControlLoopParameters; + +std::string control_loop_to_string(uint32_t int_control_loop) +{ + switch (int_control_loop) + { + case kortex_driver::ControlLoopSelection::RESERVED: + return "RESERVED"; + case kortex_driver::ControlLoopSelection::JOINT_POSITION: + return "JOINT POSITION"; + case kortex_driver::ControlLoopSelection::MOTOR_POSITION: + return "MOTOR POSITION"; + case kortex_driver::ControlLoopSelection::JOINT_VELOCITY: + return "JOINT VELOCITY"; + case kortex_driver::ControlLoopSelection::MOTOR_VELOCITY: + return "MOTOR VELOCITY"; + case kortex_driver::ControlLoopSelection::JOINT_TORQUE: + return "JOINT TORQUE"; + case kortex_driver::ControlLoopSelection::MOTOR_CURRENT: + return "MOTOR CURRENT"; + default: + return "UNKNOWN CONTROL LOOP TYPE"; + } +} + +bool example_find_actuators_and_set_device_id(ros::NodeHandle& n, const std::string& robot_name, uint32_t device_id) +{ + ros::ServiceClient service_client_read_all_devices = n.serviceClient("/" + robot_name + "/device_manager/read_all_devices"); + kortex_driver::ReadAllDevices service_read_all_devices; + kortex_driver::DeviceTypes device_type; + std::vector device_id_vector; + + std::ostringstream oss; + oss << std::endl; + + if (service_client_read_all_devices.call(service_read_all_devices)) + { + auto output = service_read_all_devices.response.output; + // Cycle through all found devices to find actuators + for(int i = 0; i < output.device_handle.size(); i++) + { + + if((output.device_handle[i].device_type == device_type.BIG_ACTUATOR) || + (output.device_handle[i].device_type == device_type.MEDIUM_ACTUATOR) || + (output.device_handle[i].device_type == device_type.SMALL_ACTUATOR)) + { + // Add the device_id to the vector if we found an actuator + device_id_vector.push_back(output.device_handle[i].device_identifier); + oss << "Found an actuator with device id " << output.device_handle[i].device_identifier << std::endl; + } + } + } + else + { + std::string error_string = "Failed to call ReadAllDevices"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + oss << "----------------------------"; + ROS_INFO("%s", oss.str().c_str()); + oss.clear(); + + // Check if the specified device_id is in the vector + if (std::find(device_id_vector.begin(), device_id_vector.end(), device_id) != device_id_vector.end()) + { + ROS_INFO("Device id %u is a valid actuator device id.", device_id); + } + else + { + std::string error_string = "Device id " + std::to_string(device_id) + " does not correspond to an actuator's device id."; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // We need to set the device ID of the actuator we want to configure + ros::ServiceClient service_client_set_device_id = n.serviceClient("/" + robot_name + "/actuator_config/set_device_id"); + kortex_driver::SetDeviceID service_set_device_id; + service_set_device_id.request.device_id = device_id; + if (service_client_set_device_id.call(service_set_device_id)) + { + ROS_INFO("Device ID was properly set."); + } + else + { + std::string error_string = "Failed to call SetDeviceID"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + return true; + +} + +bool example_clear_actuator_faults(ros::NodeHandle& n, const std::string& robot_name) +{ + ros::ServiceClient service_client_clear_faults = n.serviceClient("/" + robot_name + "/actuator_config/clear_faults"); + kortex_driver::ActuatorConfig_ClearFaults service_clear_faults; + if (service_client_clear_faults.call(service_clear_faults)) + { + ROS_INFO("Faults were cleared properly."); + return true; + } + else + { + std::string error_string = "Failed to call ActuatorConfig_ClearFaults"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } +} + +bool example_get_control_loop_parameters(ros::NodeHandle& n, const std::string& robot_name, ControlLoopParameters& output) +{ + // Get the actuator control loop parameters + ros::ServiceClient service_client_get_control_loop_parameters = n.serviceClient("/" + robot_name + "/actuator_config/get_control_loop_parameters"); + kortex_driver::GetControlLoopParameters service_get_control_loop_parameters; + std::ostringstream oss; + if (service_client_get_control_loop_parameters.call(service_get_control_loop_parameters)) + { + // The msg file can be found at kortex_driver/msg/generated/actuator_config/ControlLoopParameters.msg + kortex_driver::GetControlLoopParametersResponse::_output_type initial_parameters = service_get_control_loop_parameters.response.output; + oss << std::endl << "Control Loop Parameters : " << std::endl; + oss << "Loop selection : " << control_loop_to_string(initial_parameters.loop_selection) << std::endl; + oss << "Error saturation : " << initial_parameters.error_saturation << std::endl; + oss << "Output saturation : " << initial_parameters.output_saturation << std::endl; + oss << "kAz : ["; + for (auto element : initial_parameters.kAz) + oss << element << "; "; + oss << "]" << std::endl; + oss << "kBz : ["; + for (auto element : initial_parameters.kBz) + oss << element << "; "; + oss << "]" << std::endl; + oss << "Error dead band : " << initial_parameters.error_dead_band << std::endl; + ROS_INFO("%s", oss.str().c_str()); + output = initial_parameters; + return true; + } + else + { + std::string error_string = "Failed to call GetControlLoopParameters"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } +} + +int main(int argc, char **argv) +{ + // Init the node and get the namespace parameter + ros::init(argc, argv, "actuator_configuration_example_cpp"); + + // For testing purpose + ros::param::del("/kortex_examples_test_results/actuator_configuration_cpp"); + + bool success = true; + + ros::NodeHandle n; + std::string robot_name = "my_gen3"; + int device_id = 1; + + // Parameter robot_name + if (!ros::param::get("~robot_name", robot_name)) + { + std::string error_string = "Parameter robot_name was not specified, defaulting to " + robot_name + " as namespace"; + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using robot_name " + robot_name + " as namespace"; + ROS_INFO("%s", error_string.c_str()); + } + + // Parameter device_id + if (!ros::param::get("~device_id", device_id)) + { + std::string error_string = "Parameter device_id was not specified, defaulting to " + std::to_string(device_id); + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using device_id " + std::to_string(device_id); + ROS_INFO("%s", error_string.c_str()); + } + + //------------------------------------------------------------- + // Find actuators and set which one we want to configure + success &= example_find_actuators_and_set_device_id(n, robot_name, device_id); + + //------------------------------------------------------------- + // Clear the faults on a specific actuator + success &= example_clear_actuator_faults(n, robot_name); + + //------------------------------------------------------------- + // Get the control loop parameters on a specific actuator + ControlLoopParameters parameters; + success &= example_get_control_loop_parameters(n, robot_name, parameters); + + // Report success for testing purposes + ros::param::set("/kortex_examples_test_results/actuator_configuration_cpp", success); + + return success ? 0 : 1; +} \ No newline at end of file diff --git a/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.py b/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.py new file mode 100755 index 0000000..7291a3c --- /dev/null +++ b/ros_kortex/kortex_examples/src/actuator_config/example_actuator_configuration.py @@ -0,0 +1,176 @@ +#!/usr/bin/env python +### +# KINOVA (R) KORTEX (TM) +# +# Copyright (c) 2019 Kinova inc. All rights reserved. +# +# This software may be modified and distributed +# under the terms of the BSD 3-Clause license. +# +# Refer to the LICENSE file for details. +# +### + +import sys +import rospy +from std_msgs.msg import Bool +from kortex_driver.srv import * +from kortex_driver.msg import * + +class ExampleActuatorConfiguration: + def __init__(self): + try: + rospy.init_node('example_actuator_configuration_python') + + # Get node params + self.robot_name = rospy.get_param('~robot_name', "my_gen3") + self.device_id = rospy.get_param('~device_id', 1) + rospy.loginfo("Using robot_name " + self.robot_name + " and device_id " + str(self.device_id)) + + # Init the services + read_all_devices_full_name = '/' + self.robot_name + '/device_manager/read_all_devices' + rospy.wait_for_service(read_all_devices_full_name, 0.5) + self.read_all_devices = rospy.ServiceProxy(read_all_devices_full_name, ReadAllDevices) + + set_device_id_full_name = '/' + self.robot_name + '/actuator_config/set_device_id' + rospy.wait_for_service(set_device_id_full_name, 0.5) + self.set_device_id = rospy.ServiceProxy(set_device_id_full_name, SetDeviceID) + + clear_faults_full_name = '/' + self.robot_name + '/actuator_config/clear_faults' + rospy.wait_for_service(clear_faults_full_name, 0.5) + self.clear_faults = rospy.ServiceProxy(clear_faults_full_name, ActuatorConfig_ClearFaults) + + get_control_loop_parameters_full_name = '/' + self.robot_name + '/actuator_config/get_control_loop_parameters' + rospy.wait_for_service(get_control_loop_parameters_full_name, 0.5) + self.get_control_loop_parameters = rospy.ServiceProxy(get_control_loop_parameters_full_name, GetControlLoopParameters) + except: + self.is_init_success = False + else: + self.is_init_success = True + + def control_loop_to_string(self, control_loop): + if control_loop == ControlLoopSelection.RESERVED: + return "RESERVED" + elif control_loop == ControlLoopSelection.JOINT_POSITION: + return "JOINT POSITION" + elif control_loop == ControlLoopSelection.MOTOR_POSITION: + return "MOTOR POSITION" + elif control_loop == ControlLoopSelection.JOINT_VELOCITY: + return "JOINT VELOCITY" + elif control_loop == ControlLoopSelection.MOTOR_VELOCITY: + return "MOTOR VELOCITY" + elif control_loop == ControlLoopSelection.JOINT_TORQUE: + return "JOINT TORQUE" + elif control_loop == ControlLoopSelection.MOTOR_CURRENT: + return "MOTOR CURRENT" + else: + return "UNKNOWN CONTROL LOOP TYPE"; + + def example_find_actuators_and_set_device_id(self): + rospy.loginfo("-------------------------------") + rospy.loginfo("Finding actuators...") + + actuator_device_ids = [] + + try: + all_devices = self.read_all_devices() + for device in all_devices.output.device_handle: + if device.device_type == DeviceTypes.BIG_ACTUATOR or device.device_type == DeviceTypes.SMALL_ACTUATOR or device.device_type == DeviceTypes.MEDIUM_ACTUATOR: + # Add the device_id to the list if we found an actuator + actuator_device_ids.append(device.device_identifier) + rospy.loginfo("Found an actuator with device id " + str(device.device_identifier)) + + except rospy.ServiceException: + rospy.logerr("Failed to call ReadAllDevices.") + return False + + else: + rospy.loginfo("-------------------------------") + + # Check if the specified device_id is in the list + if self.device_id in actuator_device_ids: + rospy.loginfo("Device id " + str(self.device_id) + " is a valid actuator device id.") + else: + raise ValueError("Device id " + str(self.device_id) + " does not correspond to an actuator's device id.") + return False + + # We need to set the device ID of the actuator we want to configure + req = SetDeviceIDRequest() + req.device_id = self.device_id + try: + self.set_device_id(req) + except rospy.ServiceException: + rospy.logerr("Failed to call SetDeviceId") + return False + + return True + + def example_clear_actuator_faults(self): + try: + self.clear_faults() + rospy.loginfo("Faults were cleared successfully on actuator " + str(self.device_id)) + return True + except rospy.ServiceException: + rospy.logerr("Failed to call ActuatorConfig_ClearFaults") + return False + + def example_get_control_loop_parameters(self, output): + try: + control_loop_parameters_response = self.get_control_loop_parameters() + except rospy.ServiceException: + rospy.logerr("Failed to call GetControlLoopParameters") + return False + else: + # The msg file can be found at kortex_driver/msg/generated/actuator_config/ControlLoopParameters.msg + oss = "" + control_loop_parameters = control_loop_parameters_response.output + oss = oss + "\nControl Loop parameters :\n" + oss = oss + "Loop selection : " + self.control_loop_to_string(control_loop_parameters.loop_selection) + "\n" + oss = oss + "Error saturation : " + str(control_loop_parameters.error_saturation) + "\n" + oss = oss + "Output saturation : " + str(control_loop_parameters.output_saturation) + "\n" + oss = oss + "kAz : [" + for element in control_loop_parameters.kAz: + oss = oss + str(element) + " ;" + oss = oss + "]\n" + oss = oss + "kBz : [" + for element in control_loop_parameters.kBz: + oss = oss + str(element) + " ; " + oss = oss + "]\n" + oss = oss + "Error dead band : " + str(control_loop_parameters.error_dead_band) + "\n" + rospy.loginfo(oss) + + output = control_loop_parameters + return True + + def main(self): + # For testing purposes + success = self.is_init_success + try: + rospy.delete_param("/kortex_examples_test_results/actuator_configuration_python") + except: + pass + + if success: + + #------------------------------------------------------------- + # Find actuators and set which one we want to configure + success &= self.example_find_actuators_and_set_device_id() + + #------------------------------------------------------------- + # Clear the faults on a specific actuator + success &= self.example_clear_actuator_faults() + + #------------------------------------------------------------- + # Get the control loop parameters on a specific actuator + control_loop_parameters = None + success &= self.example_get_control_loop_parameters(control_loop_parameters) + + # For testing purposes + rospy.set_param("/kortex_examples_test_results/actuator_configuration_python", success) + + if not success: + rospy.logerr("The example encountered an error.") + +if __name__ == "__main__": + ex = ExampleActuatorConfiguration() + ex.main() diff --git a/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp b/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp new file mode 100644 index 0000000..37b0943 --- /dev/null +++ b/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.cpp @@ -0,0 +1,270 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2019 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ +#include +#include + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define HOME_ACTION_IDENTIFIER 2 + +bool all_notifs_succeeded = true; + +std::atomic last_action_notification_event{0}; +std::atomic last_action_notification_id{0}; + +void notification_callback(const kortex_driver::ActionNotification& notif) +{ + last_action_notification_event = notif.action_event; + last_action_notification_id = notif.handle.identifier; +} + +bool wait_for_action_end_or_abort() +{ + while (ros::ok()) + { + if (last_action_notification_event.load() == kortex_driver::ActionEvent::ACTION_END) + { + ROS_INFO("Received ACTION_END notification for action %d", last_action_notification_id.load()); + return true; + } + else if (last_action_notification_event.load() == kortex_driver::ActionEvent::ACTION_ABORT) + { + ROS_INFO("Received ACTION_ABORT notification for action %d", last_action_notification_id.load()); + all_notifs_succeeded = false; + return false; + } + ros::spinOnce(); + } +} + +bool example_home_the_robot(ros::NodeHandle n, std::string robot_name) +{ + ros::ServiceClient service_client_read_action = n.serviceClient("/" + robot_name + "/base/read_action"); + kortex_driver::ReadAction service_read_action; + + // The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + service_read_action.request.input.identifier = HOME_ACTION_IDENTIFIER; + + if (!service_client_read_action.call(service_read_action)) + { + std::string error_string = "Failed to call ReadAction"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // We can now execute the Action that we read + ros::ServiceClient service_client_execute_action = n.serviceClient("/" + robot_name + "/base/execute_action"); + kortex_driver::ExecuteAction service_execute_action; + + service_execute_action.request.input = service_read_action.response.output; + + if (service_client_execute_action.call(service_execute_action)) + { + ROS_INFO("The Home position action was sent to the robot."); + } + else + { + std::string error_string = "Failed to call ExecuteAction"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + return wait_for_action_end_or_abort(); +} + +bool example_cartesian_action(ros::NodeHandle n, std::string robot_name) +{ + ros::ServiceClient service_client_activate_notif = n.serviceClient("/" + robot_name + "/base/activate_publishing_of_action_topic"); + kortex_driver::OnNotificationActionTopic service_activate_notif; + + // We need to call this service to activate the Action Notification on the kortex_driver node. + if (service_client_activate_notif.call(service_activate_notif)) + { + ROS_INFO("Action notification activated!"); + } + else + { + std::string error_string = "Action notification publication failed"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + ros::Duration(1.00).sleep(); + + kortex_driver::ConstrainedPose my_constrained_pose; + kortex_driver::CartesianSpeed my_cartesian_speed; + + my_cartesian_speed.translation = 0.1f; + my_cartesian_speed.orientation = 15.0f; + + my_constrained_pose.constraint.oneof_type.speed.push_back(my_cartesian_speed); + + my_constrained_pose.target_pose.x = 0.374f; + my_constrained_pose.target_pose.y = 0.081f; + my_constrained_pose.target_pose.z = 0.450f; + my_constrained_pose.target_pose.theta_x = -57.6f; + my_constrained_pose.target_pose.theta_y = 91.1f; + my_constrained_pose.target_pose.theta_z = 2.3f; + + ros::ServiceClient service_client_execute_action = n.serviceClient("/" + robot_name + "/base/execute_action"); + kortex_driver::ExecuteAction service_execute_action; + + service_execute_action.request.input.oneof_action_parameters.reach_pose.push_back(my_constrained_pose); + service_execute_action.request.input.name = "pose1"; + service_execute_action.request.input.handle.identifier = 1001; + service_execute_action.request.input.handle.action_type = kortex_driver::ActionType::REACH_POSE; + + last_action_notification_event = 0; + if (service_client_execute_action.call(service_execute_action)) + { + ROS_INFO("Pose 1 was sent to the robot."); + } + else + { + std::string error_string = "Failed to call ExecuteAction on pose 1"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // Waiting for the pose 1 to end + wait_for_action_end_or_abort(); + + // Change the pose and give it a new identifier + service_execute_action.request.input.handle.identifier = 1002; + service_execute_action.request.input.name = "pose2"; + + my_constrained_pose.target_pose.z = 0.3f; + + service_execute_action.request.input.oneof_action_parameters.reach_pose.clear(); + service_execute_action.request.input.oneof_action_parameters.reach_pose.push_back(my_constrained_pose); + + last_action_notification_event = 0; + if (service_client_execute_action.call(service_execute_action)) + { + ROS_INFO("Pose 2 was sent to the robot."); + } + else + { + std::string error_string = "Failed to call ExecuteAction on pose 2"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // Waiting for the pose 2 to end. + wait_for_action_end_or_abort(); + + // Change the pose and give it a new identifier + service_execute_action.request.input.handle.identifier = 1003; + service_execute_action.request.input.name = "pose3"; + + my_constrained_pose.target_pose.x = 0.45f; + + service_execute_action.request.input.oneof_action_parameters.reach_pose.clear(); + service_execute_action.request.input.oneof_action_parameters.reach_pose.push_back(my_constrained_pose); + + last_action_notification_event = 0; + if (service_client_execute_action.call(service_execute_action)) + { + ROS_INFO("Pose 3 was sent to the robot."); + } + else + { + std::string error_string = "Failed to call ExecuteAction on pose 3"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // Waiting for the pose 3 to end + wait_for_action_end_or_abort(); + + return true; +} + +// This function sets the reference frame to the robot's base +bool example_set_cartesian_reference_frame(ros::NodeHandle n, std::string robot_name) +{ + // Initialize the ServiceClient + ros::ServiceClient service_client_set_cartesian_reference_frame = n.serviceClient("/" + robot_name + "/control_config/set_cartesian_reference_frame"); + kortex_driver::SetCartesianReferenceFrame service_set_cartesian_reference_frame; + + service_set_cartesian_reference_frame.request.input.reference_frame = kortex_driver::CartesianReferenceFrame::CARTESIAN_REFERENCE_FRAME_BASE; + if (!service_client_set_cartesian_reference_frame.call(service_set_cartesian_reference_frame)) + { + std::string error_string = "Failed to call SetCartesianReferenceFrame"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + else + { + ROS_INFO("Set reference to base frame."); + } + + // Wait a bit + std::this_thread::sleep_for(std::chrono::milliseconds(250)); + + return true; +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "full_arm_cartesian_action_cpp"); + + // For testing purpose + ros::param::del("/kortex_examples_test_results/cartesian_poses_with_notifications_cpp"); + + bool success = true; + + //******************************************************************************* + // ROS Parameters + ros::NodeHandle n; + std::string robot_name = "my_gen3"; + + // Parameter robot_name + if (!ros::param::get("~robot_name", robot_name)) + { + std::string error_string = "Parameter robot_name was not specified, defaulting to " + robot_name + " as namespace"; + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using robot_name " + robot_name + " as namespace"; + ROS_INFO("%s", error_string.c_str()); + } + + ros::Subscriber sub = n.subscribe("/" + robot_name + "/action_topic", 1000, notification_callback); + success &= example_set_cartesian_reference_frame(n, robot_name); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + success &= example_home_the_robot(n, robot_name); + success &= example_cartesian_action(n, robot_name); + success &= all_notifs_succeeded; + + // Report success for testing purposes + ros::param::set("/kortex_examples_test_results/cartesian_poses_with_notifications_cpp", success); + + return success ? 0 : 1; +} \ No newline at end of file diff --git a/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py b/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py new file mode 100755 index 0000000..9e9e3dd --- /dev/null +++ b/ros_kortex/kortex_examples/src/full_arm/example_cartesian_poses_with_notifications.py @@ -0,0 +1,261 @@ +#!/usr/bin/env python +### +# KINOVA (R) KORTEX (TM) +# +# Copyright (c) 2019 Kinova inc. All rights reserved. +# +# This software may be modified and distributed +# under the terms of the BSD 3-Clause license. +# +# Refer to the LICENSE file for details. +# +### + +import sys +import rospy +import time +from kortex_driver.srv import * +from kortex_driver.msg import * + +class ExampleCartesianActionsWithNotifications: + def __init__(self): + try: + rospy.init_node('example_cartesian_poses_with_notifications_python') + + self.HOME_ACTION_IDENTIFIER = 2 + + self.action_topic_sub = None + self.all_notifs_succeeded = True + + # Get node params + self.robot_name = rospy.get_param('~robot_name', "my_gen3") + + rospy.loginfo("Using robot_name " + self.robot_name) + + # Init the action topic subscriber + self.action_topic_sub = rospy.Subscriber("/" + self.robot_name + "/action_topic", ActionNotification, self.cb_action_topic) + self.last_action_notif_type = None + + # Init the services + clear_faults_full_name = '/' + self.robot_name + '/base/clear_faults' + rospy.wait_for_service(clear_faults_full_name) + self.clear_faults = rospy.ServiceProxy(clear_faults_full_name, Base_ClearFaults) + + read_action_full_name = '/' + self.robot_name + '/base/read_action' + rospy.wait_for_service(read_action_full_name) + self.read_action = rospy.ServiceProxy(read_action_full_name, ReadAction) + + execute_action_full_name = '/' + self.robot_name + '/base/execute_action' + rospy.wait_for_service(execute_action_full_name) + self.execute_action = rospy.ServiceProxy(execute_action_full_name, ExecuteAction) + + set_cartesian_reference_frame_full_name = '/' + self.robot_name + '/control_config/set_cartesian_reference_frame' + rospy.wait_for_service(set_cartesian_reference_frame_full_name) + self.set_cartesian_reference_frame = rospy.ServiceProxy(set_cartesian_reference_frame_full_name, SetCartesianReferenceFrame) + + activate_publishing_of_action_notification_full_name = '/' + self.robot_name + '/base/activate_publishing_of_action_topic' + rospy.wait_for_service(activate_publishing_of_action_notification_full_name) + self.activate_publishing_of_action_notification = rospy.ServiceProxy(activate_publishing_of_action_notification_full_name, OnNotificationActionTopic) + except: + self.is_init_success = False + else: + self.is_init_success = True + + def cb_action_topic(self, notif): + self.last_action_notif_type = notif.action_event + + def wait_for_action_end_or_abort(self): + while not rospy.is_shutdown(): + if (self.last_action_notif_type == ActionEvent.ACTION_END): + rospy.loginfo("Received ACTION_END notification") + return True + elif (self.last_action_notif_type == ActionEvent.ACTION_ABORT): + rospy.loginfo("Received ACTION_ABORT notification") + self.all_notifs_succeeded = False + return False + else: + time.sleep(0.01) + + def example_clear_faults(self): + try: + self.clear_faults() + except rospy.ServiceException: + rospy.logerr("Failed to call ClearFaults") + return False + else: + rospy.loginfo("Cleared the faults successfully") + rospy.sleep(2.5) + return True + + def example_home_the_robot(self): + # The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + req = ReadActionRequest() + req.input.identifier = self.HOME_ACTION_IDENTIFIER + self.last_action_notif_type = None + try: + res = self.read_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ReadAction") + return False + # Execute the HOME action if we could read it + else: + # What we just read is the input of the ExecuteAction service + req = ExecuteActionRequest() + req.input = res.output + rospy.loginfo("Sending the robot home...") + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ExecuteAction") + return False + else: + return self.wait_for_action_end_or_abort() + + def example_set_cartesian_reference_frame(self): + # Prepare the request with the frame we want to set + req = SetCartesianReferenceFrameRequest() + req.input.reference_frame = CartesianReferenceFrame.CARTESIAN_REFERENCE_FRAME_MIXED + + # Call the service + try: + self.set_cartesian_reference_frame() + except rospy.ServiceException: + rospy.logerr("Failed to call SetCartesianReferenceFrame") + return False + else: + rospy.loginfo("Set the cartesian reference frame successfully") + return True + + # Wait a bit + rospy.sleep(0.25) + + def example_subscribe_to_a_robot_notification(self): + # Activate the publishing of the ActionNotification + req = OnNotificationActionTopicRequest() + rospy.loginfo("Activating the action notifications...") + try: + self.activate_publishing_of_action_notification(req) + except rospy.ServiceException: + rospy.logerr("Failed to call OnNotificationActionTopic") + return False + else: + rospy.loginfo("Successfully activated the Action Notifications!") + + rospy.sleep(1.0) + + return True + + def main(self): + # For testing purposes + success = self.is_init_success + try: + rospy.delete_param("/kortex_examples_test_results/cartesian_poses_with_notifications_python") + except: + pass + + if success: + + #******************************************************************************* + # Make sure to clear the robot's faults else it won't move if it's already in fault + success &= self.example_clear_faults() + #******************************************************************************* + + #******************************************************************************* + # Subscribe to ActionNotification's from the robot to know when a cartesian pose is finished + success &= self.example_subscribe_to_a_robot_notification() + #******************************************************************************* + + #******************************************************************************* + # Start the example from the Home position + success &= self.example_home_the_robot() + #******************************************************************************* + + #******************************************************************************* + # Set the reference frame to "Mixed" + success &= self.example_set_cartesian_reference_frame() + + #******************************************************************************* + # Prepare and send pose 1 + my_cartesian_speed = CartesianSpeed() + my_cartesian_speed.translation = 0.1 # m/s + my_cartesian_speed.orientation = 15 # deg/s + + my_constrained_pose = ConstrainedPose() + my_constrained_pose.constraint.oneof_type.speed.append(my_cartesian_speed) + + my_constrained_pose.target_pose.x = 0.374 + my_constrained_pose.target_pose.y = 0.081 + my_constrained_pose.target_pose.z = 0.450 + my_constrained_pose.target_pose.theta_x = -57.6 + my_constrained_pose.target_pose.theta_y = 91.1 + my_constrained_pose.target_pose.theta_z = 2.3 + + req = ExecuteActionRequest() + req.input.oneof_action_parameters.reach_pose.append(my_constrained_pose) + req.input.name = "pose1" + req.input.handle.action_type = ActionType.REACH_POSE + req.input.handle.identifier = 1001 + + rospy.loginfo("Sending pose 1...") + self.last_action_notif_type = None + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to send pose 1") + success = False + else: + rospy.loginfo("Waiting for pose 1 to finish...") + + self.wait_for_action_end_or_abort() + + # Prepare and send pose 2 + req.input.handle.identifier = 1002 + req.input.name = "pose2" + + my_constrained_pose.target_pose.z = 0.3 + + req.input.oneof_action_parameters.reach_pose[0] = my_constrained_pose + + rospy.loginfo("Sending pose 2...") + self.last_action_notif_type = None + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to send pose 2") + success = False + else: + rospy.loginfo("Waiting for pose 2 to finish...") + + self.wait_for_action_end_or_abort() + + # Prepare and send pose 3 + req.input.handle.identifier = 1003 + req.input.name = "pose3" + + my_constrained_pose.target_pose.x = 0.45 + + req.input.oneof_action_parameters.reach_pose[0] = my_constrained_pose + + rospy.loginfo("Sending pose 3...") + self.last_action_notif_type = None + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to send pose 3") + success = False + else: + rospy.loginfo("Waiting for pose 3 to finish...") + + self.wait_for_action_end_or_abort() + + success &= self.all_notifs_succeeded + + # For testing purposes + rospy.set_param("/kortex_examples_test_results/cartesian_poses_with_notifications_python", success) + + if not success: + rospy.logerr("The example encountered an error.") + +if __name__ == "__main__": + ex = ExampleCartesianActionsWithNotifications() + ex.main() diff --git a/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.cpp b/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.cpp new file mode 100644 index 0000000..8459f12 --- /dev/null +++ b/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.cpp @@ -0,0 +1,363 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2019 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ +#include +#include + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define HOME_ACTION_IDENTIFIER 2 + +std::atomic last_action_notification_event{0}; + +void notification_callback(const kortex_driver::ActionNotification& notif) +{ + last_action_notification_event = notif.action_event; +} + +bool wait_for_action_end_or_abort() +{ + while (ros::ok()) + { + if (last_action_notification_event.load() == kortex_driver::ActionEvent::ACTION_END) + { + ROS_INFO("Received ACTION_END notification"); + return true; + } + else if (last_action_notification_event.load() == kortex_driver::ActionEvent::ACTION_ABORT) + { + ROS_INFO("Received ACTION_ABORT notification"); + return false; + } + ros::spinOnce(); + } +} + + + +bool example_clear_faults(ros::NodeHandle n, std::string robot_name) +{ + ros::ServiceClient service_client_clear_faults = n.serviceClient("/" + robot_name + "/base/clear_faults"); + kortex_driver::Base_ClearFaults service_clear_faults; + + // Clear the faults + if (!service_client_clear_faults.call(service_clear_faults)) + { + std::string error_string = "Failed to clear the faults"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // Wait a bit + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + return true; +} + +bool example_home_the_robot(ros::NodeHandle n, std::string robot_name) +{ + ros::ServiceClient service_client_read_action = n.serviceClient("/" + robot_name + "/base/read_action"); + kortex_driver::ReadAction service_read_action; + last_action_notification_event = 0; + + // The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + service_read_action.request.input.identifier = HOME_ACTION_IDENTIFIER; + + if (!service_client_read_action.call(service_read_action)) + { + std::string error_string = "Failed to call ReadAction"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // We can now execute the Action that we read + ros::ServiceClient service_client_execute_action = n.serviceClient("/" + robot_name + "/base/execute_action"); + kortex_driver::ExecuteAction service_execute_action; + + service_execute_action.request.input = service_read_action.response.output; + + if (service_client_execute_action.call(service_execute_action)) + { + ROS_INFO("The Home position action was sent to the robot."); + } + else + { + std::string error_string = "Failed to call ExecuteAction"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + return wait_for_action_end_or_abort(); +} + +bool example_set_cartesian_reference_frame(ros::NodeHandle n, std::string robot_name) +{ + // Initialize the ServiceClient + ros::ServiceClient service_client_set_cartesian_reference_frame = n.serviceClient("/" + robot_name + "/control_config/set_cartesian_reference_frame"); + kortex_driver::SetCartesianReferenceFrame service_set_cartesian_reference_frame; + + service_set_cartesian_reference_frame.request.input.reference_frame = kortex_driver::CartesianReferenceFrame::CARTESIAN_REFERENCE_FRAME_MIXED; + if (!service_client_set_cartesian_reference_frame.call(service_set_cartesian_reference_frame)) + { + std::string error_string = "Failed to call SetCartesianReferenceFrame"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + // Wait a bit + std::this_thread::sleep_for(std::chrono::milliseconds(250)); + + return true; +} + +bool example_send_cartesian_pose(ros::NodeHandle n, std::string robot_name) +{ + last_action_notification_event = 0; + // Get the actual cartesian pose to increment it + // You can create a subscriber to listen to the base_feedback + // Here we only need the latest message in the topic though + auto feedback = ros::topic::waitForMessage("/" + robot_name + "/base_feedback"); + + // Initialize the ServiceClient for the cartesian pose + ros::ServiceClient service_client_play_cartesian_trajectory = n.serviceClient("/" + robot_name + "/base/play_cartesian_trajectory"); + kortex_driver::PlayCartesianTrajectory service_play_cartesian_trajectory; + + // Initialize input + float current_x = feedback->base.commanded_tool_pose_x; + float current_y = feedback->base.commanded_tool_pose_y; + float current_z = feedback->base.commanded_tool_pose_z; + float current_theta_x = feedback->base.commanded_tool_pose_theta_x; + float current_theta_y = feedback->base.commanded_tool_pose_theta_y; + float current_theta_z = feedback->base.commanded_tool_pose_theta_z; + + // Creating the target pose + service_play_cartesian_trajectory.request.input.target_pose.x = current_x; + service_play_cartesian_trajectory.request.input.target_pose.y = current_y; + service_play_cartesian_trajectory.request.input.target_pose.z = current_z + 0.10; + service_play_cartesian_trajectory.request.input.target_pose.theta_x = current_theta_x; + service_play_cartesian_trajectory.request.input.target_pose.theta_y = current_theta_y; + service_play_cartesian_trajectory.request.input.target_pose.theta_z = current_theta_z; + + kortex_driver::CartesianSpeed poseSpeed; + poseSpeed.translation = 0.1; + poseSpeed.orientation = 15; + + // The constraint is a one_of in Protobuf. The one_of concept does not exist in ROS + // To specify a one_of, create it and put it in the appropriate vector of the oneof_type member of the ROS object : + service_play_cartesian_trajectory.request.input.constraint.oneof_type.speed.push_back(poseSpeed); + + if (service_client_play_cartesian_trajectory.call(service_play_cartesian_trajectory)) + { + ROS_INFO("The new cartesian pose was sent to the robot."); + } + else + { + std::string error_string = "Failed to call PlayCartesianTrajectory"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + return wait_for_action_end_or_abort(); +} + +bool example_send_joint_angles(ros::NodeHandle n, std::string robot_name, int degrees_of_freedom) +{ + last_action_notification_event = 0; + // Initialize the ServiceClient + ros::ServiceClient service_client_play_joint_trajectory = n.serviceClient("/" + robot_name + "/base/play_joint_trajectory"); + kortex_driver::PlayJointTrajectory service_play_joint_trajectory; + + std::vector angles_to_send; + for (unsigned int i = 0; i < degrees_of_freedom; i++) + { + angles_to_send.push_back(0.0); + } + + for (int i = 0; i < degrees_of_freedom; i++) + { + kortex_driver::JointAngle temp_angle; + temp_angle.joint_identifier = i; + temp_angle.value = angles_to_send[i]; + service_play_joint_trajectory.request.input.joint_angles.joint_angles.push_back(temp_angle); + } + + if (service_client_play_joint_trajectory.call(service_play_joint_trajectory)) + { + ROS_INFO("The joint angles were sent to the robot."); + } + else + { + std::string error_string = "Failed to call PlayJointTrajectory"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + return wait_for_action_end_or_abort(); +} + +bool example_send_gripper_command(ros::NodeHandle n, std::string robot_name, double value) +{ + // Initialize the ServiceClient + ros::ServiceClient service_client_send_gripper_command = n.serviceClient("/" + robot_name + "/base/send_gripper_command"); + kortex_driver::SendGripperCommand service_send_gripper_command; + + // Initialize the request + kortex_driver::Finger finger; + finger.finger_identifier = 0; + finger.value = value; + service_send_gripper_command.request.input.gripper.finger.push_back(finger); + service_send_gripper_command.request.input.mode = kortex_driver::GripperMode::GRIPPER_POSITION; + + if (service_client_send_gripper_command.call(service_send_gripper_command)) + { + ROS_INFO("The gripper command was sent to the robot."); + } + else + { + std::string error_string = "Failed to call SendGripperCommand"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + return true; +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "full_arm_movement_example_cpp"); + + // For testing purpose + ros::param::del("/kortex_examples_test_results/full_arm_movement_cpp"); + + bool success = true; + + //******************************************************************************* + // ROS Parameters + ros::NodeHandle n; + std::string robot_name = "my_gen3"; + int degrees_of_freedom = 7; + bool is_gripper_present = false; + + // Parameter robot_name + if (!ros::param::get("~robot_name", robot_name)) + { + std::string error_string = "Parameter robot_name was not specified, defaulting to " + robot_name + " as namespace"; + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using robot_name " + robot_name + " as namespace"; + ROS_INFO("%s", error_string.c_str()); + } + + // Parameter degrees_of_freedom + if (!ros::param::get("/" + robot_name + "/degrees_of_freedom", degrees_of_freedom)) + { + std::string error_string = "Parameter /" + robot_name + "/degrees_of_freedom was not specified, defaulting to " + std::to_string(degrees_of_freedom) + " as degrees of freedom"; + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using degrees_of_freedom " + std::to_string(degrees_of_freedom) + " as degrees_of_freedom"; + ROS_INFO("%s", error_string.c_str()); + } + + // Parameter is_gripper_present + if (!ros::param::get("/" + robot_name + "/is_gripper_present", is_gripper_present)) + { + std::string error_string = "Parameter /" + robot_name + "/is_gripper_present was not specified, defaulting to " + std::to_string(is_gripper_present); + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using is_gripper_present " + std::to_string(is_gripper_present); + ROS_INFO("%s", error_string.c_str()); + } + //******************************************************************************* + + // Subscribe to the Action Topic + ros::Subscriber sub = n.subscribe("/" + robot_name + "/action_topic", 1000, notification_callback); + + // We need to call this service to activate the Action Notification on the kortex_driver node. + ros::ServiceClient service_client_activate_notif = n.serviceClient("/" + robot_name + "/base/activate_publishing_of_action_topic"); + kortex_driver::OnNotificationActionTopic service_activate_notif; + if (service_client_activate_notif.call(service_activate_notif)) + { + ROS_INFO("Action notification activated!"); + } + else + { + std::string error_string = "Action notification publication failed"; + ROS_ERROR("%s", error_string.c_str()); + success = false; + } + + //******************************************************************************* + // Make sure to clear the robot's faults else it won't move if it's already in fault + success &= example_clear_faults(n, robot_name); + //******************************************************************************* + + //******************************************************************************* + // Move the robot to the Home position with an Action + success &= example_home_the_robot(n, robot_name); + //******************************************************************************* + + //******************************************************************************* + // Example of gripper command + // Let's close the gripper + if (is_gripper_present) + { + success &= example_send_gripper_command(n, robot_name, 0.0); + } + //******************************************************************************* + + //******************************************************************************* + // Set the reference frame to "Mixed" + success &= example_set_cartesian_reference_frame(n, robot_name); + + // Example of cartesian pose + // Let's make it move in Z + success &= example_send_cartesian_pose(n, robot_name); + //******************************************************************************* + + //******************************************************************************* + // Example of angular position + // Let's send the arm to vertical position + success &= example_send_joint_angles(n, robot_name, degrees_of_freedom); + //******************************************************************************* + + //******************************************************************************* + // Example of gripper command + // Let's close the gripper + if (is_gripper_present) + { + success &= example_send_gripper_command(n, robot_name, 0.5); + } + //******************************************************************************* + + // Report success for testing purposes + ros::param::set("/kortex_examples_test_results/full_arm_movement_cpp", success); + + return success ? 0 : 1; +} \ No newline at end of file diff --git a/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.py b/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.py new file mode 100755 index 0000000..14868b1 --- /dev/null +++ b/ros_kortex/kortex_examples/src/full_arm/example_full_arm_movement.py @@ -0,0 +1,300 @@ +#!/usr/bin/env python +### +# KINOVA (R) KORTEX (TM) +# +# Copyright (c) 2019 Kinova inc. All rights reserved. +# +# This software may be modified and distributed +# under the terms of the BSD 3-Clause license. +# +# Refer to the LICENSE file for details. +# +### + +import sys +import rospy +import time +from kortex_driver.srv import * +from kortex_driver.msg import * + +class ExampleFullArmMovement: + def __init__(self): + try: + rospy.init_node('example_full_arm_movement_python') + + self.HOME_ACTION_IDENTIFIER = 2 + + # Get node params + self.robot_name = rospy.get_param('~robot_name', "my_gen3") + self.degrees_of_freedom = rospy.get_param("/" + self.robot_name + "/degrees_of_freedom", 7) + self.is_gripper_present = rospy.get_param("/" + self.robot_name + "/is_gripper_present", False) + + rospy.loginfo("Using robot_name " + self.robot_name + " , robot has " + str(self.degrees_of_freedom) + " degrees of freedom and is_gripper_present is " + str(self.is_gripper_present)) + + # Init the action topic subscriber + self.action_topic_sub = rospy.Subscriber("/" + self.robot_name + "/action_topic", ActionNotification, self.cb_action_topic) + self.last_action_notif_type = None + + # Init the services + clear_faults_full_name = '/' + self.robot_name + '/base/clear_faults' + rospy.wait_for_service(clear_faults_full_name) + self.clear_faults = rospy.ServiceProxy(clear_faults_full_name, Base_ClearFaults) + + read_action_full_name = '/' + self.robot_name + '/base/read_action' + rospy.wait_for_service(read_action_full_name) + self.read_action = rospy.ServiceProxy(read_action_full_name, ReadAction) + + execute_action_full_name = '/' + self.robot_name + '/base/execute_action' + rospy.wait_for_service(execute_action_full_name) + self.execute_action = rospy.ServiceProxy(execute_action_full_name, ExecuteAction) + + set_cartesian_reference_frame_full_name = '/' + self.robot_name + '/control_config/set_cartesian_reference_frame' + rospy.wait_for_service(set_cartesian_reference_frame_full_name) + self.set_cartesian_reference_frame = rospy.ServiceProxy(set_cartesian_reference_frame_full_name, SetCartesianReferenceFrame) + + play_cartesian_trajectory_full_name = '/' + self.robot_name + '/base/play_cartesian_trajectory' + rospy.wait_for_service(play_cartesian_trajectory_full_name) + self.play_cartesian_trajectory = rospy.ServiceProxy(play_cartesian_trajectory_full_name, PlayCartesianTrajectory) + + play_joint_trajectory_full_name = '/' + self.robot_name + '/base/play_joint_trajectory' + rospy.wait_for_service(play_joint_trajectory_full_name) + self.play_joint_trajectory = rospy.ServiceProxy(play_joint_trajectory_full_name, PlayJointTrajectory) + + send_gripper_command_full_name = '/' + self.robot_name + '/base/send_gripper_command' + rospy.wait_for_service(send_gripper_command_full_name) + self.send_gripper_command = rospy.ServiceProxy(send_gripper_command_full_name, SendGripperCommand) + + activate_publishing_of_action_notification_full_name = '/' + self.robot_name + '/base/activate_publishing_of_action_topic' + rospy.wait_for_service(activate_publishing_of_action_notification_full_name) + self.activate_publishing_of_action_notification = rospy.ServiceProxy(activate_publishing_of_action_notification_full_name, OnNotificationActionTopic) + except: + self.is_init_success = False + else: + self.is_init_success = True + + def cb_action_topic(self, notif): + self.last_action_notif_type = notif.action_event + + def wait_for_action_end_or_abort(self): + while not rospy.is_shutdown(): + if (self.last_action_notif_type == ActionEvent.ACTION_END): + rospy.loginfo("Received ACTION_END notification") + return True + elif (self.last_action_notif_type == ActionEvent.ACTION_ABORT): + rospy.loginfo("Received ACTION_ABORT notification") + return False + else: + time.sleep(0.01) + + def example_subscribe_to_a_robot_notification(self): + # Activate the publishing of the ActionNotification + req = OnNotificationActionTopicRequest() + rospy.loginfo("Activating the action notifications...") + try: + self.activate_publishing_of_action_notification(req) + except rospy.ServiceException: + rospy.logerr("Failed to call OnNotificationActionTopic") + return False + else: + rospy.loginfo("Successfully activated the Action Notifications!") + + rospy.sleep(1.0) + return True + + def example_clear_faults(self): + try: + self.clear_faults() + except rospy.ServiceException: + rospy.logerr("Failed to call ClearFaults") + return False + else: + rospy.loginfo("Cleared the faults successfully") + rospy.sleep(2.5) + return True + + def example_home_the_robot(self): + # The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + self.last_action_notif_type = None + req = ReadActionRequest() + req.input.identifier = self.HOME_ACTION_IDENTIFIER + try: + res = self.read_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ReadAction") + return False + # Execute the HOME action if we could read it + else: + # What we just read is the input of the ExecuteAction service + req = ExecuteActionRequest() + req.input = res.output + rospy.loginfo("Sending the robot home...") + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ExecuteAction") + return False + else: + return self.wait_for_action_end_or_abort() + + def example_set_cartesian_reference_frame(self): + self.last_action_notif_type = None + # Prepare the request with the frame we want to set + req = SetCartesianReferenceFrameRequest() + req.input.reference_frame = CartesianReferenceFrame.CARTESIAN_REFERENCE_FRAME_MIXED + + # Call the service + try: + self.set_cartesian_reference_frame() + except rospy.ServiceException: + rospy.logerr("Failed to call SetCartesianReferenceFrame") + return False + else: + rospy.loginfo("Set the cartesian reference frame successfully") + + # Wait a bit + rospy.sleep(0.25) + return True + + def example_send_cartesian_pose(self): + self.last_action_notif_type = None + # Get the actual cartesian pose to increment it + # You can create a subscriber to listen to the base_feedback + # Here we only need the latest message in the topic though + feedback = rospy.wait_for_message("/" + self.robot_name + "/base_feedback", BaseCyclic_Feedback) + + req = PlayCartesianTrajectoryRequest() + req.input.target_pose.x = feedback.base.commanded_tool_pose_x + req.input.target_pose.y = feedback.base.commanded_tool_pose_y + req.input.target_pose.z = feedback.base.commanded_tool_pose_z + 0.10 + req.input.target_pose.theta_x = feedback.base.commanded_tool_pose_theta_x + req.input.target_pose.theta_y = feedback.base.commanded_tool_pose_theta_y + req.input.target_pose.theta_z = feedback.base.commanded_tool_pose_theta_z + + pose_speed = CartesianSpeed() + pose_speed.translation = 0.1 + pose_speed.orientation = 15 + + # The constraint is a one_of in Protobuf. The one_of concept does not exist in ROS + # To specify a one_of, create it and put it in the appropriate list of the oneof_type member of the ROS object : + req.input.constraint.oneof_type.speed.append(pose_speed) + + # Call the service + rospy.loginfo("Sending the robot to the cartesian pose...") + try: + self.play_cartesian_trajectory(req) + except rospy.ServiceException: + rospy.logerr("Failed to call PlayCartesianTrajectory") + return False + else: + return self.wait_for_action_end_or_abort() + + def example_send_joint_angles(self): + self.last_action_notif_type = None + # Create the list of angles + req = PlayJointTrajectoryRequest() + # Here the arm is vertical (all zeros) + for i in range(self.degrees_of_freedom): + temp_angle = JointAngle() + temp_angle.joint_identifier = i + temp_angle.value = 0.0 + req.input.joint_angles.joint_angles.append(temp_angle) + + # Send the angles + rospy.loginfo("Sending the robot vertical...") + try: + self.play_joint_trajectory(req) + except rospy.ServiceException: + rospy.logerr("Failed to call PlayJointTrajectory") + return False + else: + return self.wait_for_action_end_or_abort() + + def example_send_gripper_command(self, value): + # Initialize the request + # Close the gripper + req = SendGripperCommandRequest() + finger = Finger() + finger.finger_identifier = 0 + finger.value = value + req.input.gripper.finger.append(finger) + req.input.mode = GripperMode.GRIPPER_POSITION + + rospy.loginfo("Sending the gripper command...") + + # Call the service + try: + self.send_gripper_command(req) + except rospy.ServiceException: + rospy.logerr("Failed to call SendGripperCommand") + return False + else: + time.sleep(0.5) + return True + + def main(self): + # For testing purposes + success = self.is_init_success + try: + rospy.delete_param("/kortex_examples_test_results/full_arm_movement_python") + except: + pass + + if success: + #******************************************************************************* + # Make sure to clear the robot's faults else it won't move if it's already in fault + success &= self.example_clear_faults() + #******************************************************************************* + + #******************************************************************************* + # Activate the action notifications + success &= self.example_subscribe_to_a_robot_notification() + #******************************************************************************* + + #******************************************************************************* + # Move the robot to the Home position with an Action + success &= self.example_home_the_robot() + #******************************************************************************* + + #******************************************************************************* + # Example of gripper command + # Let's fully open the gripper + if self.is_gripper_present: + success &= self.example_send_gripper_command(0.0) + else: + rospy.logwarn("No gripper is present on the arm.") + #******************************************************************************* + + #******************************************************************************* + # Set the reference frame to "Mixed" + success &= self.example_set_cartesian_reference_frame() + + # Example of cartesian pose + # Let's make it move in Z + success &= self.example_send_cartesian_pose() + #******************************************************************************* + + #******************************************************************************* + # Example of angular position + # Let's send the arm to vertical position + success &= self.example_send_joint_angles() + #******************************************************************************* + + #******************************************************************************* + # Example of gripper command + # Let's close the gripper at 50% + if self.is_gripper_present: + success &= self.example_send_gripper_command(0.5) + else: + rospy.logwarn("No gripper is present on the arm.") + #******************************************************************************* + + # For testing purposes + rospy.set_param("/kortex_examples_test_results/full_arm_movement_python", success) + + if not success: + rospy.logerr("The example encountered an error.") + + +if __name__ == "__main__": + ex = ExampleFullArmMovement() + ex.main() diff --git a/ros_kortex/kortex_examples/src/move_it/example_move_it_trajectories.py b/ros_kortex/kortex_examples/src/move_it/example_move_it_trajectories.py new file mode 100755 index 0000000..82db88f --- /dev/null +++ b/ros_kortex/kortex_examples/src/move_it/example_move_it_trajectories.py @@ -0,0 +1,240 @@ +#!/usr/bin/env python + +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, SRI International +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of SRI International nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Acorn Pooley, Mike Lautman + +# Inspired from http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/move_group_python_interface/move_group_python_interface_tutorial.html +# Modified by Alexandre Vannobel to test the FollowJointTrajectory Action Server for the Kinova Gen3 robot + +# To run this node in a given namespace with rosrun (for example 'my_gen3'), start a Kortex driver and then run : +# rosrun kortex_examples example_moveit_trajectories.py __ns:=my_gen3 + +import sys +import time +import rospy +import moveit_commander +import moveit_msgs.msg +import geometry_msgs.msg +from math import pi +from std_srvs.srv import Empty + +class ExampleMoveItTrajectories(object): + """ExampleMoveItTrajectories""" + def __init__(self): + + # Initialize the node + super(ExampleMoveItTrajectories, self).__init__() + moveit_commander.roscpp_initialize(sys.argv) + rospy.init_node('example_move_it_trajectories') + + try: + self.is_gripper_present = rospy.get_param(rospy.get_namespace() + "is_gripper_present", False) + if self.is_gripper_present: + gripper_joint_names = rospy.get_param(rospy.get_namespace() + "gripper_joint_names", []) + self.gripper_joint_name = gripper_joint_names[0] + else: + gripper_joint_name = "" + self.degrees_of_freedom = rospy.get_param(rospy.get_namespace() + "degrees_of_freedom", 7) + + # Create the MoveItInterface necessary objects + arm_group_name = "arm" + self.robot = moveit_commander.RobotCommander("robot_description") + self.scene = moveit_commander.PlanningSceneInterface(ns=rospy.get_namespace()) + self.arm_group = moveit_commander.MoveGroupCommander(arm_group_name, ns=rospy.get_namespace()) + self.display_trajectory_publisher = rospy.Publisher(rospy.get_namespace() + 'move_group/display_planned_path', + moveit_msgs.msg.DisplayTrajectory, + queue_size=20) + + if self.is_gripper_present: + gripper_group_name = "gripper" + self.gripper_group = moveit_commander.MoveGroupCommander(gripper_group_name, ns=rospy.get_namespace()) + + rospy.loginfo("Initializing node in namespace " + rospy.get_namespace()) + except Exception as e: + print (e) + self.is_init_success = False + else: + self.is_init_success = True + + + def reach_named_position(self, target): + arm_group = self.arm_group + + # Going to one of those targets + rospy.loginfo("Going to named target " + target) + # Set the target + arm_group.set_named_target(target) + # Plan the trajectory + planned_path1 = arm_group.plan() + # Execute the trajectory and block while it's not finished + return arm_group.execute(planned_path1, wait=True) + + def reach_joint_angles(self, tolerance): + arm_group = self.arm_group + success = True + + # Get the current joint positions + joint_positions = arm_group.get_current_joint_values() + rospy.loginfo("Printing current joint positions before movement :") + for p in joint_positions: rospy.loginfo(p) + + # Set the goal joint tolerance + self.arm_group.set_goal_joint_tolerance(tolerance) + + # Set the joint target configuration + if self.degrees_of_freedom == 7: + joint_positions[0] = pi/2 + joint_positions[1] = 0 + joint_positions[2] = pi/4 + joint_positions[3] = -pi/4 + joint_positions[4] = 0 + joint_positions[5] = pi/2 + joint_positions[6] = 0.2 + elif self.degrees_of_freedom == 6: + joint_positions[0] = 0 + joint_positions[1] = 0 + joint_positions[2] = pi/2 + joint_positions[3] = pi/4 + joint_positions[4] = 0 + joint_positions[5] = pi/2 + arm_group.set_joint_value_target(joint_positions) + + # Plan and execute in one command + success &= arm_group.go(wait=True) + + # Show joint positions after movement + new_joint_positions = arm_group.get_current_joint_values() + rospy.loginfo("Printing current joint positions after movement :") + for p in new_joint_positions: rospy.loginfo(p) + return success + + def get_cartesian_pose(self): + arm_group = self.arm_group + + # Get the current pose and display it + pose = arm_group.get_current_pose() + rospy.loginfo("Actual cartesian pose is : ") + rospy.loginfo(pose.pose) + + return pose.pose + + def reach_cartesian_pose(self, pose, tolerance, constraints): + arm_group = self.arm_group + + # Set the tolerance + arm_group.set_goal_position_tolerance(tolerance) + + # Set the trajectory constraint if one is specified + if constraints is not None: + arm_group.set_path_constraints(constraints) + + # Get the current Cartesian Position + arm_group.set_pose_target(pose) + + # Plan and execute + rospy.loginfo("Planning and going to the Cartesian Pose") + return arm_group.go(wait=True) + + def reach_gripper_position(self, relative_position): + gripper_group = self.gripper_group + + # We only have to move this joint because all others are mimic! + gripper_joint = self.robot.get_joint(self.gripper_joint_name) + gripper_max_absolute_pos = gripper_joint.max_bound() + gripper_min_absolute_pos = gripper_joint.min_bound() + try: + val = gripper_joint.move(relative_position * (gripper_max_absolute_pos - gripper_min_absolute_pos) + gripper_min_absolute_pos, True) + return val + except: + return False + +def main(): + example = ExampleMoveItTrajectories() + + # For testing purposes + success = example.is_init_success + try: + rospy.delete_param("/kortex_examples_test_results/moveit_general_python") + except: + pass + + if success: + rospy.loginfo("Reaching Named Target Vertical...") + + success &= example.reach_named_position("vertical") + + rospy.loginfo("Reaching Joint Angles...") + + success &= example.reach_joint_angles(tolerance=0.01) #rad + + rospy.loginfo("Reaching Named Target Home...") + + success &= example.reach_named_position("home") + + rospy.loginfo("Reaching Cartesian Pose...") + + actual_pose = example.get_cartesian_pose() + actual_pose.position.z -= 0.2 + success &= example.reach_cartesian_pose(pose=actual_pose, tolerance=0.01, constraints=None) + + if example.degrees_of_freedom == 7: + rospy.loginfo("Reach Cartesian Pose with constraints...") + # Get actual pose + actual_pose = example.get_cartesian_pose() + actual_pose.position.y -= 0.3 + + # Orientation constraint (we want the end effector to stay the same orientation) + constraints = moveit_msgs.msg.Constraints() + orientation_constraint = moveit_msgs.msg.OrientationConstraint() + orientation_constraint.orientation = actual_pose.orientation + constraints.orientation_constraints.append(orientation_constraint) + + # Send the goal + success &= example.reach_cartesian_pose(pose=actual_pose, tolerance=0.01, constraints=constraints) + + if example.is_gripper_present: + rospy.loginfo("Opening the gripper...") + success &= example.reach_gripper_position(0) + + rospy.loginfo("Closing the gripper 50%...") + success &= example.reach_gripper_position(0.5) + + # For testing purposes + rospy.set_param("/kortex_examples_test_results/moveit_general_python", success) + + if not success: + rospy.logerr("The example encountered an error.") + +if __name__ == '__main__': + main() diff --git a/ros_kortex/kortex_examples/src/move_it/simulation_pid_tuning.py b/ros_kortex/kortex_examples/src/move_it/simulation_pid_tuning.py new file mode 100755 index 0000000..78e5c42 --- /dev/null +++ b/ros_kortex/kortex_examples/src/move_it/simulation_pid_tuning.py @@ -0,0 +1,120 @@ +#!/usr/bin/env python + +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, SRI International +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of SRI International nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Acorn Pooley, Mike Lautman + +# Inspired from http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/move_group_python_interface/move_group_python_interface_tutorial.html +# Modified by Alexandre Vannobel to tune the simulated controller's PID for Gazebo and the Gen3 robot + +# Usage : +# rosrun kortex_examples simulation_pid_tuning.py _inertia:=low _actuator:=3 _sleep_time:=2 +# inertia : low or high +# actuator : 1 to max number (7 for Gen3) +# sleep_time : time to sleep between trajectories (in seconds) + +import sys +import time +import rospy +import moveit_commander +import moveit_msgs.msg +import geometry_msgs.msg +from math import pi +from std_srvs.srv import Empty + +high_inertia = [[[0, 1.57, 0, 0, 0, 0, 0],[0, 1.57, 0, 0, 0, 0, 0],[0, 1.57, 1.57, 0, 0, 0, 0],[0, 0, 0, 1.57, 0, 0, 0],[0, 0.78, 0, 0.78, 0, 0, 0],[0, 0.78, 0, 0.78, 0, 0.25, 0],[0, 0.78, 0, 0.78, 0, 0, 0]], \ + [[0.25, 1.57, 0, 0, 0, 0, 0],[0, 1.25, 0, 0, 0, 0, 0],[0, 1.57, 1.25, 0, 0, 0, 0],[0, 0, 0, 1.25, 0, 0, 0],[0, 0.78, 0, 0.78, 0.25, 0, 0],[0, 0.78, 0, 0.78, 0, 0, 0],[0, 0.78, 0, 0.78, 0, 0, 0.25]]] + +low_inertia = [[[0, 0, 0, 0, 0, 0, 0],[0, 1.57, 1.57, 1.57, 0, 1.57, 0],[0, 0, 0, 0, 0, 0, 0],[0, 0, 0, 1.57, 0, 1.57, 0],[0, 0, 0, 0, 0, 0, 0],[0, 0.78, 0, 0.78, 0, 1.57, 0],[0, 0, 0, 0, 0, 0, 0]], \ + [[0.25, 0, 0, 0, 0, 0, 0], [0, 1.25, 1.57, 1.57, 0, 1.57, 0], [0, 0, 0.25, 0, 0, 0, 0], [0, 0, 0, 1.25, 0, 1.57, 0], [0, 0, 0, 0, 0.25, 0, 0],[0, 0.78, 0, 0.78, 0, 1.25, 0],[0, 0, 0, 0, 0, 0, 0.25]]] + +class MoveItPIDTuning(object): + """MoveItPIDTuning""" + def __init__(self): + + # Initialize the node + super(MoveItPIDTuning, self).__init__() + moveit_commander.roscpp_initialize(sys.argv) + rospy.init_node('MoveItPIDTuning_node') + + self.actuator = rospy.get_param("~actuator") + if self.actuator < 1 or self.actuator > 7: + rospy.logerr("Actuator must be between 1 and 7 inclusively for gen3") + exit(0) + self.inertia = rospy.get_param("~inertia") + rospy.loginfo("---{}---".format(self.inertia)) + if self.inertia != "low" and self.inertia != "high": + rospy.logerr("Inertia must be low or high") + exit(0) + self.sleep_time = rospy.get_param("~sleep_time") + + # Create the MoveItInterface necessary objects + arm_group_name = "arm" + self.robot = moveit_commander.RobotCommander() + self.scene = moveit_commander.PlanningSceneInterface() + self.arm_group = moveit_commander.MoveGroupCommander(arm_group_name) + + def reach_joint_angles(self, using_one): + arm_group = self.arm_group + + # Set the joint target configuration + joint_target = [] + if self.inertia == "high": + if using_one is True: + joint_target = high_inertia[0][self.actuator-1] + else: + joint_target = high_inertia[1][self.actuator-1] + if self.inertia == "low": + if using_one is True: + joint_target = low_inertia[0][self.actuator-1] + else: + joint_target = low_inertia[1][self.actuator-1] + + arm_group.set_joint_value_target(joint_target) + + # Plan and execute in one command + arm_group.go(wait=True) + +def main(): + tuner = MoveItPIDTuning() + rospy.loginfo("Going to first position, then will wait 10 secs before starting") + tuner.reach_joint_angles(True) + rospy.sleep(10) + while(True): + tuner.reach_joint_angles(True) + rospy.sleep(tuner.sleep_time) + tuner.reach_joint_angles(False) + rospy.sleep(tuner.sleep_time) + +if __name__ == '__main__': + main() diff --git a/ros_kortex/kortex_examples/src/tests/kortex_examples_tests.cc b/ros_kortex/kortex_examples/src/tests/kortex_examples_tests.cc new file mode 100644 index 0000000..e5cc868 --- /dev/null +++ b/ros_kortex/kortex_examples/src/tests/kortex_examples_tests.cc @@ -0,0 +1,99 @@ +#include +#include +#include + +class KortexDriverTest : public ::testing::Test { + protected: + + void SetUp() override + { + // Make sure we erase all test results + for (auto ex : examples) + { + ros::param::del(example_prefix + ex.first); + } + + // Look for the //has_vision_module parameter to know if the vision examples should fail + ros::param::get("~robot_name", robot_name); + ros::param::get("/" + robot_name + "/has_vision_module", has_vision_module); + + // Add the vision configuration examples to the list of tests to run if needed + if (has_vision_module) + { + examples.push_back(std::make_pair("vision_configuration_cpp", true)); + examples.push_back(std::make_pair("vision_configuration_python", true)); + } + } + + void TearDown() override + { + } + + ros::NodeHandle n; + std::string robot_name; + bool has_vision_module; + const int timeout_seconds = 90; + const std::string example_prefix = "/kortex_examples_test_results/"; + // The first element is the name of the example + // The second element is a boolean value to indicate what value we expect when running this test + std::vector> examples = + { + {"actuator_configuration_python", true}, + {"cartesian_poses_with_notifications_cpp", true}, + {"cartesian_poses_with_notifications_python", true}, + {"full_arm_movement_cpp", true}, + {"full_arm_movement_python", true}, + {"actuator_configuration_cpp", true}, + {"moveit_general_python", true} + }; + + bool waitForExample(std::string example_name) + { + bool success = false; + for (int i = 0; i < timeout_seconds && !success; i++) + { + // If the parameter is not yet on the server, wait for it to come up + if (!ros::param::has(example_prefix + example_name)) + { + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + } + // If the parameter is set on the server, break + if (ros::param::get(example_prefix + example_name, success)) + { + break; + } + } + return success; + } + +}; + +// Check if all examples ran correctly +TEST_F(KortexDriverTest, checkAllExamplesSuccess) +{ + bool success = true; + std::ostringstream failed_tests_message; + failed_tests_message << "The following examples failed :" << std::endl; + for (auto ex : examples) + { + bool example_success = waitForExample(ex.first); + if (!example_success) + { + failed_tests_message << "\t- " << ex.first << std::endl; + } + success &= (example_success == ex.second); + } + ASSERT_TRUE(success) << failed_tests_message.str(); +} + +int main(int argc, char** argv){ + ros::init(argc, argv, "KortexArmDriverInitTestsNode"); + testing::InitGoogleTest(&argc, argv); + + std::thread t([]{while(ros::ok()) ros::spin();}); + + auto res = RUN_ALL_TESTS(); + + ros::shutdown(); + return res; +} \ No newline at end of file diff --git a/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.cpp b/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.cpp new file mode 100644 index 0000000..45ae83e --- /dev/null +++ b/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.cpp @@ -0,0 +1,363 @@ +/* + * KINOVA (R) KORTEX (TM) + * + * Copyright (c) 2019 Kinova inc. All rights reserved. + * + * This software may be modified and distributed + * under the terms of the BSD 3-Clause license. + * + * Refer to the LICENSE file for details. + * + */ + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +std::string sensor_type_enum_to_string(uint32_t enum_value) +{ + std::string s = ""; + switch (enum_value) + { + case kortex_driver::Sensor::SENSOR_COLOR: + s = "Color"; + break; + + case kortex_driver::Sensor::SENSOR_DEPTH: + s = "Depth"; + break; + + default: + case kortex_driver::Sensor::SENSOR_UNSPECIFIED: + s = "Unspecified"; + break; + } + return s; +} + +std::string resolution_enum_to_string(uint32_t enum_value) +{ + std::string s = ""; + switch (enum_value) + { + case kortex_driver::Resolution::RESOLUTION_320x240: + s = "320 x 240"; + break; + case kortex_driver::Resolution::RESOLUTION_424x240: + s = "424 x 240"; + break; + case kortex_driver::Resolution::RESOLUTION_480x270: + s = "480 x 270"; + break; + case kortex_driver::Resolution::RESOLUTION_640x480: + s = "640 x 480"; + break; + case kortex_driver::Resolution::RESOLUTION_1280x720: + s = "1280 x 720"; + break; + case kortex_driver::Resolution::RESOLUTION_1920x1080: + s = "1920 x 1080"; + break; + default: + case kortex_driver::Resolution::RESOLUTION_UNSPECIFIED: + s = "Unspecified"; + break; + } + return s; +} + +std::string framerate_enum_to_string(uint32_t enum_value) +{ + std::string s = ""; + switch (enum_value) + { + case kortex_driver::FrameRate::FRAMERATE_6_FPS: + s = "6 FPS"; + break; + case kortex_driver::FrameRate::FRAMERATE_15_FPS: + s = "15 FPS"; + break; + case kortex_driver::FrameRate::FRAMERATE_30_FPS: + s = "30 FPS"; + break; + default: + case kortex_driver::FrameRate::FRAMERATE_UNSPECIFIED: + s = "Unspecified"; + break; + } + return s; +} + +std::string bitrate_enum_to_string(uint32_t enum_value) +{ + std::string s = ""; + switch (enum_value) + { + case kortex_driver::BitRate::BITRATE_10_MBPS: + s = "10 MBPS"; + break; + case kortex_driver::BitRate::BITRATE_15_MBPS: + s = "15 MBPS"; + break; + case kortex_driver::BitRate::BITRATE_20_MBPS: + s = "20 MBPS"; + break; + case kortex_driver::BitRate::BITRATE_25_MBPS: + s = "25 MBPS"; + break; + default: + case kortex_driver::BitRate::BITRATE_UNSPECIFIED: + s = "Unspecified"; + break; + } + return s; +} + +bool example_get_intrinsic_parameters(ros::NodeHandle n, const std::string& robot_name) +{ + ros::ServiceClient service_client_get_intrinsic_parameters = n.serviceClient("/" + robot_name + "/vision_config/get_intrinsic_parameters"); + kortex_driver::GetIntrinsicParameters service_get_intrinsic_parameters; + + // Get the parameters from the color sensor + kortex_driver::GetIntrinsicParametersRequest req; + req.input.sensor = kortex_driver::Sensor::SENSOR_COLOR; // Change to SENSOR_DEPTH for the depth sensor + service_get_intrinsic_parameters.request = req; + + if (!service_client_get_intrinsic_parameters.call(service_get_intrinsic_parameters)) + { + std::string error_string = "Failed to call GetIntrinsicParameters"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + auto output = service_get_intrinsic_parameters.response.output; + // The message description can be seen at msg/generated/vision_config/IntrinsicParameters.msg + std::ostringstream oss; + oss << std::endl << "---------------------------------" << std::endl + << "Intrinsic parameters are : " << std::endl + << "Focal length in x is : " << output.focal_length_x << std::endl + << "Focal length in y is : " << output.focal_length_y << std::endl + << "Principal point in x is : " << output.principal_point_x << std::endl + << "Principal point in y is : " << output.principal_point_y << std::endl + << "Distortion coefficients are : [" << + "k1 = " << output.distortion_coeffs.k1 << "; " << + "k2 = " << output.distortion_coeffs.k2 << "; " << + "k3 = " << output.distortion_coeffs.k3 << "; " << + "p1 = " << output.distortion_coeffs.p1 << "; " << + "p2 = " << output.distortion_coeffs.p2 << "]" << std::endl; + + // The Sensor enum can be seen at msg/generated/vision_config/Sensor.msg + oss << "Sensor type is : " << sensor_type_enum_to_string(output.sensor) << std::endl; + + // The Resolution enum can be seen at msg/generated/vision_config/Resolution.msg + oss << "Resolution is : " << resolution_enum_to_string(output.resolution) << std::endl + << "---------------------------------"; + + ROS_INFO("%s", oss.str().c_str()); + + return true; +} + +bool example_get_extrinsic_parameters(ros::NodeHandle n, const std::string& robot_name) +{ + ros::ServiceClient service_client_get_extrinsic_parameters = n.serviceClient("/" + robot_name + "/vision_config/get_extrinsic_parameters"); + kortex_driver::GetExtrinsicParameters service_get_extrinsic_parameters; + + kortex_driver::GetExtrinsicParametersRequest req; + + if (!service_client_get_extrinsic_parameters.call(service_get_extrinsic_parameters)) + { + std::string error_string = "Failed to call GetExtrinsicParameters"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + auto output = service_get_extrinsic_parameters.response.output; + // The message description can be seen at msg/generated/vision_config/ExtrinsicParameters.msg + std::ostringstream oss; + oss << std::endl << "---------------------------------" << std::endl + << "Extrinsic parameters are : " << std::endl + << "Rotation parameters matrix is : " << std::endl + << "| " << output.rotation.row1.column1 << " ; " << output.rotation.row1.column2 << " ; " << output.rotation.row1.column3 << " |" << std::endl + << "| " << output.rotation.row2.column1 << " ; " << output.rotation.row2.column2 << " ; " << output.rotation.row2.column3 << " |" << std::endl + << "| " << output.rotation.row3.column1 << " ; " << output.rotation.row3.column2 << " ; " << output.rotation.row3.column3 << " |" << std::endl; + + oss << "Translation parameters are : " << + "[ x = " << output.translation.t_x << + " ; y = " << output.translation.t_y << + " ; z = " << output.translation.t_z << " ]" + << std::endl << "---------------------------------" << std::endl; + + ROS_INFO("%s", oss.str().c_str()); + + return true; +} + +bool example_get_sensor_settings(ros::NodeHandle n, const std::string& robot_name) +{ + ros::ServiceClient service_client_get_sensor_settings = n.serviceClient("/" + robot_name + "/vision_config/get_sensor_settings"); + kortex_driver::GetSensorSettings service_get_sensor_settings; + + kortex_driver::GetSensorSettingsRequest req; + + // Get settings for the color sensor + req.input.sensor = kortex_driver::Sensor::SENSOR_COLOR; + service_get_sensor_settings.request = req; + + if (!service_client_get_sensor_settings.call(service_get_sensor_settings)) + { + std::string error_string = "Failed to call GetSensorSettings"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + auto output = service_get_sensor_settings.response.output; + + std::ostringstream oss; + oss << std::endl << + "---------------------------------" << std::endl << + "Get sensor settings : " << std::endl << + "Bit rate : " << bitrate_enum_to_string(output.bit_rate) << std::endl << + "Frame rate : " << framerate_enum_to_string(output.frame_rate) << std::endl << + "Resolution : " << resolution_enum_to_string(output.resolution) << std::endl << + "---------------------------------"; + + ROS_INFO("%s", oss.str().c_str()); + + return true; +} + +bool example_change_the_resolution(ros::NodeHandle n, const std::string& robot_name) +{ + ros::ServiceClient service_client_set_sensor_settings = n.serviceClient("/" + robot_name + "/vision_config/set_sensor_settings"); + kortex_driver::SetSensorSettings service_set_sensor_settings; + + kortex_driver::SetSensorSettingsRequest req; + + ROS_INFO("Changing the resolution..."); + + // Set the resolution to be 640 x 480 on the color sensor + // You have to specify all parameters else the call will return an INVALID_PARAM error + req.input.sensor = kortex_driver::Sensor::SENSOR_COLOR; + req.input.resolution = kortex_driver::Resolution::RESOLUTION_1280x720; + req.input.bit_rate = kortex_driver::BitRate::BITRATE_10_MBPS; + req.input.frame_rate = kortex_driver::FrameRate::FRAMERATE_30_FPS; + + service_set_sensor_settings.request = req; + + if (!service_client_set_sensor_settings.call(service_set_sensor_settings)) + { + std::string error_string = "Failed to call SetSensorSettings"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + ROS_INFO("Resolution changed successfully."); + + return true; +} + +bool example_get_sensor_option_value(ros::NodeHandle n, const std::string& robot_name) +{ + ros::ServiceClient service_client_get_sensor_option_value = n.serviceClient("/" + robot_name + "/vision_config/get_option_value"); + kortex_driver::GetOptionValue service_get_sensor_option_value; + + kortex_driver::GetOptionValueRequest req; + + // The only supported options for now are: + // For Color sensor : + // OPTION_BRIGHTNESS, OPTION_CONTRAST, OPTION_SATURATION + // For Depth sensor : + // OPTION_EXPOSURE, OPTION_GAIN, OPTION_ENABLE_AUTO_EXPOSURE, OPTION_VISUAL_PRESET, OPTION_FRAMES_QUEUE_SIZE, + // OPTION_ERROR_POLLING_ENABLE, OPTION_OUTPUT_TRIGGER_ENABLED, OPTION_DEPTH_UNITS, + // OPTION_STEREO_BASELINE (read-only) + + // Trying to call an unsupported option in this service (or in the SetOptionValue service) will generate an error + // Get the actual value the color sensor's contrast + req.input.sensor = kortex_driver::Sensor::SENSOR_COLOR; + req.input.option = kortex_driver::Option::OPTION_CONTRAST; + + service_get_sensor_option_value.request = req; + + if (!service_client_get_sensor_option_value.call(service_get_sensor_option_value)) + { + std::string error_string = "Failed to call GetOptionValue"; + ROS_ERROR("%s", error_string.c_str()); + return false; + } + + auto output = service_get_sensor_option_value.response.output; + std::ostringstream oss; + oss << std::endl << "---------------------------------" << std::endl + << "Get Option value : " << std::endl + << "Option value is : " << std::endl + << "For sensor : " << output.sensor << std::endl + << "For option : " << output.option << std::endl + << "The value is : " << output.value << std::endl + << "---------------------------------" << std::endl; + + ROS_INFO("%s", oss.str().c_str()); + + return true; +} + +int main(int argc, char **argv) +{ + // Init the node and get the namespace parameter + ros::init(argc, argv, "vision_configuration_example_cpp"); + + // For testing purpose + ros::param::del("/kortex_examples_test_results/vision_configuration_cpp"); + + bool success = true; + + ros::NodeHandle n; + std::string robot_name = "my_gen3"; + + // Parameter robot_name + if (!ros::param::get("~robot_name", robot_name)) + { + std::string error_string = "Parameter robot_name was not specified, defaulting to " + robot_name + " as namespace"; + ROS_WARN("%s", error_string.c_str()); + } + else + { + std::string error_string = "Using robot_name " + robot_name + " as namespace"; + ROS_INFO("%s", error_string.c_str()); + } + + //------------------------------------------------------------- + // Get the intrinsic parameters for a given sensor + success &= example_get_intrinsic_parameters(n, robot_name); + + //------------------------------------------------------------- + // Get the extrinsic parameters for a given sensor + success &= example_get_extrinsic_parameters(n, robot_name); + + //------------------------------------------------------------- + // Get the sensor settings for a given sensor + success &= example_get_sensor_settings(n, robot_name); + + //------------------------------------------------------------- + // Set the extrinsic parameters for a given sensor + success &= example_change_the_resolution(n, robot_name); + + //------------------------------------------------------------- + // Get an option value + success &= example_get_sensor_option_value(n, robot_name); + + // Report success for testing purposes + ros::param::set("/kortex_examples_test_results/vision_configuration_cpp", success); + + return success ? 0 : 1; +} \ No newline at end of file diff --git a/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.py b/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.py new file mode 100755 index 0000000..5f8b50d --- /dev/null +++ b/ros_kortex/kortex_examples/src/vision_config/example_vision_configuration.py @@ -0,0 +1,287 @@ +#!/usr/bin/env python +### +# KINOVA (R) KORTEX (TM) +# +# Copyright (c) 2019 Kinova inc. All rights reserved. +# +# This software may be modified and distributed +# under the terms of the BSD 3-Clause license. +# +# Refer to the LICENSE file for details. +# +### + +import sys +import rospy +from kortex_driver.srv import * +from kortex_driver.msg import * + +class ExampleVisionConfiguration: + def __init__(self): + try: + rospy.init_node('example_vision_configuration_python') + + # Get node params + self.robot_name = rospy.get_param('~robot_name', "my_gen3") + rospy.loginfo("Using robot_name " + self.robot_name) + + # Init the services + get_intrinsic_parameters_full_name = '/' + self.robot_name + '/vision_config/get_intrinsic_parameters' + rospy.wait_for_service(get_intrinsic_parameters_full_name, 0.5) + self.get_intrinsic_parameters = rospy.ServiceProxy(get_intrinsic_parameters_full_name, GetIntrinsicParameters) + + get_extrinsic_parameters_full_name = '/' + self.robot_name + '/vision_config/get_extrinsic_parameters' + rospy.wait_for_service(get_extrinsic_parameters_full_name, 0.5) + self.get_extrinsic_parameters = rospy.ServiceProxy(get_extrinsic_parameters_full_name, GetExtrinsicParameters) + + get_sensor_settings_full_name = '/' + self.robot_name + '/vision_config/get_sensor_settings' + rospy.wait_for_service(get_sensor_settings_full_name, 0.5) + self.get_sensor_settings = rospy.ServiceProxy(get_sensor_settings_full_name, GetSensorSettings) + + set_sensor_settings_full_name = '/' + self.robot_name + '/vision_config/set_sensor_settings' + rospy.wait_for_service(set_sensor_settings_full_name, 0.5) + self.set_sensor_settings = rospy.ServiceProxy(set_sensor_settings_full_name, SetSensorSettings) + + get_option_value_full_name = '/' + self.robot_name + '/vision_config/get_option_value' + rospy.wait_for_service(get_option_value_full_name, 0.5) + self.get_option_value = rospy.ServiceProxy(get_option_value_full_name, GetOptionValue) + except: + self.is_init_success = False + else: + self.is_init_success = True + + def sensor_type_enum_to_string(self, enum_value): + s = "" + if enum_value == Sensor.SENSOR_COLOR: + s = "Color" + elif enum_value == Sensor.SENSOR_DEPTH: + s = "Depth" + else: + s = "Unspecified" + return s + + def resolution_enum_to_string(self, enum_value): + s = "" + if enum_value == Resolution.RESOLUTION_320x240: + s = "320 x 240" + elif enum_value == Resolution.RESOLUTION_424x240: + s = "424 x 240" + elif enum_value == Resolution.RESOLUTION_480x270: + s = "480 x 270" + elif enum_value == Resolution.RESOLUTION_640x480: + s = "640 x 480" + elif enum_value == Resolution.RESOLUTION_1280x720: + s = "1280 x 720" + elif enum_value == Resolution.RESOLUTION_1920x1080: + s = "1920 x 1080" + else: + s = "Unspecified" + return s + + def framerate_enum_to_string(self, enum_value): + s = "" + if enum_value == FrameRate.FRAMERATE_6_FPS: + s = "6 FPS" + elif enum_value == FrameRate.FRAMERATE_15_FPS: + s = "15 FPS" + elif enum_value == FrameRate.FRAMERATE_30_FPS: + s = "30 FPS" + else: + s = "Unspecified" + return s + + def bitrate_enum_to_string(self, enum_value): + s = "" + if enum_value == BitRate.BITRATE_10_MBPS: + s = "10 MBPS" + elif enum_value == BitRate.BITRATE_15_MBPS: + s = "15 MBPS" + elif enum_value == BitRate.BITRATE_20_MBPS: + s = "20 MBPS" + elif enum_value == BitRate.BITRATE_25_MBPS: + s = "25 MBPS" + else: + s = "Unspecified" + return s + + def example_get_intrinsic_parameters(self): + # Call the service to get the params + req = GetIntrinsicParametersRequest() + req.input.sensor = Sensor.SENSOR_COLOR # Change to SENSOR_DEPTH for the depth sensor + try: + res = self.get_intrinsic_parameters(req) + except rospy.ServiceException: + rospy.logerr("Failed to call GetIntrinsicParameters") + return False + else: + # Print them + # The message description can be seen at msg/generated/vision_config/IntrinsicParameters.msg + intrinsic_parameters = res.output + out = "" + out += "\n----------------------------------\n" + out += "Intrinsic parameters are :\n" + out += "Focal length in x is : " + str(intrinsic_parameters.focal_length_x) + "\n" + out += "Focal length in y is : " + str(intrinsic_parameters.focal_length_y) + "\n" + out += "Principal point in x is : " + str(intrinsic_parameters.principal_point_x) + "\n" + out += "Principal point in y is : " + str(intrinsic_parameters.principal_point_y) + "\n" + out += "Distortion coefficients are : [" + out += "k1 = " + str(intrinsic_parameters.distortion_coeffs.k1) + "; " + out += "k2 = " + str(intrinsic_parameters.distortion_coeffs.k2) + "; " + out += "k3 = " + str(intrinsic_parameters.distortion_coeffs.k3) + "; " + out += "p1 = " + str(intrinsic_parameters.distortion_coeffs.p1) + "; " + out += "p2 = " + str(intrinsic_parameters.distortion_coeffs.p2) + "]" + "\n" + + # The Sensor enum can be seen at msg/generated/vision_config/Sensor.msg + out += "Sensor type is : " + self.sensor_type_enum_to_string(intrinsic_parameters.sensor) + "\n" + + # The Resolution enum can be seen at msg/generated/vision_config/Resolution.msg + out += "Resolution is : " + self.resolution_enum_to_string(intrinsic_parameters.resolution) + "\n" + out += "----------------------------------" + + rospy.loginfo(out) + + return True + + def example_get_extrinsic_parameters(self): + # Call the service + try: + res = self.get_extrinsic_parameters() + except rospy.ServiceException: + rospy.logerr("Failed to call GetExtrinsicParameters") + return False + else: + # Print the result + # The message description can be seen at msg/generated/vision_config/ExtrinsicParameters.msg + extrinsic_parameters = res.output + out = "\n----------------------------------\n" + out += "Extrinsic parameters are :\n" + out += "Rotation parameters matrix is : " + "\n" + out += "| " + str(extrinsic_parameters.rotation.row1.column1) + " ; " + str(extrinsic_parameters.rotation.row1.column2) + " ; " + str(extrinsic_parameters.rotation.row1.column3) + " |" + "\n" + out += "| " + str(extrinsic_parameters.rotation.row2.column1) + " ; " + str(extrinsic_parameters.rotation.row2.column2) + " ; " + str(extrinsic_parameters.rotation.row2.column3) + " |" + "\n" + out += "| " + str(extrinsic_parameters.rotation.row3.column1) + " ; " + str(extrinsic_parameters.rotation.row3.column2) + " ; " + str(extrinsic_parameters.rotation.row3.column3) + " |" + "\n" + + out += "Translation parameters are : " + out += "[ x = " + str(extrinsic_parameters.translation.t_x) + out += " ; y = " + str(extrinsic_parameters.translation.t_y) + out += " ; z = " + str(extrinsic_parameters.translation.t_z) + " ]" + out += "\n" + "---------------------------------" + "\n" + + rospy.loginfo(out) + return True + + def example_get_sensor_settings(self): + # Call the service + req = GetSensorSettingsRequest() + req.input.sensor = Sensor.SENSOR_COLOR + try: + res = self.get_sensor_settings(req) + except rospy.ServiceException: + rospy.logerr("Failed to call GetSensorSettings") + return False + else: + # Print the result + sensor_settings = res.output + out = "\n----------------------------------\n" + out += "Get sensor settings : " "\n" + out += "Bit rate : " + self.bitrate_enum_to_string(sensor_settings.bit_rate) + "\n" + out += "Frame rate : " + self.framerate_enum_to_string(sensor_settings.frame_rate) + "\n" + out += "Resolution : " + self.resolution_enum_to_string(sensor_settings.resolution) + "\n" + out += "---------------------------------" + + rospy.loginfo(out) + + return True + + def example_change_the_resolution(self): + rospy.loginfo("Changing the resolution...") + req = SetSensorSettingsRequest() + # Set the resolution to be 640 x 480 on the color sensor + # You have to specify all parameters else the call will return an INVALID_PARAM error + req.input.sensor = Sensor.SENSOR_COLOR + req.input.resolution = Resolution.RESOLUTION_1280x720 + req.input.bit_rate = BitRate.BITRATE_10_MBPS + req.input.frame_rate = FrameRate.FRAMERATE_30_FPS + try: + self.set_sensor_settings(req) + except rospy.ServiceException: + rospy.logerr("Failed to call SetSensorSettings and change the resolution") + return False + else: + rospy.loginfo("Resolution changed successfully") + return True + + def example_get_sensor_option_value(self): + req = GetOptionValueRequest() + + # The only supported options for now are: + # For Color sensor : + # OPTION_BRIGHTNESS, OPTION_CONTRAST, OPTION_SATURATION + # For Depth sensor : + # OPTION_EXPOSURE, OPTION_GAIN, OPTION_ENABLE_AUTO_EXPOSURE, OPTION_VISUAL_PRESET, OPTION_FRAMES_QUEUE_SIZE, + # OPTION_ERROR_POLLING_ENABLE, OPTION_OUTPUT_TRIGGER_ENABLED, OPTION_DEPTH_UNITS, + # OPTION_STEREO_BASELINE (read-only) + # Trying to call an unsupported option in this service (or in the SetOptionValue service) will generate an error + + # Get the actual value the color sensor's contrast + req.input.sensor = Sensor.SENSOR_COLOR + req.input.option = Option.OPTION_CONTRAST + + try: + res = self.get_option_value(req) + except rospy.ServiceException: + rospy.logerr("Failed to call GetOptionValue") + return False + else: + option_value = res.output + out = "\n---------------------------------\n" + out += "Get Option value :\n" + out += "Option value is : \n" + out += "For sensor : " + self.sensor_type_enum_to_string(option_value.sensor) + "\n" + # You can see the Option enum at msg/generated/vision_config/Option.msg + out += "For option : " + str(option_value.option) + "\n" + out += "The value is : " + str(option_value.value) + "\n" + out += "---------------------------------\n" + + rospy.loginfo(out) + + return True + + def main(self): + + # For testing purposes + success = self.is_init_success + try: + rospy.delete_param("/kortex_examples_test_results/vision_configuration_python") + except: + pass + + if success: + #------------------------------------------------------------- + # Get the intrinsic parameters for a given sensor + success &= self.example_get_intrinsic_parameters() + + #------------------------------------------------------------- + # Get the extrinsic parameters for a given sensor + success &= self.example_get_extrinsic_parameters() + + #------------------------------------------------------------- + # Get the sensor settings for a given sensor + success &= self.example_get_sensor_settings() + + #------------------------------------------------------------- + # Set the extrinsic parameters for a given sensor + success &= self.example_change_the_resolution() + + #------------------------------------------------------------- + # Get an option value + success &= self.example_get_sensor_option_value() + + # For testing purposes + rospy.set_param("/kortex_examples_test_results/vision_configuration_python", success) + + if not success: + rospy.logerr("The example encountered an error.") + +if __name__ == "__main__": + ex = ExampleVisionConfiguration() + ex.main() diff --git a/ros_kortex/kortex_gazebo/CMakeLists.txt b/ros_kortex/kortex_gazebo/CMakeLists.txt new file mode 100644 index 0000000..0de0aba --- /dev/null +++ b/ros_kortex/kortex_gazebo/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.8.3) + +project(kortex_gazebo) + +# This is added to remove policy CMP0054 warning (see https://stackoverflow.com/questions/45900159/how-to-use-variables-and-avoid-cmp0054-policy-violations) +cmake_policy(SET CMP0054 NEW) + +find_package(catkin REQUIRED) + +find_package(gazebo) + +catkin_package() + +find_package(roslaunch) + +foreach(dir config launch meshes urdf) + install(DIRECTORY ${dir}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) +endforeach(dir) + +# Gazebo is compiled with Protobuf 2.6.1 and Kortex with Protobuf 3.5.1 +# The 2.6.1 includes are prepended to the include_directories so the Gazebo plugins we compile here build +include_directories(BEFORE ./include/) +include_directories(${GAZEBO_INCLUDE_DIRS}) +link_directories(${GAZEBO_LIBRARY_DIRS}) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") + +# To add your Gazebo plugin to this package, put your source file under src and uncomment/modify those lines +# add_library(my_gazebo_plugin SHARED src/my_gazebo_plugin.cpp) +# target_link_libraries(my_gazebo_plugin ${GAZEBO_LIBRARIES}) diff --git a/ros_kortex/kortex_gazebo/launch/spawn_kortex_robot.launch b/ros_kortex/kortex_gazebo/launch/spawn_kortex_robot.launch new file mode 100644 index 0000000..aa911dd --- /dev/null +++ b/ros_kortex/kortex_gazebo/launch/spawn_kortex_robot.launch @@ -0,0 +1,170 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_gazebo/launch/start_gazebo.launch b/ros_kortex/kortex_gazebo/launch/start_gazebo.launch new file mode 100644 index 0000000..a69e0d2 --- /dev/null +++ b/ros_kortex/kortex_gazebo/launch/start_gazebo.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ros_kortex/kortex_gazebo/media/materials/scripts/kortex.material b/ros_kortex/kortex_gazebo/media/materials/scripts/kortex.material new file mode 100644 index 0000000..2a83a91 --- /dev/null +++ b/ros_kortex/kortex_gazebo/media/materials/scripts/kortex.material @@ -0,0 +1,23 @@ +material Kortex/Gray +{ + technique + { + pass ambient + { + ambient 0.803 0.824 0.820 + diffuse 0.803 0.824 0.820 + } + } +} + +material Kortex/Blue +{ + technique + { + pass ambient + { + ambient 0 0.055 0.525 + diffuse 0 0.055 0.525 + } + } +} \ No newline at end of file diff --git a/ros_kortex/kortex_gazebo/package.xml b/ros_kortex/kortex_gazebo/package.xml new file mode 100644 index 0000000..850ac4d --- /dev/null +++ b/ros_kortex/kortex_gazebo/package.xml @@ -0,0 +1,30 @@ + + kortex_gazebo + 2.2.2 + +

Gazebo simulation package for Kortex robots

+

This package contains launch files to spawn the Kortex robot in Gazebo and visualize it in RViz, as well as configuration files.

+
+ Alexandre Vannobel + + BSD + catkin + roslaunch + kortex_driver + robot_state_publisher + rviz + joint_state_publisher + gazebo + xacro + gazebo_ros + gazebo_ros_control + moveit_commander + moveit_ros_control_interface + moveit_msgs + geometry_msgs + std_srvs + + + + +
diff --git a/ros_kortex/kortex_gazebo/readme.md b/ros_kortex/kortex_gazebo/readme.md new file mode 100644 index 0000000..ca3c339 --- /dev/null +++ b/ros_kortex/kortex_gazebo/readme.md @@ -0,0 +1,98 @@ + + +# Kortex Gazebo + +## Overview +This package contains files to simulate the Kinova Gen3 and Gen3 lite robots in Gazebo. + +### License + +The source code is released under a [BSD 3-Clause license](../LICENSE). + +**Author: Kinova inc.
+Affiliation: [Kinova inc.](https://www.kinovarobotics.com/)
+Maintainer: Kinova inc. support@kinovarobotics.com** + +This package has been tested under ROS Kinetic, Gazebo 7 and Ubuntu 16.04 and under ROS Melodic, Gazebo 9 and Ubuntu 18.04. + +## A word on stability of the models + +The arms's controllers are simulated with the `gazebo_ros_control` package, which provides PID effort controllers for every joint. It is not an exact simulation of the real arms's behaviour. The simulated arms are stable in most of their workspace, although we have seen the Gen3 be a bit less stable in a very low inertia position (vertical). The gains are set in .yaml files in the `kortex_control` package, so they can be modified by end users. + +Other disclaimers : + - The simulation has not been tested with simulated payload. + - No characterization was done to compare and quantify the performance of the simulated controllers and the real arm's controllers. The simulation only offers a **visually comparable experience** to the real arms. + - Very rarely, the base (fixed to the world frame) seems to lose its fixation and the arm goes unstable. We are currently looking for the root cause of this behavior, but we found that clicking **Edit ---> Reset Model Poses** (Shift + Ctrl + R) in Gazebo is a workaround. + +## Usage + +The [spawn_kortex_robot.launch file](launch/spawn_kortex_robot.launch) launches the arm simulation in [Gazebo](http://gazebosim.org), with [ros_control](http://wiki.ros.org/ros_control) controllers and [MoveIt!](https://moveit.ros.org/). +The launch can be parametrized with arguments : + +**Arguments**: +- **start_gazebo** : If this argument is false, Gazebo will not be launched within this launched file. It is useful if you already launched Gazebo yourself and just want to spawn the robot. The default value is **true** (Gazebo will be started). +- **gazebo_gui** : If this argument is false, only the Gazebo Server will be launched. The default value is **true**. +- **start_rviz** : If this argument is true, RViz will be launched. The default value is **true**. +- **x0** : The default X-axis position of the robot in Gazebo. The default value is **0.0**. +- **y0** : The default Y-axis position of the robot in Gazebo. The default value is **0.0**. +- **z0** : The default Z-axis position of the robot in Gazebo. The default value is **0.0**. +- **arm** : Name of your robot arm model. See the `kortex_description/arms` folder to see the available robot models. The default value is **gen3**. +- **gripper** : Name of your robot arm's tool / gripper. See the `kortex_description/grippers` folder to see the available end effector models (or to add your own). The default value is **""**. For Gen3, you can also put **robotiq_2f_85**. For Gen3 lite, you need to put **gen3_lite_2f**. +- **robot_name** : This is the namespace of the arm that is going to be spawned. It defaults to **my_$(arg arm)** (so my_gen3 for arm="gen3"). +- **use_trajectory_controller** : If this argument is false, one `JointPositionController` per joint will be launched and the arm will offer a basic ROS Control interface to control every joint individually with topics. If this argument is true, a MoveIt! node will be started for the arm and the arm will offer a `FollowJointTrajectory` interface to control the arm (via a `JointTrajectoryController`). The default value is **true**. +- **use_sim_time** : If this value is true, Gazebo will use simulated time instead of system clock. The default value is **true**. +- **debug** : If this value is true, Gazebo will be launched in debug mode. This option is useful for debugging Gazebo-related issues that won't show in the terminal. The default value is **false**. +- **paused** : If this value is true, Gazebo will be started paused. The default value is **$(arg use_trajectory_controller)** because, when MoveIt! is enabled, Gazebo needs to be started paused to let the controllers initialize. + +To launch it with default arguments, run the following command in a terminal : + +`roslaunch kortex_gazebo spawn_kortex_robot.launch` + +To launch it with optional arguments, specify the argument name, then ":=", then the value you want. For example, : + +`roslaunch kortex_gazebo spawn_kortex_robot.launch start_rviz:=false x0:=1.0 y0:=2.55 use_trajectory_controller:=false` + +You can also have a look at the [roslaunch documentation](http://wiki.ros.org/roslaunch/Commandline%20Tools) for more details. + +## Gazebo + +Gazebo loads an empty world an first, then the `spawn_model` node from the [gazebo_ros package](http://wiki.ros.org/gazebo_ros) is used to load the `robot_description` (taken from the Parameter Server) and spawn the robot in the simulator. + +## Controllers + +The simulated arm is controlled with a `effort_controllers/JointTrajectoryController` from [ros_controllers](http://wiki.ros.org/ros_controllers). +This controller offers a [FollowJointTrajectory](http://wiki.ros.org/joint_trajectory_controller) interface to control the simulated arm, which is configured with [MoveIt!](http://docs.ros.org/kinetic/api/moveit_tutorials/html/index.html) so the trajectories outputed by the `move_group` node are sent to the robot in Gazebo and executed. +The RViz Motion Planning plugin offers simple motion planning support for the simulated robot. See the [kortex_move_it_config documentation](../kortex_move_it_config/readme.md) for more details. + +There are also individual JointPositionController's for every joint, stopped by default. These are used by the kortex_arm_driver node to do velocity control. + +See the [kortex_driver package documentation](../kortex_driver/readme.md) for more details on how to use the simulated arm. + +## Initialization script + +The package also uses a [Python script](./scripts/home_robot.py) to home the robot after the robot has been spawned. +Gazebo is **launched with paused physics**. Otherwise, the arm would fall to the ground because the controllers are not fully loaded when the robot is spawned in the simulator. +When everything is well loaded, the script unpauses Gazebo's physics and executes the robot's Home action. + +## Plugins + +To properly simulate the grippers in Gazebo, we use two Gazebo Plugins. + +### Mimic joint plugin + +Gazebo doesn't offer support for the URDF **mimic** tag. +By loading one instance of [this plugin](../third_party/roboticsgroup_gazebo_plugins/README.md) per mimic joint, we are able to simulate those joints properly. The plugin parameters are specified with the [transmission elements for the Robotiq gripper](../kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_transmission_macro.xacro) and the [transmission elements for the Gen3 lite gripper](../kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_transmission_macro.xacro). + +### Gazebo grasp plugin + +Gazebo doesn't support grasping very well. By loading [this plugin](../third_party/gazebo-pkgs/README.md), we make sure objects grasped by the gripper will not fall. The plugin parameters are specified in with the [transmission elements for the Robotiq gripper](../kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_transmission_macro.xacro) and the [transmission elements for the Gen3 lite gripper](../kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_transmission_macro.xacro). diff --git a/ros_kortex/kortex_gazebo/scripts/home_robot.py b/ros_kortex/kortex_gazebo/scripts/home_robot.py new file mode 100755 index 0000000..26ef88f --- /dev/null +++ b/ros_kortex/kortex_gazebo/scripts/home_robot.py @@ -0,0 +1,111 @@ +#!/usr/bin/env python + +import sys +import time +import rospy +from std_srvs.srv import Empty +from kortex_driver.msg import ActionNotification, ActionEvent +from kortex_driver.srv import ReadAction, ReadActionRequest, ExecuteAction, ExecuteActionRequest + +class ExampleInitializeGazeboRobot(object): + """Unpause Gazebo and home robot""" + + def __init__(self): + # Initialize the node + self.HOME_ACTION_IDENTIFIER = 2 + self.last_action_notif_type = None + + try: + self.robot_name = rospy.get_param('~robot_name') + self.action_topic_sub = rospy.Subscriber("/" + self.robot_name + "/action_topic", ActionNotification, self.cb_action_topic) + + # Wait for the driver to be initialised + while not rospy.has_param("/" + self.robot_name + "/is_initialized"): + time.sleep(0.1) + + # Init the services + read_action_full_name = '/' + self.robot_name + '/base/read_action' + rospy.wait_for_service(read_action_full_name) + self.read_action = rospy.ServiceProxy(read_action_full_name, ReadAction) + + execute_action_full_name = '/' + self.robot_name + '/base/execute_action' + rospy.wait_for_service(execute_action_full_name) + self.execute_action = rospy.ServiceProxy(execute_action_full_name, ExecuteAction) + except rospy.ROSException as e: + self.is_init_success = False + else: + self.is_init_success = True + + def cb_action_topic(self, notif): + self.last_action_notif_type = notif.action_event + + def wait_for_action_end_or_abort(self): + while not rospy.is_shutdown(): + if (self.last_action_notif_type == ActionEvent.ACTION_END): + rospy.loginfo("Received ACTION_END notification") + return True + elif (self.last_action_notif_type == ActionEvent.ACTION_ABORT): + rospy.loginfo("Received ACTION_ABORT notification") + return False + else: + time.sleep(0.01) + + def home_the_robot(self): + # The Home Action is used to home the robot. It cannot be deleted and is always ID #2: + self.last_action_notif_type = None + req = ReadActionRequest() + req.input.identifier = self.HOME_ACTION_IDENTIFIER + + try: + res = self.read_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ReadAction") + return False + # Execute the HOME action if we could read it + else: + # What we just read is the input of the ExecuteAction service + req = ExecuteActionRequest() + req.input = res.output + rospy.loginfo("Sending the robot home...") + try: + self.execute_action(req) + except rospy.ServiceException: + rospy.logerr("Failed to call ExecuteAction") + return False + else: + return self.wait_for_action_end_or_abort() + +def main(): + try: + # For testing purposes + try: + rospy.delete_param("is_initialized") + except: + pass + + # Unpause the physics + rospy.loginfo("Unpausing Gazebo...") + rospy.wait_for_service('/gazebo/unpause_physics') + unpause_gazebo = rospy.ServiceProxy('/gazebo/unpause_physics', Empty) + resp = unpause_gazebo() + rospy.loginfo("Unpaused Gazebo.") + + example = ExampleInitializeGazeboRobot() + success = example.is_init_success + if success: + success &= example.home_the_robot() + + except Exception as e: + print (e) + success = False + + # For testing purposes + rospy.set_param("is_initialized", success) + if not success: + rospy.logerr("The Gazebo initialization encountered an error.") + else: + rospy.loginfo("The Gazebo initialization executed without fail.") + +if __name__ == '__main__': + rospy.init_node('init_robot') + main() diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/.setup_assistant b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/.setup_assistant new file mode 100644 index 0000000..8619322 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: kortex_description + relative_path: robots/gen3_lite_gen3_lite_2f.xacro + xacro_args: "" + SRDF: + relative_path: config/gen3_lite_gen3_lite_2f.srdf + CONFIG: + author_name: Alexandre Vannobel + author_email: avannobel@kinova.ca + generated_timestamp: 1564078352 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/CMakeLists.txt b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/CMakeLists.txt new file mode 100644 index 0000000..3bef278 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gen3_lite_gen3_lite_2f_move_it_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/chomp_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/chomp_planning.yaml new file mode 100644 index 0000000..75258e5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.01 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearence: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: true +max_recovery_attempts: 5 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/fake_controllers.yaml new file mode 100644 index 0000000..60730a0 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/fake_controllers.yaml @@ -0,0 +1,12 @@ +controller_list: + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - name: $(arg prefix)fake_gripper_controller + joints: + - $(arg prefix)right_finger_bottom_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/gen3_lite_gen3_lite_2f.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/gen3_lite_gen3_lite_2f.srdf.xacro new file mode 100644 index 0000000..bd5ef23 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/gen3_lite_gen3_lite_2f.srdf.xacro @@ -0,0 +1,108 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/joint_limits.yaml new file mode 100644 index 0000000..66e05b1 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/joint_limits.yaml @@ -0,0 +1,39 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.99 + has_acceleration_limits: true + max_acceleration: 0.35 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.99 + has_acceleration_limits: true + max_acceleration: 0.17 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.99 + has_acceleration_limits: true + max_acceleration: 0.14 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.99 + has_acceleration_limits: true + max_acceleration: 0.35 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.99 + has_acceleration_limits: true + max_acceleration: 3.5 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.55 + has_acceleration_limits: true + max_acceleration: 3.5 + right_finger_bottom_joint: + has_velocity_limits: true + max_velocity: 1000 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/kinematics.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/kinematics.yaml new file mode 100644 index 0000000..3b90b6d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/kinematics.yaml @@ -0,0 +1,5 @@ +arm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/ompl_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/ompl_planning.yaml new file mode 100644 index 0000000..2ee2dbe --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/ompl_planning.yaml @@ -0,0 +1,176 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +arm: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints($(arg prefix)joint_1,$(arg prefix)joint_2) + longest_valid_segment_fraction: 0.005 +gripper: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/ros_controllers.yaml new file mode 100644 index 0000000..2934c6d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/ros_controllers.yaml @@ -0,0 +1,22 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_lite_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + + - name: "$(arg prefix)gen3_lite_2f_gripper_controller" + action_ns: gripper_cmd + default: True + type: GripperCommand + joints: + - $(arg prefix)right_finger_bottom_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/sensors_3d.yaml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/sensors_3d.yaml new file mode 100644 index 0000000..d2955dc --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/config/sensors_3d.yaml @@ -0,0 +1,3 @@ +# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it +sensors: + - {} \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/chomp_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..d3682c0 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/default_warehouse_db.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/default_warehouse_db.launch new file mode 100644 index 0000000..f2e0e57 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/demo.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/demo.launch new file mode 100644 index 0000000..0a411e3 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/demo.launch @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/fake_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..3b0aed0 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/gen3_lite_gen3_lite_2f_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/gen3_lite_gen3_lite_2f_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..afb7340 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/gen3_lite_gen3_lite_2f_moveit_controller_manager.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/gen3_lite_gen3_lite_2f_moveit_sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/gen3_lite_gen3_lite_2f_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/gen3_lite_gen3_lite_2f_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/joystick_control.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/move_group.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/move_group.launch new file mode 100644 index 0000000..f26a35d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/move_group.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/moveit.rviz b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/moveit.rviz new file mode 100644 index 0000000..0877e1e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/moveit.rviz @@ -0,0 +1,689 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 664 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: left_arm + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: /base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.9965 + Focal Point: + X: 0.113567 + Y: 0.10592 + Z: 2.23518e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.509797 + Target Frame: /base_link + Value: XYOrbit (rviz) + Yaw: 5.65995 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 459 + Y: -243 diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/moveit_rviz.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/moveit_rviz.launch new file mode 100644 index 0000000..5cc4eff --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/ompl_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..b8cd5b6 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/planning_context.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/planning_context.launch new file mode 100644 index 0000000..4ebcf35 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/planning_context.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..6f17242 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/ros_controllers.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/ros_controllers.launch new file mode 100644 index 0000000..a75f705 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/ros_controllers.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/run_benchmark_ompl.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..0d4f158 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..c7348ac --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/setup_assistant.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/setup_assistant.launch new file mode 100644 index 0000000..f20f3eb --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/trajectory_execution.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..7a09c04 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/warehouse.launch b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/warehouse.launch new file mode 100644 index 0000000..50e16ef --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/warehouse_settings.launch.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml new file mode 100644 index 0000000..8e729e4 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_lite_gen3_lite_2f_move_it_config/package.xml @@ -0,0 +1,34 @@ + + + gen3_lite_gen3_lite_2f_move_it_config + 2.2.2 + + An automatically generated package with all the configuration and launch files for using the gen3_lite_gen3_lite_2f with the MoveIt! Motion Planning Framework + + Alexandre Vannobel + Alexandre Vannobel + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + joint_state_publisher + robot_state_publisher + xacro + + + kortex_description + kortex_description + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/.setup_assistant b/ros_kortex/kortex_move_it_config/gen3_move_it_config/.setup_assistant new file mode 100644 index 0000000..94c2fcb --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: kortex_description + relative_path: robots/gen3.xacro + xacro_args: arm:=gen3 + SRDF: + relative_path: config/gen3.srdf + CONFIG: + author_name: Alexandre Vannobel + author_email: avannobel@kinova.ca + generated_timestamp: 1551811297 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/CMakeLists.txt b/ros_kortex/kortex_move_it_config/gen3_move_it_config/CMakeLists.txt new file mode 100644 index 0000000..6fb6fa4 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gen3_move_it_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/default_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/default_joint_limits.yaml new file mode 100644 index 0000000..7a51e2c --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/default_joint_limits.yaml @@ -0,0 +1,34 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/fake_controllers.yaml new file mode 100644 index 0000000..84de5e8 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/fake_controllers.yaml @@ -0,0 +1,9 @@ +controller_list: + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/gen3.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/gen3.srdf.xacro new file mode 100644 index 0000000..1257563 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/gen3.srdf.xacro @@ -0,0 +1,63 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/hard_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/hard_joint_limits.yaml new file mode 100644 index 0000000..f43b69a --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/hard_joint_limits.yaml @@ -0,0 +1,34 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/ros_controllers.yaml new file mode 100644 index 0000000..221f960 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/6dof/ros_controllers.yaml @@ -0,0 +1,15 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/default_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/default_joint_limits.yaml new file mode 100644 index 0000000..056e61f --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/default_joint_limits.yaml @@ -0,0 +1,39 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_7: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/fake_controllers.yaml new file mode 100644 index 0000000..9bf3b0d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/fake_controllers.yaml @@ -0,0 +1,10 @@ +controller_list: + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/gen3.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/gen3.srdf.xacro new file mode 100644 index 0000000..beb8c85 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/gen3.srdf.xacro @@ -0,0 +1,75 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/hard_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/hard_joint_limits.yaml new file mode 100644 index 0000000..fdd996b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/hard_joint_limits.yaml @@ -0,0 +1,39 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_7: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/ros_controllers.yaml new file mode 100644 index 0000000..cfaa620 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/7dof/ros_controllers.yaml @@ -0,0 +1,16 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/chomp_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/chomp_planning.yaml new file mode 100644 index 0000000..75258e5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.01 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearence: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: true +max_recovery_attempts: 5 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/kinematics.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/kinematics.yaml new file mode 100644 index 0000000..3b90b6d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/kinematics.yaml @@ -0,0 +1,5 @@ +arm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/ompl_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/ompl_planning.yaml new file mode 100644 index 0000000..1667cab --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/ompl_planning.yaml @@ -0,0 +1,150 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +arm: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints($(arg prefix)joint_1,$(arg prefix)joint_2) + longest_valid_segment_fraction: 0.005 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/sensors_3d.yaml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/sensors_3d.yaml new file mode 100644 index 0000000..d2955dc --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/config/sensors_3d.yaml @@ -0,0 +1,3 @@ +# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it +sensors: + - {} \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/chomp_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..c418533 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/default_warehouse_db.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/default_warehouse_db.launch new file mode 100644 index 0000000..0c1b817 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/demo.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/demo.launch new file mode 100644 index 0000000..a219d6f --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/demo.launch @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/fake_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..482742e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/gen3_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/gen3_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..5b91ac1 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/gen3_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/gen3_moveit_sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/gen3_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/gen3_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/joystick_control.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/move_group.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/move_group.launch new file mode 100644 index 0000000..56ffd49 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/move_group.launch @@ -0,0 +1,91 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/moveit.rviz b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/moveit.rviz new file mode 100644 index 0000000..0877e1e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/moveit.rviz @@ -0,0 +1,689 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 664 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: left_arm + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: /base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.9965 + Focal Point: + X: 0.113567 + Y: 0.10592 + Z: 2.23518e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.509797 + Target Frame: /base_link + Value: XYOrbit (rviz) + Yaw: 5.65995 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 459 + Y: -243 diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/moveit_rviz.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/moveit_rviz.launch new file mode 100644 index 0000000..7f1a2a1 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/ompl_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..bfe3d6c --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/planning_context.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/planning_context.launch new file mode 100644 index 0000000..e33d8e8 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/planning_context.launch @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..607842b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/run_benchmark_ompl.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..16cb218 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..c1f110c --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/setup_assistant.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/setup_assistant.launch new file mode 100644 index 0000000..42f9a76 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/trajectory_execution.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..ebb523b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/warehouse.launch b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/warehouse.launch new file mode 100644 index 0000000..67c5103 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/warehouse_settings.launch.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_move_it_config/package.xml b/ros_kortex/kortex_move_it_config/gen3_move_it_config/package.xml new file mode 100644 index 0000000..f8040e4 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_move_it_config/package.xml @@ -0,0 +1,35 @@ + + + gen3_move_it_config + 2.2.2 + + An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt! Motion Planning Framework + + Alexandre Vannobel + + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + joint_state_publisher + robot_state_publisher + xacro + + + kortex_description + kortex_description + industrial_trajectory_filters + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/.setup_assistant b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/.setup_assistant new file mode 100644 index 0000000..05b9cb9 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: kortex_description + relative_path: robots/gen3_robotiq_2f_85.xacro + xacro_args: arm:=gen3 gripper:=robotiq_2f_85 + SRDF: + relative_path: config/gen3_robotiq_2f_85.srdf + CONFIG: + author_name: Alexandre Vannobel + author_email: avannobel@kinova.ca + generated_timestamp: 1551813671 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/CMakeLists.txt b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/CMakeLists.txt new file mode 100644 index 0000000..82f2429 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gen3_robotiq_2f_140_move_it_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/default_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/default_joint_limits.yaml new file mode 100644 index 0000000..83fdb6b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/default_joint_limits.yaml @@ -0,0 +1,64 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/fake_controllers.yaml new file mode 100644 index 0000000..b9ec393 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/fake_controllers.yaml @@ -0,0 +1,11 @@ + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - name: $(arg prefix)fake_gripper_controller + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/gen3_robotiq_2f_140.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/gen3_robotiq_2f_140.srdf.xacro new file mode 100644 index 0000000..8521c61 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/gen3_robotiq_2f_140.srdf.xacro @@ -0,0 +1,198 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/hard_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/hard_joint_limits.yaml new file mode 100644 index 0000000..18bcded --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/hard_joint_limits.yaml @@ -0,0 +1,64 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/ros_controllers.yaml new file mode 100644 index 0000000..f5d5e61 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/6dof/ros_controllers.yaml @@ -0,0 +1,22 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + + - name: "$(arg prefix)robotiq_2f_140_gripper_controller" + action_ns: gripper_cmd + default: True + type: GripperCommand + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/default_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/default_joint_limits.yaml new file mode 100644 index 0000000..b172331 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/default_joint_limits.yaml @@ -0,0 +1,69 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_7: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/fake_controllers.yaml new file mode 100644 index 0000000..57fb469 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/fake_controllers.yaml @@ -0,0 +1,13 @@ +controller_list: + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 + - name: $(arg prefix)fake_gripper_controller + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/gen3_robotiq_2f_140.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/gen3_robotiq_2f_140.srdf.xacro new file mode 100644 index 0000000..cd5bb0e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/gen3_robotiq_2f_140.srdf.xacro @@ -0,0 +1,218 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/hard_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/hard_joint_limits.yaml new file mode 100644 index 0000000..7c29158 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/hard_joint_limits.yaml @@ -0,0 +1,69 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_7: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/ros_controllers.yaml new file mode 100644 index 0000000..f1b8067 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/7dof/ros_controllers.yaml @@ -0,0 +1,23 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 + + - name: "$(arg prefix)robotiq_2f_140_gripper_controller" + action_ns: gripper_cmd + default: True + type: GripperCommand + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/chomp_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/chomp_planning.yaml new file mode 100644 index 0000000..75258e5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.01 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearence: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: true +max_recovery_attempts: 5 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/kinematics.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/kinematics.yaml new file mode 100644 index 0000000..46a2386 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +arm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/ompl_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/ompl_planning.yaml new file mode 100644 index 0000000..2ee2dbe --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/ompl_planning.yaml @@ -0,0 +1,176 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +arm: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints($(arg prefix)joint_1,$(arg prefix)joint_2) + longest_valid_segment_fraction: 0.005 +gripper: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/sensors_3d.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/sensors_3d.yaml new file mode 100644 index 0000000..d2955dc --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/config/sensors_3d.yaml @@ -0,0 +1,3 @@ +# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it +sensors: + - {} \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/chomp_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..0d872ab --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/default_warehouse_db.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/default_warehouse_db.launch new file mode 100644 index 0000000..182c096 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/demo.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/demo.launch new file mode 100644 index 0000000..340aed4 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/demo.launch @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/fake_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..6ff1ed9 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/gen3_robotiq_2f_140_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/gen3_robotiq_2f_140_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..6007253 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/gen3_robotiq_2f_140_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/gen3_robotiq_2f_140_moveit_sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/gen3_robotiq_2f_140_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/gen3_robotiq_2f_140_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/joystick_control.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/move_group.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/move_group.launch new file mode 100644 index 0000000..765335b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/move_group.launch @@ -0,0 +1,91 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/moveit.rviz b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/moveit.rviz new file mode 100644 index 0000000..0877e1e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/moveit.rviz @@ -0,0 +1,689 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 664 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: left_arm + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: /base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.9965 + Focal Point: + X: 0.113567 + Y: 0.10592 + Z: 2.23518e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.509797 + Target Frame: /base_link + Value: XYOrbit (rviz) + Yaw: 5.65995 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 459 + Y: -243 diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/moveit_rviz.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/moveit_rviz.launch new file mode 100644 index 0000000..794f7e5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/ompl_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..99ec2a5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/planning_context.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/planning_context.launch new file mode 100644 index 0000000..803e5ae --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/planning_context.launch @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..4e99c9c --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/run_benchmark_ompl.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..cf41639 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..a19ae58 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/setup_assistant.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/setup_assistant.launch new file mode 100644 index 0000000..b74e781 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/trajectory_execution.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..3eb4a38 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/warehouse.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/warehouse.launch new file mode 100644 index 0000000..9bb4298 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/warehouse_settings.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml new file mode 100644 index 0000000..5028098 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_140_move_it_config/package.xml @@ -0,0 +1,35 @@ + + + gen3_robotiq_2f_140_move_it_config + 2.2.2 + + An automatically generated package with all the configuration and launch files for using the gen3_robotiq_2f_140 with the MoveIt! Motion Planning Framework + + Alexandre Vannobel + + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + joint_state_publisher + robot_state_publisher + xacro + industrial_trajectory_filters + + + kortex_description + kortex_description + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/.setup_assistant b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/.setup_assistant new file mode 100644 index 0000000..05b9cb9 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: kortex_description + relative_path: robots/gen3_robotiq_2f_85.xacro + xacro_args: arm:=gen3 gripper:=robotiq_2f_85 + SRDF: + relative_path: config/gen3_robotiq_2f_85.srdf + CONFIG: + author_name: Alexandre Vannobel + author_email: avannobel@kinova.ca + generated_timestamp: 1551813671 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/CMakeLists.txt b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/CMakeLists.txt new file mode 100644 index 0000000..78da7d1 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gen3_robotiq_2f_85_move_it_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/default_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/default_joint_limits.yaml new file mode 100644 index 0000000..83fdb6b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/default_joint_limits.yaml @@ -0,0 +1,64 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/fake_controllers.yaml new file mode 100644 index 0000000..b9ec393 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/fake_controllers.yaml @@ -0,0 +1,11 @@ + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - name: $(arg prefix)fake_gripper_controller + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/gen3_robotiq_2f_85.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/gen3_robotiq_2f_85.srdf.xacro new file mode 100644 index 0000000..0ff251e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/gen3_robotiq_2f_85.srdf.xacro @@ -0,0 +1,199 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/hard_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/hard_joint_limits.yaml new file mode 100644 index 0000000..18bcded --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/hard_joint_limits.yaml @@ -0,0 +1,64 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/ros_controllers.yaml new file mode 100644 index 0000000..f13b3e5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/6dof/ros_controllers.yaml @@ -0,0 +1,22 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + + - name: "$(arg prefix)robotiq_2f_85_gripper_controller" + action_ns: gripper_cmd + default: True + type: GripperCommand + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/default_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/default_joint_limits.yaml new file mode 100644 index 0000000..b172331 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/default_joint_limits.yaml @@ -0,0 +1,69 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)joint_7: + has_velocity_limits: true + max_velocity: 0.86 + has_acceleration_limits: true + max_acceleration: 0.3 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/fake_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/fake_controllers.yaml new file mode 100644 index 0000000..57fb469 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/fake_controllers.yaml @@ -0,0 +1,13 @@ +controller_list: + - name: $(arg prefix)fake_arm_controller + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 + - name: $(arg prefix)fake_gripper_controller + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/gen3_robotiq_2f_85.srdf.xacro b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/gen3_robotiq_2f_85.srdf.xacro new file mode 100644 index 0000000..0463d2d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/gen3_robotiq_2f_85.srdf.xacro @@ -0,0 +1,218 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/hard_joint_limits.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/hard_joint_limits.yaml new file mode 100644 index 0000000..7c29158 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/hard_joint_limits.yaml @@ -0,0 +1,69 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + $(arg prefix)joint_1: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_2: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_3: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_4: + has_velocity_limits: true + max_velocity: 1.37 + has_acceleration_limits: true + max_acceleration: 1.56 + $(arg prefix)joint_5: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_6: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)joint_7: + has_velocity_limits: true + max_velocity: 1.15 + has_acceleration_limits: true + max_acceleration: 3.0 + $(arg prefix)left_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_inner_finger_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)left_inner_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + $(arg prefix)right_outer_knuckle_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/ros_controllers.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/ros_controllers.yaml new file mode 100644 index 0000000..f401d72 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/7dof/ros_controllers.yaml @@ -0,0 +1,23 @@ +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: + - name: "$(arg prefix)gen3_joint_trajectory_controller" + action_ns: follow_joint_trajectory + default: True + type: FollowJointTrajectory + joints: + - $(arg prefix)joint_1 + - $(arg prefix)joint_2 + - $(arg prefix)joint_3 + - $(arg prefix)joint_4 + - $(arg prefix)joint_5 + - $(arg prefix)joint_6 + - $(arg prefix)joint_7 + + - name: "$(arg prefix)robotiq_2f_85_gripper_controller" + action_ns: gripper_cmd + default: True + type: GripperCommand + joints: + - $(arg prefix)finger_joint \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/chomp_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/chomp_planning.yaml new file mode 100644 index 0000000..75258e5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.01 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearence: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: true +max_recovery_attempts: 5 \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/kinematics.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/kinematics.yaml new file mode 100644 index 0000000..46a2386 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +arm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/ompl_planning.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/ompl_planning.yaml new file mode 100644 index 0000000..2ee2dbe --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/ompl_planning.yaml @@ -0,0 +1,176 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +arm: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints($(arg prefix)joint_1,$(arg prefix)joint_2) + longest_valid_segment_fraction: 0.005 +gripper: + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/sensors_3d.yaml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/sensors_3d.yaml new file mode 100644 index 0000000..d2955dc --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/config/sensors_3d.yaml @@ -0,0 +1,3 @@ +# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it +sensors: + - {} \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/chomp_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..1fd48ef --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/default_warehouse_db.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/default_warehouse_db.launch new file mode 100644 index 0000000..35770c5 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/demo.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/demo.launch new file mode 100644 index 0000000..6f4dcea --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/demo.launch @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/fake_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..d9a0984 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/gen3_robotiq_2f_85_moveit_controller_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/gen3_robotiq_2f_85_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..1d65402 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/gen3_robotiq_2f_85_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/gen3_robotiq_2f_85_moveit_sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/gen3_robotiq_2f_85_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/gen3_robotiq_2f_85_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/joystick_control.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/move_group.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/move_group.launch new file mode 100644 index 0000000..806b0a2 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/move_group.launch @@ -0,0 +1,91 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/moveit.rviz b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/moveit.rviz new file mode 100644 index 0000000..0877e1e --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/moveit.rviz @@ -0,0 +1,689 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 664 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: left_arm + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: /base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.9965 + Focal Point: + X: 0.113567 + Y: 0.10592 + Z: 2.23518e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.509797 + Target Frame: /base_link + Value: XYOrbit (rviz) + Yaw: 5.65995 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 459 + Y: -243 diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/moveit_rviz.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/moveit_rviz.launch new file mode 100644 index 0000000..d15601d --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/ompl_planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..5ef1a12 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/planning_context.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/planning_context.launch new file mode 100644 index 0000000..497da46 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/planning_context.launch @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/planning_pipeline.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..438586b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/run_benchmark_ompl.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..0ff9e83 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/sensor_manager.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..2e6a49f --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/setup_assistant.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/setup_assistant.launch new file mode 100644 index 0000000..ed669a6 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/trajectory_execution.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..55e216c --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/warehouse.launch b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/warehouse.launch new file mode 100644 index 0000000..f4d4f96 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/warehouse_settings.launch.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml new file mode 100644 index 0000000..1e21504 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/gen3_robotiq_2f_85_move_it_config/package.xml @@ -0,0 +1,35 @@ + + + gen3_robotiq_2f_85_move_it_config + 2.2.2 + + An automatically generated package with all the configuration and launch files for using the gen3_robotiq_2f_85 with the MoveIt! Motion Planning Framework + + Alexandre Vannobel + + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + joint_state_publisher + robot_state_publisher + xacro + industrial_trajectory_filters + + + kortex_description + kortex_description + + + diff --git a/ros_kortex/kortex_move_it_config/kortex_move_it_config/CMakeLists.txt b/ros_kortex/kortex_move_it_config/kortex_move_it_config/CMakeLists.txt new file mode 100644 index 0000000..5a74a9b --- /dev/null +++ b/ros_kortex/kortex_move_it_config/kortex_move_it_config/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(kortex_move_it_config) +find_package(catkin REQUIRED) +catkin_metapackage() \ No newline at end of file diff --git a/ros_kortex/kortex_move_it_config/kortex_move_it_config/package.xml b/ros_kortex/kortex_move_it_config/kortex_move_it_config/package.xml new file mode 100644 index 0000000..a9cbce9 --- /dev/null +++ b/ros_kortex/kortex_move_it_config/kortex_move_it_config/package.xml @@ -0,0 +1,37 @@ + + + kortex_move_it_config + 2.2.2 + + The metapackage for the automatically generated MoveIt configuration packages + + Alexandre Vannobel + + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + joint_state_publisher + robot_state_publisher + xacro + + + kortex_description + + + + + + + diff --git a/ros_kortex/kortex_move_it_config/readme.md b/ros_kortex/kortex_move_it_config/readme.md new file mode 100644 index 0000000..832f49c --- /dev/null +++ b/ros_kortex/kortex_move_it_config/readme.md @@ -0,0 +1,31 @@ + + +# Kortex MoveIt! Config + +## Overview +This folder contains all the auto-generated MoveIt! configuration ROS packages. These packages have been generated using the [MoveIt! Setup Assistant](http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/setup_assistant/setup_assistant_tutorial.html). + +## Naming + +The packages that don't use a gripper are named `ARM_move_it_config`, where "ARM" is the name of the arm you are using. +See the `kortex_description/arms` folder for a list of supported Kinova Kortex robots. + +The packages that use a gripper are named `ARM_GRIPPER_move_it_config`, where "ARM" is the name of the arm you are using and "GRIPPER" is the name of the gripper you are using. +See the `kortex_description/grippers` folder for a list of supported Kinova Kortex grippers. + +## Using MoveIt! with Kinova Kortex Robots + +Upon launching the main launch file of a `move_it_config` package, `move_group.launch` (normally launched from the real arm driver's launch file and the simulation launch file), the [C++](http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/move_group_interface/move_group_interface_tutorial.html) and [Python](http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/move_group_python_interface/move_group_python_interface_tutorial.html) interfaces for MoveIt will be enabled. +You will be able to use motion planning, configure the planning scene, send trajectories and send pose goals to the simulated robot from your own ROS nodes. + +You can take a look at our [MoveIt! Python example](../kortex_examples/python/move_it/example_move_it_trajectories.py) for a concrete example. diff --git a/ros_kortex/notebooks/Example.ipynb b/ros_kortex/notebooks/Example.ipynb deleted file mode 100644 index c5103ff..0000000 --- a/ros_kortex/notebooks/Example.ipynb +++ /dev/null @@ -1,190 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "using Pkg\n", - "Pkg.activate(joinpath(@__DIR__, \"..\"))\n", - "Pkg.instantiate()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "using Revise\n", - "using TORA" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "using MeshCat\n", - "using MeshCatMechanisms\n", - "using RigidBodyDynamics" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.greet()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "vis = Visualizer()\n", - "\n", - "setprop!(vis[\"/Cameras/default/rotated/\"], \"fov\", 40)\n", - "\n", - "# IJuliaCell(vis) # Show the viewer here (in the notebook)\n", - "open(vis) # Show the viewer in a separate tab" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "robot = TORA.create_robot_kuka_iiwa_14(vis)\n", - "problem = TORA.Problem(robot, 301, 1/150)\n", - "\n", - "# Constrain initial and final joint velocities to zero\n", - "TORA.fix_joint_velocities!(problem, robot, 1, zeros(robot.n_v))\n", - "TORA.fix_joint_velocities!(problem, robot, problem.num_knots, zeros(robot.n_v))\n", - "\n", - "# # Constrain the position of the end-effector\n", - "# TORA.constrain_ee_position!(problem, 1, [ 1.0, 0.0, 0.5])\n", - "# TORA.constrain_ee_position!(problem, 101, [ 0.0, 1.0, 0.5])\n", - "# TORA.constrain_ee_position!(problem, 201, [-1.0, 0.0, 0.5])\n", - "# TORA.constrain_ee_position!(problem, 301, [ 0.0, -1.0, 0.5])\n", - "\n", - "let\n", - " CubicTimeScaling(Tf::Number, t::Number) = 3(t / Tf)^2 - 2(t / Tf)^3\n", - " QuinticTimeScaling(Tf::Number, t::Number) = 10(t / Tf)^3 - 15(t / Tf)^4 + 6(t / Tf)^5\n", - "\n", - " for k = 1:2:problem.num_knots\n", - " θ = CubicTimeScaling(problem.num_knots - 1, k - 1) * 2π\n", - " pos = [0.5, 0.2 * cos(θ), 0.8 + 0.2 * sin(θ)]\n", - " # pos = [0.5, 0.3 * sin(θ) + 0.1 * sin(8 * θ), 0.8 + 0.3 * cos(θ) + 0.1 * cos(8 * θ)]\n", - " TORA.constrain_ee_position!(problem, k, pos)\n", - " end\n", - "end\n", - "\n", - "TORA.show_problem_info(problem)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "initial_q = [0, 0, 0, -π/2, 0, 0, 0]\n", - "\n", - "zero!(robot.state)\n", - "set_configuration!(robot.state, initial_q)\n", - "set_configuration!(robot.mvis, configuration(robot.state))\n", - "\n", - "initial_qs = repeat(initial_q, 1, problem.num_knots)\n", - "initial_vs = zeros(robot.n_v, problem.num_knots)\n", - "initial_τs = zeros(robot.n_τ, problem.num_knots)\n", - "\n", - "initial_guess = [initial_qs; initial_vs; initial_τs]\n", - "\n", - "# Flatten matrix and truncate torques of last knot\n", - "initial_guess = vec(initial_guess)[1:end - robot.n_τ];" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "use_inv_dyn = true\n", - "minimise_τ = false\n", - "\n", - "# Choose which solver you want to use:\n", - "solve = TORA.solve_with_ipopt # Uses Ipopt (https://github.com/coin-or/Ipopt)\n", - "# solve = TORA.solve_with_knitro # Uses KNITRO (https://www.artelys.com/solvers/knitro/)\n", - "\n", - "# Calling this will start the optimization.\n", - "cpu_time, x, solver_log = solve(problem, robot,\n", - " initial_guess=initial_guess,\n", - " use_inv_dyn=use_inv_dyn,\n", - " minimise_τ=minimise_τ)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.plot_log(solver_log)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "let\n", - " ee_positions = TORA.get_ee_path(problem, robot, x)\n", - " TORA.show_ee_path(vis, ee_positions)\n", - "\n", - " nₓ = robot.n_q + robot.n_v + robot.n_τ # dimension of each mesh point\n", - " ind_q = hcat([range(1 + (i * nₓ), length=robot.n_q) for i = (1:problem.num_knots) .- 1]...)\n", - " q_mat = x[ind_q]\n", - "\n", - " ts = range(0, length=problem.num_knots, step=problem.dt)\n", - " qs = [q_mat[:, i] for i = 1:size(q_mat, 2)]\n", - "\n", - " animation = Animation(robot.mvis, ts, qs)\n", - " setanimation!(robot.mvis, animation)\n", - "end" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.plot_results(problem, robot, x)" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Julia 1.5.2", - "language": "julia", - "name": "julia-1.5" - }, - "language_info": { - "file_extension": ".jl", - "mimetype": "application/julia", - "name": "julia", - "version": "1.5.2" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/ros_kortex/notebooks/Tutorial.ipynb b/ros_kortex/notebooks/Tutorial.ipynb deleted file mode 100644 index 595e2de..0000000 --- a/ros_kortex/notebooks/Tutorial.ipynb +++ /dev/null @@ -1,156 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "using Pkg\n", - "Pkg.activate(joinpath(@__DIR__, \"..\"))\n", - "Pkg.instantiate()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "using TORA\n", - "using MeshCat\n", - "using MeshCatMechanisms\n", - "using RigidBodyDynamics" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.greet()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "vis = Visualizer()\n", - "\n", - "# Change the camera's Field of View\n", - "setprop!(vis[\"/Cameras/default/rotated/\"], \"fov\", 40)\n", - "\n", - "# IJuliaCell(vis) # Show the viewer here (in the notebook)\n", - "open(vis) # Show the viewer in a separate tab" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "robot = TORA.create_robot_kuka_iiwa_14(vis)\n", - "problem = TORA.Problem(robot, 301, 1/150)\n", - "\n", - "# Constrain initial and final joint velocities to zero\n", - "TORA.fix_joint_velocities!(problem, robot, 1, zeros(robot.n_v))\n", - "TORA.fix_joint_velocities!(problem, robot, problem.num_knots, zeros(robot.n_v))\n", - "\n", - "let CubicTimeScaling(Tf::Number, t::Number) = 3(t / Tf)^2 - 2(t / Tf)^3\n", - " for k = 1:2:problem.num_knots # For every other knot\n", - " θ = CubicTimeScaling(problem.num_knots - 1, k - 1) * 2π\n", - " pos = [0.5, 0.2 * cos(θ), 0.8 + 0.2 * sin(θ)]\n", - " TORA.constrain_ee_position!(problem, k, pos)\n", - " end\n", - "end" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.show_problem_info(problem)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "initial_q = [0, 0, 0, -π/2, 0, 0, 0]\n", - "\n", - "zero!(robot.state)\n", - "set_configuration!(robot.state, initial_q)\n", - "set_configuration!(robot.mvis, configuration(robot.state))\n", - "\n", - "initial_qs = repeat(initial_q, 1, problem.num_knots)\n", - "initial_vs = zeros(robot.n_v, problem.num_knots)\n", - "initial_τs = zeros(robot.n_τ, problem.num_knots)\n", - "\n", - "initial_guess = [initial_qs; initial_vs; initial_τs]\n", - "\n", - "# Flatten matrix and truncate torques of last knot\n", - "initial_guess = vec(initial_guess)[1:end - robot.n_τ];" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Calling this will start the optimization\n", - "cpu_time, x, solver_log = TORA.solve_with_ipopt(problem, robot, initial_guess=initial_guess)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.play_trajectory(vis, problem, robot, x)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.plot_results(problem, robot, x)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "TORA.plot_log(solver_log)" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Julia 1.5.2", - "language": "julia", - "name": "julia-1.5" - }, - "language_info": { - "file_extension": ".jl", - "mimetype": "application/julia", - "name": "julia", - "version": "1.5.2" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/ros_kortex/readme.md b/ros_kortex/readme.md new file mode 100644 index 0000000..e31fabb --- /dev/null +++ b/ros_kortex/readme.md @@ -0,0 +1,86 @@ +# ros_kortex +ROS Kortex is the official ROS package to interact with Kortex and its related products. It is built upon the Kortex API, documentation for which can be found in the [GitHub Kortex repository](https://github.com/Kinovarobotics/kortex). + +## Download links + +You can refer to the [Kortex repository "Download links" section](https://github.com/Kinovarobotics/kortex#download-links) to download the firmware package and the release notes. + +### Accessing the color and depth streams + +To access the color and depth streams, you will need to clone and follow the instructions to install the [ros_kortex_vision repository ](https://github.com/Kinovarobotics/ros_kortex_vision). +## Installation + +### Setup + +- [Robot Operating System (ROS)](http://wiki.ros.org) (middleware for robotics) + +This package has been tested under ROS Kinetic (Ubuntu 16.04) and ROS Melodic (Ubuntu 18.04). +You can find the instructions to install ROS Kinetic [here](http://wiki.ros.org/kinetic/Installation/Ubuntu) and ROS Melodic [here](http://wiki.ros.org/melodic/Installation/Ubuntu). + +[Google Protocol Buffers](https://developers.google.com/protocol-buffers/) is used by Kinova to define the Kortex APIs and to automatically generate ROS messages, services and C++ classes from the Kortex API `.proto` files. The installation of Google Protocol Buffers is required by developers implementing new APIs with the robot. However, since we already provide all the necessary generated files on GitHub, this is not required for most end users of the robot. + +### Build + +These are the instructions to run in a terminal to create the workspace, clone the `ros_kortex` repository and install the necessary ROS dependencies: + + sudo apt install python3 python3-pip + sudo python3 -m pip install conan + conan config set general.revisions_enabled=1 + conan profile new default --detect > /dev/null + conan profile update settings.compiler.libcxx=libstdc++11 default + mkdir -p catkin_workspace/src + cd catkin_workspace/src + git clone https://github.com/Kinovarobotics/ros_kortex.git + cd ../ + rosdep install --from-paths src --ignore-src -y + +Then, to build and source the workspace: + catkin_make + source devel/setup.bash + +You can also build against one of the ARMv8 builds of the Kortex API with Conan if you specify the `CONAN_TARGET_PLATFORM` CMake argument when using `catkin_make`. The following platforms are supported: + +- Artik 710: + + catkin_make --cmake-args -DCONAN_TARGET_PLATFORM=artik710 + source devel/setup.bash + +- IMX6: + + catkin_make --cmake-args -DCONAN_TARGET_PLATFORM=imx6 + source devel/setup.bash + +- NVidia Jetson: + + catkin_make --cmake-args -DCONAN_TARGET_PLATFORM=jetson + source devel/setup.bash + +As you see, there are instructions to install the Conan package manager. You can learn more about why we use Conan or how to simply download the API and link against it [in this specific section of the kortex_driver readme](kortex_driver/readme.md#conan). You can also decide + +## Contents + +The following is a description of the packages included in this repository. + +### kortex_control +This package implements the simulation controllers that control the arm in Gazebo. For more details, please consult the [README](kortex_control/readme.md) from the package subdirectory. + +**Note** The `ros_control` controllers for the real arm are not yet implemented and will be in a future release of `ros_kortex`. + +### kortex_description +This package contains the URDF (Unified Robot Description Format), STL and configuration files for the Kortex-compatible robots. For more details, please consult the [README](kortex_description/readme.md) from the package subdirectory. + +### kortex_driver +This package implements a ROS node that allows communication between a node and a Kinova Gen3 or Gen3 lite robot. For more details, please consult the [README](kortex_driver/readme.md) from the package subdirectory. + +### kortex_examples +This package holds all the examples needed to understand the basics of `ros_kortex`. Most of the examples are written in both C++ and Python. Only the MoveIt! example is available exclusively in Python for now. +A more detailed [description](kortex_examples/readme.md) can be found in the package subdirectory. + +### kortex_gazebo +This package contains files to simulate the Kinova Gen3 and Gen3 lite robots in Gazebo. For more details, please consult the [README](kortex_gazebo/readme.md) from the package subdirectory. + +### kortex_move_it_config +This metapackage contains the auto-generated MoveIt! files to use the Kinova Gen3 and Gen3 lite arms with the MoveIt! motion planning framework. For more details, please consult the [README](kortex_move_it_config/readme.md) from the package subdirectory. + +### third_party +This folder contains the third-party packages we use with the ROS Kortex packages. Currently, it consists of two packages used for the simulation of the Robotiq Gripper in Gazebo. We use [gazebo-pkgs](third_party/gazebo-pkgs/README.md) for grasping support in Gazebo and [roboticsgroup_gazebo_plugins](third_party/roboticsgroup_gazebo_plugins/README.md) to mimic joint support in Gazebo. diff --git a/ros_kortex/robots/iiwa14.urdf b/ros_kortex/robots/iiwa14.urdf deleted file mode 100644 index 558147c..0000000 --- a/ros_kortex/robots/iiwa14.urdf +++ /dev/null @@ -1,464 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - true - - - - - 50.0 - /iiwa/state/CartesianWrench - iiwa_joint_7 - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - /iiwa - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - diff --git a/ros_kortex/src/TORA.jl b/ros_kortex/src/TORA.jl deleted file mode 100644 index 5b08903..0000000 --- a/ros_kortex/src/TORA.jl +++ /dev/null @@ -1,42 +0,0 @@ -module TORA - -# Workaround for: https://github.com/JuliaRobotics/RigidBodyDynamics.jl/issues/500 -using LinearAlgebra; BLAS.set_num_threads(1) - -using Colors -using ForwardDiff -using GeometryTypes -using Ipopt -using MeshCat -using MeshCatMechanisms -using NPZ -using Plots -using Requires -using RigidBodyDynamics -using SparseArrays -using SparseDiffTools - -using Plots.PlotMeasures: px -using Random: rand! - -import Base: length - -function __init__() - @require KNITRO = "67920dd8-b58e-52a8-8622-53c4cffbe346" include("./transcription/knitro.jl") -end - -greet() = print("Hello World!") - -# `Struct`-defining files -include("./jacobian_data.jl") -include("./robot.jl") -include("./problem.jl") -include("./solver_log.jl") - -# Regular source code -include("./constraints/dynamics.jl") -include("./constraints/end_effector.jl") -include("./transcription/ipopt.jl") -include("./plots.jl") - -end # module diff --git a/ros_kortex/src/constraints/dynamics.jl b/ros_kortex/src/constraints/dynamics.jl deleted file mode 100644 index 8200e7e..0000000 --- a/ros_kortex/src/constraints/dynamics.jl +++ /dev/null @@ -1,131 +0,0 @@ -function explicit_euler_step(qᵢ, vᵢ, v̇ᵢ, h) - qᵢ₊₁ = qᵢ + h * vᵢ - vᵢ₊₁ = vᵢ + h * v̇ᵢ - - [qᵢ₊₁ - vᵢ₊₁] -end - -function semi_implicit_euler_step(qᵢ, vᵢ, v̇ᵢ, h) - vᵢ₊₁ = vᵢ + h * v̇ᵢ - qᵢ₊₁ = qᵢ + h * vᵢ₊₁ - - [qᵢ₊₁ - vᵢ₊₁] -end - -function forward_dynamics_defects!(defects, robot, x::AbstractArray{T}, h) where {T} - # Indices of the decision variables - ind_qᵢ = (1:robot.n_q) - ind_vᵢ = (1:robot.n_v) .+ (robot.n_q) - ind_τᵢ = (1:robot.n_τ) .+ (robot.n_q + robot.n_v) - ind_qᵢ₊₁ = (1:robot.n_q) .+ (robot.n_q + robot.n_v + robot.n_τ) - ind_vᵢ₊₁ = (1:robot.n_v) .+ (robot.n_q + robot.n_v + robot.n_τ + robot.n_q) - - # Retrieve values of the decision variables - qᵢ , vᵢ , τᵢ = x[ind_qᵢ ], x[ind_vᵢ ], x[ind_τᵢ] - qᵢ₊₁, vᵢ₊₁ = x[ind_qᵢ₊₁], x[ind_vᵢ₊₁] - - # Update robot state - state = robot.statecache[T] - set_configuration!(state, qᵢ) - set_velocity!(state, vᵢ) - - # Compute forward dynamics - result = robot.dynamicsresultcache[T] - dynamics!(result, state, τᵢ) - v̇ᵢ = result.v̇ - - # Integrate the robot state - xᵢ₊₁_integrated = semi_implicit_euler_step(qᵢ, vᵢ, v̇ᵢ, h) - - # Next robot state discretised - xᵢ₊₁_discretised = [qᵢ₊₁ - vᵢ₊₁] - - # Evaluate state defects (joint positions and joint velocities) - copyto!(defects, xᵢ₊₁_integrated - xᵢ₊₁_discretised) -end - -function inverse_dynamics_defects!(defects, robot, x::AbstractArray{T}, h) where {T} - # Indices of the decision variables - ind_qᵢ = (1:robot.n_q) - ind_vᵢ = (1:robot.n_v) .+ (robot.n_q) - ind_τᵢ = (1:robot.n_τ) .+ (robot.n_q + robot.n_v) - ind_qᵢ₊₁ = (1:robot.n_q) .+ (robot.n_q + robot.n_v + robot.n_τ) - ind_vᵢ₊₁ = (1:robot.n_v) .+ (robot.n_q + robot.n_v + robot.n_τ + robot.n_q) - - # Retrieve values of the decision variables - qᵢ , vᵢ , τᵢ = x[ind_qᵢ ], x[ind_vᵢ ], x[ind_τᵢ] - qᵢ₊₁, vᵢ₊₁ = x[ind_qᵢ₊₁], x[ind_vᵢ₊₁] - - # Update robot state - state = robot.statecache[T] - set_configuration!(state, qᵢ) - set_velocity!(state, vᵢ) - - # Implicit joint accelerations - v̇ᵢ = similar(velocity(state)) - copyto!(v̇ᵢ, (vᵢ₊₁ - vᵢ) / h) - - # Compute inverse dynamics - torques = similar(velocity(state)) # create a SegmentedVector instance - dynamics_result = robot.dynamicsresultcache[T] - wrenches = dynamics_result.jointwrenches - accelerations = dynamics_result.accelerations - inverse_dynamics!(torques, wrenches, accelerations, state, v̇ᵢ) - - # position_defects = (qᵢ + h * vᵢ) - qᵢ₊₁ # Explicit Euler - position_defects = (qᵢ + h * vᵢ₊₁) - qᵢ₊₁ # Semi-Implicit Euler - torque_defects = torques - τᵢ - - # Evaluate defects (joint positions and joint torques) - copyto!(defects, [position_defects - torque_defects]) -end - -# - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -function make_cb_eval_fc_con_dyn(problem, robot, jacdata, eval_fc!::Function) - nₓ = robot.n_q + robot.n_v + robot.n_τ # dimension of each mesh points - length_c = size(jacdata.jac, 1) # length of constraint per pair of knots - - function cb_eval_fc_con_dyn(kc, cb, evalRequest, evalResult, userParams) - x = evalRequest.x - - for i = 0:problem.num_knots - 2 - # Calculate the indices of the appropriate decision variables - ind_vars = range(1 + i * nₓ, length=size(jacdata.jac, 2)) - - # Evaluate constraints for Knitro - offset_con = i * length_c - ind_con = (1:length_c) .+ offset_con - @views eval_fc!(evalResult.c[ind_con], robot, x[ind_vars], problem.dt) - end - - return 0 - end -end - -function make_cb_eval_ga_con_dyn(problem, robot, jacdata) - nₓ = robot.n_q + robot.n_v + robot.n_τ # dimension of each mesh points - - function cb_eval_ga_con_dyn(kc, cb, evalRequest, evalResult, userParams) - x = evalRequest.x - - for i = 0:problem.num_knots - 2 - # Calculate the indices of the appropriate decision variables - ind_vars = range(1 + i * nₓ, length=size(jacdata.jac, 2)) - - # Evaluate the Jacobian at that point - jacdata(x[ind_vars]) - - # Pass the Jacobian to Knitro - offset_jac = i * jacdata.length_jac - ind_jac = (1:jacdata.length_jac) .+ offset_jac - evalResult.jac[ind_jac] = nonzeros(jacdata.jac) - end - - return 0 - end -end diff --git a/ros_kortex/src/constraints/end_effector.jl b/ros_kortex/src/constraints/end_effector.jl deleted file mode 100644 index 41dc83b..0000000 --- a/ros_kortex/src/constraints/end_effector.jl +++ /dev/null @@ -1,66 +0,0 @@ -function ee_position!(position, robot, q::AbstractArray{T}) where {T} - state = robot.statecache[T] - set_configuration!(state, q) - - point = Point3D(robot.frame_ee, 0.0, 0.0, 0.0) - position[:] = transform(state, point, root_frame(robot.mechanism)).v -end - -function cb_eval_fc_con_ee(kc, cb, evalRequest, evalResult, userParams) - x = evalRequest.x - problem, robot = userParams - - # dimension of each mesh point - nₓ = robot.n_q + robot.n_v + robot.n_τ - - length_c = 3 - - for (i, k) = enumerate(sort(collect(keys(problem.ee_pos)))) - ind_qᵢ = range(1 + (k - 1) * nₓ, length=robot.n_q) # indices of the decision variables - ind_c = (1:length_c) .+ ((i - 1) * length_c) - @views ee_position!(evalResult.c[ind_c], robot, x[ind_qᵢ]) # constraint evaluation at that point - end - - return 0 -end - -function cb_eval_ga_con_ee(kc, cb, evalRequest, evalResult, userParams) - x = evalRequest.x - problem, robot = userParams - - # dimension of each mesh point - nₓ = robot.n_q + robot.n_v + robot.n_τ - - for (i, k) = enumerate(sort(collect(keys(problem.ee_pos)))) - ind_qᵢ = range(1 + (k - 1) * nₓ, length=robot.n_q) # indices of the decision variables - problem.jacdata_ee_position(x[ind_qᵢ]) # jacobian evaluation at that point - ind_jac = (1:problem.jacdata_ee_position.length_jac) .+ ((i - 1) * problem.jacdata_ee_position.length_jac) - evalResult.jac[ind_jac] = nonzeros(problem.jacdata_ee_position.jac) # pass jacobian to Knitro - end - - return 0 -end - -function get_ee_path(problem::Problem, robot::Robot, x) - positions = zeros(3, problem.num_knots) - - # dimension of each mesh point - nₓ = robot.n_q + robot.n_v + robot.n_τ - - length_c = 3 - - for i = (1:problem.num_knots) .- 1 - ind_c = (1:length_c) .+ (i * length_c) - ind_qᵢ = range(1 + i * nₓ, length=robot.n_q) - @views ee_position!(positions[ind_c], robot, x[ind_qᵢ]) - end - - return positions -end - -function show_ee_path(vis::Visualizer, ee_positions::Array{Float64}) - points = collect(eachcol(ee_positions)) - material = LineBasicMaterial(color=colorant"yellow", linewidth=2.0) - setobject!(vis["ee path"], Object(PointCloud(points), material, "Line")) - nothing -end diff --git a/ros_kortex/src/jacobian_data.jl b/ros_kortex/src/jacobian_data.jl deleted file mode 100644 index d22f9d7..0000000 --- a/ros_kortex/src/jacobian_data.jl +++ /dev/null @@ -1,35 +0,0 @@ -struct JacobianData{T1 <: SparseMatrixCSC,T2 <: ForwardColorJacCache} - f!::Function - jac::T1 - jac_cache::T2 - length_jac::Int - sparsity::SparseArrays.SparseMatrixCSC{Bool,Int64} - - function JacobianData(f!, output, input) - # TODO Proper way to do it (currently not working) - # Issue: https://github.com/SciML/SparsityDetection.jl/issues/41 - # sparsity = jacobian_sparsity(f!, output, input) - - # Workaround - num_samples = 50 - jac_samples = [ForwardDiff.jacobian(f!, rand!(output), rand!(input)) for _ in 1:num_samples] - sparsity = sparse(sum(jac_samples) .≠ 0) - - jac = convert.(Float64, sparse(sparsity)) - - jac_cache = ForwardColorJacCache(f!, input, dx=output, - colorvec=matrix_colors(jac), - sparsity=sparsity) - - length_jac = nnz(jac) - - T1 = typeof(jac) - T2 = typeof(jac_cache) - - new{T1,T2}(f!, jac, jac_cache, length_jac, sparsity) - end -end - -function (jd::JacobianData)(x) - forwarddiff_color_jacobian!(jd.jac, jd.f!, x, jd.jac_cache) -end diff --git a/ros_kortex/src/plots.jl b/ros_kortex/src/plots.jl deleted file mode 100644 index e419cd2..0000000 --- a/ros_kortex/src/plots.jl +++ /dev/null @@ -1,80 +0,0 @@ -function play_trajectory(vis, problem, robot, x) - ee_positions = get_ee_path(problem, robot, x) - show_ee_path(vis, ee_positions) - - nₓ = robot.n_q + robot.n_v + robot.n_τ # dimension of each mesh point - ind_q = hcat([range(1 + (i * nₓ), length=robot.n_q) for i = (1:problem.num_knots) .- 1]...) - q_mat = x[ind_q] - - ts = range(0, length=problem.num_knots, step=problem.dt) - qs = [q_mat[:, i] for i = 1:size(q_mat, 2)] - - animation = MeshCat.Animation(robot.mvis, ts, qs) - setanimation!(robot.mvis, animation) -end - -function plot_results(problem::Problem, robot::Robot, x) - nₓ = robot.n_q + robot.n_v + robot.n_τ # dimension of each mesh point - - # Helper ranges - ind_q = hcat([range(1 + (i * nₓ) , length=robot.n_q) for i = (1:problem.num_knots ) .- 1]...) - ind_v = hcat([range(1 + (i * nₓ) + robot.n_q , length=robot.n_v) for i = (1:problem.num_knots ) .- 1]...) - ind_τ = hcat([range(1 + (i * nₓ) + robot.n_q + robot.n_v, length=robot.n_τ) for i = (1:problem.num_knots - 1) .- 1]...) - - ts = range(0, length=problem.num_knots, step=problem.dt) - - plts = plot(ts , x[ind_q]', lw=2, legend=nothing, xlabel="time [s]", ylabel="position [rad]"), - plot(ts , x[ind_v]', lw=2, legend=nothing, xlabel="time [s]", ylabel="velocity [rad/s]"), - plot(ts[1:end-1], x[ind_τ]', lw=2, legend=nothing, xlabel="time [s]", ylabel="torque [Nm]") - - plot( - plts..., - layout=grid(3,1), - size=(600,3*400), - left_margin=20px, - bottom_margin=20px, - ) -end - -function plot_log(solver_log::SolverLog) - - plt_1 = plot( - title="feasibility", title_location=:left, - xlabel="iterations", - ylabel="error", - yaxis=(:log10, [1e-11, 1e4]), - legend=nothing, - ) - - plot!(solver_log.abs_feas_error, c=1, lw=2) - scatter!([length(solver_log.abs_feas_error)], solver_log.abs_feas_error[end:end], c=1, marker=:star4) - - plt_2 = plot( - title="objective", title_location=:left, - xlabel="iterations", - ylabel="cost (1e4)", - legend=nothing, - ) - - obj_value = solver_log.obj_value / 1e4 - - plot!(obj_value, c=1, lw=2) - scatter!([length(obj_value)], obj_value[end:end], c=1, marker=:star4) - - plot( - plt_1, plt_2, - size=(600,300), - # left_margin=20px, - - fontfamily = "Times", - guidefontsize = 12, - legendfontsize = 12, - tickfontsize = 10, - titlefontsize = 15, - ) -end - -export - play_trajectory, - plot_results, - plot_log diff --git a/ros_kortex/src/problem.jl b/ros_kortex/src/problem.jl deleted file mode 100644 index 20541ed..0000000 --- a/ros_kortex/src/problem.jl +++ /dev/null @@ -1,106 +0,0 @@ -mutable struct Problem - num_knots::Int # Total number of knots - dt::Float64 # Time step between two knots - - fixed_q::Dict{Int64,Array{Float64}} # Fixed joint positions - fixed_v::Dict{Int64,Array{Float64}} # Fixed joint velocities - fixed_τ::Dict{Int64,Array{Float64}} # Fixed joint torques - - ee_pos::Dict{Int64,Point{3,Float64}} # End-effector target positions - - # Jacobian data (e.g., for sparse Jacobian of dynamics with AD) - jacdata_fwd_dyn::JacobianData - jacdata_inv_dyn::JacobianData - jacdata_ee_position::JacobianData - - function Problem(robot, num_knots, dt) - @assert num_knots > 0 - @assert dt > 0 - - input, output = rand(2 * (robot.n_q + robot.n_v) + robot.n_τ), rand(robot.n_q + robot.n_v) - jacdata_fwd_dyn = JacobianData((out, x) -> forward_dynamics_defects!(out, robot, x, dt), output, input) - - input, output = rand(2 * (robot.n_q + robot.n_v) + robot.n_τ), rand(robot.n_q + robot.n_τ) - jacdata_inv_dyn = JacobianData((out, x) -> inverse_dynamics_defects!(out, robot, x, dt), output, input) - - input, output = rand(robot.n_q), rand(3) - jacdata_ee_position = JacobianData((out, x) -> ee_position!(out, robot, x), output, input) - - new( - num_knots, dt, - Dict{Int64,Array{Float64}}(), - Dict{Int64,Array{Float64}}(), - Dict{Int64,Array{Float64}}(), - Dict{Int64,Point{3,Float64}}(), - jacdata_fwd_dyn, - jacdata_inv_dyn, - jacdata_ee_position - ) - end -end - -""" - fix_joint_positions!(problem, robot, knot, q) - -Returns a. -""" -function fix_joint_positions!(problem::Problem, robot::Robot, knot, q) - @assert 1 <= knot <= problem.num_knots - @assert all(robot.q_lo .<= q .<= robot.q_hi) - problem.fixed_q[knot] = q - return problem -end - -""" - fix_joint_velocities!(problem, robot, knot, v) - -To do. -""" -function fix_joint_velocities!(problem::Problem, robot::Robot, knot, v) - @assert 1 <= knot <= problem.num_knots - @assert all(robot.v_lo .<= v .<= robot.v_hi) - problem.fixed_v[knot] = v - return problem -end - -""" - fix_joint_torques!(problem, robot, knot, τ) - -To do. -""" -function fix_joint_torques!(problem::Problem, robot::Robot, knot, τ) - @assert 1 <= knot <= problem.num_knots - 1 - @assert all(robot.τ_lo .<= τ .<= robot.τ_hi) - problem.fixed_τ[knot] = τ - return problem -end - -""" - constrain_ee_position!(problem, knot, position) - -To do. -""" -function constrain_ee_position!(problem::Problem, knot, position) - @assert 1 <= knot <= problem.num_knots - @assert length(position) == 3 - problem.ee_pos[knot] = position - return problem -end - -function show_problem_info(problem::Problem) - t = (problem.num_knots - 1) * problem.dt - - println("Motion duration ...................................... $(t) seconds") - println("Number of knots with constrained joint positions ..... $(length(problem.fixed_q))") - println("Number of knots with constrained joint velocities .... $(length(problem.fixed_v))") - println("Number of knots with constrained joint torques ....... $(length(problem.fixed_τ))") - println("Number of knots with constrained ee position ......... $(length(problem.ee_pos))") -end - -export - Problem, - fix_joint_positions!, - fix_joint_velocities!, - fix_joint_torques!, - constrain_ee_position!, - show_problem_info diff --git a/ros_kortex/src/robot.jl b/ros_kortex/src/robot.jl deleted file mode 100644 index 170af90..0000000 --- a/ros_kortex/src/robot.jl +++ /dev/null @@ -1,71 +0,0 @@ -struct Robot - urdfpath::String - mechanism::Mechanism - state::MechanismState - statecache::StateCache - dynamicsresultcache::DynamicsResultCache - mvis::MechanismVisualizer - - q_lo::Array{Float64} - q_hi::Array{Float64} - v_lo::Array{Float64} - v_hi::Array{Float64} - τ_lo::Array{Float64} - τ_hi::Array{Float64} - - n_q::Int64 # Number of generalized coordinates - n_v::Int64 # Number of generalized velocities - n_τ::Int64 # Number of actuated joints - - frame_ee::CartesianFrame3D # End-effector frame - - function Robot(urdfpath::String, - mechanism::Mechanism, - frame_ee::CartesianFrame3D, - mvis::MechanismVisualizer) - state = MechanismState(mechanism) - statecache = StateCache(mechanism) - dynamicsresultcache = DynamicsResultCache(mechanism) - - q_lo = [lim for joint in joints(mechanism) for lim in map(x -> x.lower, position_bounds(joint))] - q_hi = [lim for joint in joints(mechanism) for lim in map(x -> x.upper, position_bounds(joint))] - v_lo = [lim for joint in joints(mechanism) for lim in map(x -> x.lower, velocity_bounds(joint))] - v_hi = [lim for joint in joints(mechanism) for lim in map(x -> x.upper, velocity_bounds(joint))] - τ_lo = [lim for joint in joints(mechanism) for lim in map(x -> x.lower, effort_bounds(joint))] - τ_hi = [lim for joint in joints(mechanism) for lim in map(x -> x.upper, effort_bounds(joint))] - - new( - urdfpath, - mechanism, - state, - statecache, - dynamicsresultcache, - mvis, - q_lo, - q_hi, - v_lo, - v_hi, - τ_lo, - τ_hi, - num_positions(mechanism), - num_velocities(mechanism), - num_velocities(mechanism), - frame_ee - ) - end -end - -function create_robot_kuka_iiwa_14(vis::Visualizer) - package_path = joinpath(@__DIR__, "..", "iiwa_stack") - urdfpath = joinpath(@__DIR__, "..", "robots", "iiwa14.urdf") - - mechanism = parse_urdf(urdfpath, remove_fixed_tree_joints=false) - frame_ee = default_frame(findbody(mechanism, "iiwa_link_pen_tip")) - remove_fixed_tree_joints!(mechanism) - - urdfvisuals = URDFVisuals(urdfpath, package_path=[package_path]) - mvis = MechanismVisualizer(mechanism, urdfvisuals, vis["robot"]) - # setelement!(mvis, frame_ee) # Visualise a triad at the end-effector - - Robot(urdfpath, mechanism, frame_ee, mvis) -end diff --git a/ros_kortex/src/solver_log.jl b/ros_kortex/src/solver_log.jl deleted file mode 100644 index 5f659d0..0000000 --- a/ros_kortex/src/solver_log.jl +++ /dev/null @@ -1,95 +0,0 @@ -mutable struct SolverLog - x::Array{Float64,2} - abs_feas_error::Array{Float64,1} - abs_opt_error::Array{Float64,1} - obj_value::Array{Float64,1} - fc_evals::Array{Float64,1} - ga_evals::Array{Float64,1} - nStatus::Int # solution status return code - - @doc """ - SolverLog(N::Int) - - Creates an empty NLP solver log. - - # Arguments - - `N`: the total number of decision variables of the NLP. - """ - function SolverLog(N) - new(Array{Float64,2}(undef, N, 0), - Array{Float64,1}(undef, 0), - Array{Float64,1}(undef, 0), - Array{Float64,1}(undef, 0), - Array{Float64,1}(undef, 0), - Array{Float64,1}(undef, 0), - -999) - end -end - -""" - update!(log::SolverLog, - x::Array{Float64,2}, - abs_feas_error::Array{Float64,1}, - abs_opt_error::Array{Float64,1}, - obj_value::Array{Float64,1}, - fc_evals::Array{Float64,1}, - ga_evals::Array{Float64,1}) - -Updates the log. - -# Arguments -- `log`: instance of a `SolverLog`. -- `x`: an intermediate iterate point. -- `abs_feas_error`: abs_feas_error at the current point. -- `abs_opt_error`: abs_opt_error at the current point. -- `obj_value`: obj_value at the current point. -- `fc_evals`: the number of function evaluations requested by the NLP solver so far. -- `ga_evals`: the number of gradient evaluations requested by the NLP solver so far. -""" -function update!(log, x, abs_feas_error, abs_opt_error, obj_value, fc_evals, ga_evals) - log.x = hcat(log.x, x) - log.abs_feas_error = vcat(log.abs_feas_error, abs_feas_error) - log.abs_opt_error = vcat(log.abs_opt_error, abs_opt_error) - log.obj_value = vcat(log.obj_value, obj_value) - log.fc_evals = vcat(log.fc_evals, fc_evals) - log.ga_evals = vcat(log.ga_evals, ga_evals) -end - -function length(log::SolverLog) - num_iters = size(log.x, 2) - @assert all(==(num_iters), length.([log.abs_feas_error, log.abs_opt_error, log.obj_value, log.fc_evals, log.ga_evals])) - return num_iters -end - -function save(log::SolverLog, file::String) - npzwrite(file, Dict( - "x" => log.x, - "abs_feas_error" => log.abs_feas_error, - "abs_opt_error" => log.abs_opt_error, - "obj_value" => log.obj_value, - "fc_evals" => log.fc_evals, - "ga_evals" => log.ga_evals, - "nStatus" => log.nStatus, - )) -end - -function load!(log::SolverLog, file::String) - data = npzread(file) - - log.x = data["x"] - log.abs_feas_error = data["abs_feas_error"] - log.abs_opt_error = data["abs_opt_error"] - log.obj_value = data["obj_value"] - log.fc_evals = data["fc_evals"] - log.ga_evals = data["ga_evals"] - log.nStatus = data["nStatus"] - - return log -end - -export - SolverLog, - update!, - length, - save, - load! diff --git a/ros_kortex/src/transcription/ipopt.jl b/ros_kortex/src/transcription/ipopt.jl deleted file mode 100644 index 5af68f5..0000000 --- a/ros_kortex/src/transcription/ipopt.jl +++ /dev/null @@ -1,291 +0,0 @@ -function solve_with_ipopt(problem::Problem, robot::Robot; - initial_guess::Array{Float64}=Float64[], - use_inv_dyn::Bool=false, - minimise_τ::Bool=false, - user_options::Dict=Dict()) - # # # # # # # # # # # # # # # # - # Variables and their bounds # - # # # # # # # # # # # # # # # # - - n1 = robot.n_q * problem.num_knots # positions - n2 = robot.n_v * problem.num_knots # velocities - n3 = robot.n_τ * (problem.num_knots - 1) # torques - - n = n1 + n2 + n3 # total number of decision variables - - x_L = Array{Float64,2}(undef, robot.n_q, 0) - x_U = Array{Float64,2}(undef, robot.n_q, 0) - - for k = 1:problem.num_knots - if k ∈ keys(problem.fixed_q) - x_L = [x_L problem.fixed_q[k]] - x_U = [x_U problem.fixed_q[k]] - else - x_L = [x_L robot.q_lo] - x_U = [x_U robot.q_hi] - end - - if k ∈ keys(problem.fixed_v) - x_L = [x_L problem.fixed_v[k]] - x_U = [x_U problem.fixed_v[k]] - else - x_L = [x_L robot.v_lo] - x_U = [x_U robot.v_hi] - end - - if k <= problem.num_knots - 1 - if k ∈ keys(problem.fixed_τ) - x_L = [x_L problem.fixed_τ[k]] - x_U = [x_U problem.fixed_τ[k]] - else - x_L = [x_L robot.τ_lo] - x_U = [x_U robot.τ_hi] - end - end - end - - # # # # # # # # - # Constraints # - # # # # # # # # - - use_m₁ = true # nonlinear equality: dynamics - use_m₂ = true # nonlinear equality: ee xyz-position - - m₁ = !use_m₁ ? 0 : (robot.n_q + robot.n_v) * (problem.num_knots - 1) # equations of motion - m₂ = !use_m₂ ? 0 : 3 * length(problem.ee_pos) # xyz-position (3 NL equality) - - m = m₁ + m₂ # total number of constraints - - ind_con_dyn = (1:m₁) - ind_con_ee_pos = (1:m₂) .+ (m₁) - - g_L, g_U = Float64[], Float64[] - - if use_m₁ - append!(g_L, zeros(m₁)) - append!(g_U, zeros(m₁)) - end - - if use_m₂ - knots_con_ee = sort(collect(keys(problem.ee_pos))) - con_ee = hcat([[problem.ee_pos[k].data...] for k in knots_con_ee]...) - append!(g_L, vec(con_ee)) - append!(g_U, vec(con_ee)) - end - - @assert length(g_L) == length(g_U) - @assert eltype(g_L) == eltype(g_U) == Float64 - - # dimension of each mesh point - nₓ = robot.n_q + robot.n_v + robot.n_τ - - if use_inv_dyn - jacdata_dyn = problem.jacdata_inv_dyn - dynamics_defects! = inverse_dynamics_defects! - else - jacdata_dyn = problem.jacdata_fwd_dyn - dynamics_defects! = forward_dynamics_defects! - end - - function eval_g(x, g) - if use_m₁ - length_c = size(jacdata_dyn.jac, 1) # length of constraint per pair of knots - for i = 0:problem.num_knots - 2 - # Calculate the indices of the appropriate decision variables - ind_vars = range(1 + i * nₓ, length=size(jacdata_dyn.jac, 2)) - - # Evaluate constraints - offset_con = i * length_c - ind_cons = (1:length_c) .+ offset_con - @views dynamics_defects!(g[ind_cons], robot, x[ind_vars], problem.dt) - end - end - - if use_m₂ - length_c = 3 - for (i, k) = enumerate(sort(collect(keys(problem.ee_pos)))) - ind_vars = range(1 + (k - 1) * nₓ, length=robot.n_q) # indices of the decision variables - offset_con = (i - 1) * length_c + (m₁) - ind_cons = (1:length_c) .+ offset_con - @views ee_position!(g[ind_cons], robot, x[ind_vars]) # constraint evaluation at that point - end - end - end - - jacIndexConsCB = Cint[] - jacIndexVarsCB = Cint[] - - if use_m₁ - for i = 0:problem.num_knots - 2 - offset_con = i * size(jacdata_dyn.jac, 1) - ind_cons = rowvals(jacdata_dyn.jac) .+ offset_con - append!(jacIndexConsCB, ind_cons) - - for j = 1:size(jacdata_dyn.jac, 2) - ind_vars = fill(j + i * nₓ, length(nzrange(jacdata_dyn.jac, j))) - append!(jacIndexVarsCB, ind_vars) - end - end - - @assert length(jacIndexConsCB) == length(jacIndexVarsCB) - end - - if use_m₂ - ind_offset = m₁ - for k = knots_con_ee - inds = rowvals(problem.jacdata_ee_position.jac) .+ ind_offset - ind_offset += size(problem.jacdata_ee_position.jac, 1) - append!(jacIndexConsCB, inds) - end - - for k = knots_con_ee - vals = vcat([fill(j + (k - 1) * nₓ, length(nzrange(problem.jacdata_ee_position.jac, j))) - for j = 1:size(problem.jacdata_ee_position.jac, 2)]...) - append!(jacIndexVarsCB, vals) - end - - @assert length(jacIndexConsCB) == length(jacIndexVarsCB) - end - - - function eval_jac_g(x, mode, rows, cols, values) - if mode == :Structure - for (i, r, c) in zip(1:length(jacIndexConsCB), jacIndexConsCB, jacIndexVarsCB) - rows[i] = r - cols[i] = c - end - else - offset_prev = 0 - - if use_m₁ - # Dynamics constraints - for i = 0:problem.num_knots - 2 - # Calculate the indices of the appropriate decision variables - ind_vars = range(1 + i * nₓ, length=size(jacdata_dyn.jac, 2)) - - # Evaluate the Jacobian at that point - jacdata_dyn(x[ind_vars]) - - # Pass the Jacobian to Knitro - offset_jac = i * jacdata_dyn.length_jac - ind_jac = (1:jacdata_dyn.length_jac) .+ offset_jac - values[ind_jac] = nonzeros(jacdata_dyn.jac) - end - offset_prev += (problem.num_knots - 1) * jacdata_dyn.length_jac - end - - if use_m₂ - # End-effector constraints - for (i, k) = enumerate(sort(collect(keys(problem.ee_pos)))) - ind_qᵢ = range(1 + (k - 1) * nₓ, length=robot.n_q) # indices of the decision variables - problem.jacdata_ee_position(x[ind_qᵢ]) # jacobian evaluation at that point - offset_jac = (i - 1) * problem.jacdata_ee_position.length_jac + offset_prev - ind_jac = (1:problem.jacdata_ee_position.length_jac) .+ offset_jac - values[ind_jac] = nonzeros(problem.jacdata_ee_position.jac) # pass jacobian to Knitro - end - end - end - end - - # # # # # # # - # Objective # - # # # # # # # - - function eval_f(x) - return 0 - end - - function eval_grad_f(x, grad_f) - grad_f[:] = zeros(n) - end - - if minimise_τ - ind_τ = hcat([range(1 + (i * nₓ) + robot.n_q + robot.n_v, length=robot.n_τ) - for i = (1:problem.num_knots - 1) .- 1]...) - indexVars, coefs = vec(ind_τ), fill(1 / (problem.num_knots - 1), n3) - @assert length(indexVars) == length(coefs) - - eval_f = function(x) - # Minimise τ, i.e., the necessary joint torques. - return sum(coefs .* x[indexVars] .* x[indexVars]) - end - - eval_grad_f = function(x, grad_f) - grad_f[:] = zeros(n) - grad_f[indexVars] .= coefs .* 2x[indexVars] - end - end - - # # # # # # # # # # - # Create Problem # - # # # # # # # # # # - - # number of nonzeros in the Jacobian of the constraints - nele_jac = 0 - nele_jac += !use_m₁ ? 0 : jacdata_dyn.length_jac * (problem.num_knots - 1) - nele_jac += !use_m₂ ? 0 : problem.jacdata_ee_position.length_jac * length(problem.ee_pos) - - prob = Ipopt.createProblem(n, vec(x_L), vec(x_U), m, g_L, g_U, nele_jac, 0, - eval_f, eval_g, eval_grad_f, eval_jac_g) - - # # # # # # # # # - # Initial guess # - # # # # # # # # # - - if initial_guess |> isempty - initial_guess = zeros(n) - end - - # Set starting solution - prob.x = copy(initial_guess) - - @assert length(prob.x) == length(initial_guess) == n - - # # # # # # # # # - # User Options # - # # # # # # # # # - - addOption(prob, "hessian_approximation", "limited-memory") - addOption(prob, "mu_strategy", "adaptive") - # addOption(prob, "linear_solver", "ma57") - # addOption(prob, "ma57_pre_alloc", 2.0) - addOption(prob, "tol", 1.0e-3) - addOption(prob, "max_cpu_time", 10.0) - - foreach(x -> addOption(prob, x...), user_options) - - solver_log = SolverLog(n) - - function intermediate(alg_mod::Int, iter_count::Int, obj_value::Float64, inf_pr::Float64, inf_du::Float64, mu::Float64, - d_norm::Float64, regularization_size::Float64, alpha_du::Float64, alpha_pr::Float64, ls_trials::Int) - print("") # Flush the output to the Jupyter notebook cell - - x = zeros(n) # Not implemented for Ipopt - abs_opt_error = 0 # Not implemented for Ipopt - fc_evals = 0 # Not implemented for Ipopt - ga_evals = 0 # Not implemented for Ipopt - - update!(solver_log, x, inf_pr, abs_opt_error, obj_value, fc_evals, ga_evals) - - return true - end - - setIntermediateCallback(prob, intermediate) - - # # Perform a derivative check. - # addOption(prob, "derivative_test", "first-order") - - # # # # # - # Solve # - # # # # # - - cpu_time = @elapsed status = Ipopt.solveProblem(prob) - - # println(Ipopt.ApplicationReturnStatus[status]) - # println(prob.x) - # println(prob.obj_val) - - return cpu_time, prob.x, solver_log -end - -export solve_with_ipopt diff --git a/ros_kortex/src/transcription/knitro.jl b/ros_kortex/src/transcription/knitro.jl deleted file mode 100644 index 72ef1ad..0000000 --- a/ros_kortex/src/transcription/knitro.jl +++ /dev/null @@ -1,211 +0,0 @@ -using .KNITRO - -function solve_with_knitro(problem::Problem, robot::Robot; - initial_guess::Array{Float64}=Float64[], - use_inv_dyn::Bool=false, - minimise_τ::Bool=false, - user_options::Dict=Dict()) - lm = KNITRO.LMcontext() # Instantiate license manager - kc = KNITRO.KN_new_lm(lm) # Create a new Knitro instance - - # # # # # # # # # # # # # # # # - # Variables and their bounds # - # # # # # # # # # # # # # # # # - - n1 = robot.n_q * problem.num_knots # positions - n2 = robot.n_v * problem.num_knots # velocities - n3 = robot.n_τ * (problem.num_knots - 1) # torques - - n = n1 + n2 + n3 # total number of decision variables - KNITRO.KN_add_vars(kc, n) # add the variables - - nₓ = robot.n_q + robot.n_v + robot.n_τ # dimension of each mesh point - - # Helper ranges - ind_q = hcat([range(1 + (i * nₓ) , length=robot.n_q) for i = (1:problem.num_knots ) .- 1]...) - ind_v = hcat([range(1 + (i * nₓ) + robot.n_q , length=robot.n_v) for i = (1:problem.num_knots ) .- 1]...) - ind_τ = hcat([range(1 + (i * nₓ) + robot.n_q + robot.n_v, length=robot.n_τ) for i = (1:problem.num_knots - 1) .- 1]...) - - KNITRO.KN_set_var_lobnds(kc, Cint.(vec(ind_q) .- 1), repeat(robot.q_lo, problem.num_knots)) # q lower bounds - KNITRO.KN_set_var_upbnds(kc, Cint.(vec(ind_q) .- 1), repeat(robot.q_hi, problem.num_knots)) # q upper bounds - - KNITRO.KN_set_var_lobnds(kc, Cint.(vec(ind_v) .- 1), repeat(robot.v_lo, problem.num_knots)) # v lower bounds - KNITRO.KN_set_var_upbnds(kc, Cint.(vec(ind_v) .- 1), repeat(robot.v_hi, problem.num_knots)) # v upper bounds - - if !isempty(ind_τ) - KNITRO.KN_set_var_lobnds(kc, Cint.(vec(ind_τ) .- 1), repeat(robot.τ_lo, problem.num_knots - 1)) # τ lower bounds - KNITRO.KN_set_var_upbnds(kc, Cint.(vec(ind_τ) .- 1), repeat(robot.τ_hi, problem.num_knots - 1)) # τ upper bounds - end - - # Fixed variables - for (k, q) ∈ problem.fixed_q KNITRO.KN_set_var_fxbnds(kc, Cint.(vec(ind_q[:,k]) .- 1), q) end - for (k, v) ∈ problem.fixed_v KNITRO.KN_set_var_fxbnds(kc, Cint.(vec(ind_v[:,k]) .- 1), v) end - for (k, τ) ∈ problem.fixed_τ KNITRO.KN_set_var_fxbnds(kc, Cint.(vec(ind_τ[:,k]) .- 1), τ) end - - # # # # # # # # - # Constraints # - # # # # # # # # - - use_m₁ = true # nonlinear equality: dynamics - use_m₂ = true # nonlinear equality: ee xyz-position - - m₁ = !use_m₁ ? 0 : (robot.n_q + robot.n_v) * (problem.num_knots - 1) # equations of motion - m₂ = !use_m₂ ? 0 : 3 * length(problem.ee_pos) # xyz-position (3 NL equality) - - m = m₁ + m₂ # total number of constraints - KNITRO.KN_add_cons(kc, m) # add the constraints - - ind_con_dyn = (1:m₁) - ind_con_ee_pos = (1:m₂) .+ (m₁) - - if use_m₁ - KNITRO.KN_set_con_eqbnds(kc, collect(Cint, ind_con_dyn .- 1), zeros(m₁)) - - if use_inv_dyn - jac = problem.jacdata_inv_dyn.jac - cb_eval_fc_con = make_cb_eval_fc_con_dyn(problem, robot, problem.jacdata_inv_dyn, inverse_dynamics_defects!) - cb_eval_ga_con = make_cb_eval_ga_con_dyn(problem, robot, problem.jacdata_inv_dyn) - else - jac = problem.jacdata_fwd_dyn.jac - cb_eval_fc_con = make_cb_eval_fc_con_dyn(problem, robot, problem.jacdata_fwd_dyn, forward_dynamics_defects!) - cb_eval_ga_con = make_cb_eval_ga_con_dyn(problem, robot, problem.jacdata_fwd_dyn) - end - - cb = KNITRO.KN_add_eval_callback(kc, false, collect(Cint, ind_con_dyn .- 1), cb_eval_fc_con) - - jacIndexConsCB = Cint.(hcat([rowvals(jac) .+ i * size(jac, 1) - for i = 0:problem.num_knots - 2]...) .- 1) - - jacIndexVarsCB = Cint.(hcat([vcat([fill(j + i * nₓ, length(nzrange(jac, j))) - for j = 1:size(jac, 2)]...) - for i = 0:problem.num_knots - 2]...) .- 1) - - @assert length(jacIndexConsCB) == length(jacIndexVarsCB) - @assert eltype(jacIndexConsCB) == eltype(jacIndexVarsCB) == Cint - - KNITRO.KN_set_cb_grad(kc, cb, cb_eval_ga_con, - nV=0, objGradIndexVars=C_NULL, - jacIndexCons=jacIndexConsCB, - jacIndexVars=jacIndexVarsCB) - end - - if use_m₂ - knots_con_ee = sort(collect(keys(problem.ee_pos))) - - con_ee = Array{Float64,2}(undef, 3, 0) - - for k in knots_con_ee - con_ee = [con_ee problem.ee_pos[k]] - end - - @assert length(ind_con_ee_pos) == length(con_ee) - - KNITRO.KN_set_con_eqbnds(kc, collect(Cint, ind_con_ee_pos .- 1), vec(con_ee)) - - cb = KNITRO.KN_add_eval_callback(kc, false, collect(Cint, ind_con_ee_pos .- 1), cb_eval_fc_con_ee) - - ind_offset = 0 - jacIndexConsCB = Cint[] - for k = knots_con_ee - inds = rowvals(problem.jacdata_ee_position.jac) .+ ind_offset - ind_offset += size(problem.jacdata_ee_position.jac, 1) - append!(jacIndexConsCB, inds) - end - jacIndexConsCB = Cint.(jacIndexConsCB .+ (m₁) .- 1) - - jacIndexVarsCB = Cint[] - for k = knots_con_ee - vals = vcat([fill(j + (k - 1) * nₓ, length(nzrange(problem.jacdata_ee_position.jac, j))) - for j = 1:size(problem.jacdata_ee_position.jac, 2)]...) - append!(jacIndexVarsCB, vals) - end - jacIndexVarsCB = Cint.(jacIndexVarsCB .- 1) - - @assert length(jacIndexConsCB) == length(jacIndexVarsCB) - @assert eltype(jacIndexConsCB) == eltype(jacIndexVarsCB) == Cint - - KNITRO.KN_set_cb_grad(kc, cb, cb_eval_ga_con_ee, - nV=0, objGradIndexVars=C_NULL, - jacIndexCons=jacIndexConsCB, - jacIndexVars=jacIndexVarsCB) - - KNITRO.KN_set_cb_user_params(kc, cb, (problem, robot)) - end - - # # # # # # # - # Objective # - # # # # # # # - - if minimise_τ - # Minimise τ, i.e., the necessary joint torques. - indexVars, coefs = Cint.(vec(ind_τ) .- 1), fill(1 / (problem.num_knots - 1), n3) - KNITRO.KN_add_obj_quadratic_struct(kc, indexVars, indexVars, coefs) - - KNITRO.KN_set_obj_goal(kc, KNITRO.KN_OBJGOAL_MINIMIZE) - end - - # # # # # # # # # - # Initial guess # - # # # # # # # # # - - if !isempty(initial_guess) - KNITRO.KN_set_var_primal_init_values(kc, vec(initial_guess)) - else - KNITRO.KN_set_var_primal_init_values(kc, zeros(n)) - end - - # # # # # # # # # - # User Options # - # # # # # # # # # - - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_HESSOPT, KNITRO.KN_HESSOPT_LBFGS) - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_ALGORITHM, KNITRO.KN_ALG_BAR_DIRECT) - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_BAR_MURULE, KNITRO.KN_BAR_MURULE_ADAPTIVE) - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_LINSOLVER, KNITRO.KN_LINSOLVER_MA57) - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_FEASTOL, 1.0e-3) - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_FTOL, 1.0e-6) - KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_MAXTIMECPU, 10.0) - - solver_log = SolverLog(n) - - function callbackNewPoint(kc, x, duals, userParams) - print("") # Flush the output to the Jupyter notebook cell - - abs_feas_error = KNITRO.KN_get_abs_feas_error(kc) - abs_opt_error = KNITRO.KN_get_abs_opt_error(kc) - obj_value = KNITRO.KN_get_obj_value(kc) - - fc_evals = KNITRO.KN_get_number_FC_evals(kc) - ga_evals = KNITRO.KN_get_number_GA_evals(kc) - - update!(solver_log, x, abs_feas_error, abs_opt_error, obj_value, fc_evals, ga_evals) - - return 0 - end - - KNITRO.KN_set_newpt_callback(kc, callbackNewPoint) - - # # - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - # # Perform a derivative check. - # KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_DERIVCHECK, KNITRO.KN_DERIVCHECK_FIRST) - # KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_DERIVCHECK_TERMINATE, KNITRO.KN_DERIVCHECK_STOPALWAYS) - # # KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_DERIVCHECK_TOL, 1.0e-4) # Default value: 1.0e-6 - # KNITRO.KN_set_param(kc, KNITRO.KN_PARAM_DERIVCHECK_TYPE, KNITRO.KN_DERIVCHECK_CENTRAL) - - # # # # # - # Solve # - # # # # # - - KNITRO.KN_solve(kc) # Solve the problem - - # Retrieve solution information - nStatus, objSol, x, duals = KNITRO.KN_get_solution(kc) - cpu_time = KNITRO.KN_get_solve_time_real(kc) - - KNITRO.KN_free(kc) # Delete the Knitro solver instance - KNITRO.KN_release_license(lm) # Free license manager - - return cpu_time, x, solver_log -end - -export solve_with_knitro diff --git a/ros_kortex/test/Project.toml b/ros_kortex/test/Project.toml deleted file mode 100644 index 0c36332..0000000 --- a/ros_kortex/test/Project.toml +++ /dev/null @@ -1,2 +0,0 @@ -[deps] -Test = "8dfed614-e22c-5e08-85e1-65c5234f0b40" diff --git a/ros_kortex/test/runtests.jl b/ros_kortex/test/runtests.jl deleted file mode 100644 index cd20b54..0000000 --- a/ros_kortex/test/runtests.jl +++ /dev/null @@ -1,4 +0,0 @@ -using Test, TORA - -@testset "TORA" begin -end diff --git a/ros_kortex/third_party/gazebo-pkgs/LICENSE b/ros_kortex/third_party/gazebo-pkgs/LICENSE new file mode 100644 index 0000000..461daad --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/LICENSE @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2019, Jennifer Buehler +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/ros_kortex/third_party/gazebo-pkgs/README.md b/ros_kortex/third_party/gazebo-pkgs/README.md new file mode 100644 index 0000000..1bb2ba0 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/README.md @@ -0,0 +1,9 @@ +These ROS packages were cloned from https://github.com/JenniferBuehler/gazebo-pkgs into ros_kortex to properly simulate grasping in Gazebo for the Robotiq 2f 85 gripper. +The repository was cloned at commit e54939f6a80982dc1b89c3c2fb288e989f758b20. +The original readme file follows: + +# gazebo-pkgs + +A collection of tools and plugins for Gazebo. + +Please also refer to [the wiki](https://github.com/JenniferBuehler/gazebo-pkgs/wiki) for more information. diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CHANGELOG.rst b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CHANGELOG.rst new file mode 100644 index 0000000..c8c1009 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CHANGELOG.rst @@ -0,0 +1,19 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package gazebo_grasp_plugin +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.2 (2018-01-06) +------------------ +* Merge branch jacknlliu-fix-c11-error +* fix build error with c++ 11 +* Contributors: Jack Liu, Jennifer Buehler + +1.0.1 (2016-06-08) +------------------ +* Fixed cmake files for jenkins builds +* Contributors: Jennifer Buehler + +1.0.0 (2016-06-07) +------------------ +* Initial release +* Contributors: Jennifer Buehler diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CMakeLists.txt b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CMakeLists.txt new file mode 100644 index 0000000..a93a285 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/CMakeLists.txt @@ -0,0 +1,140 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gazebo_grasp_plugin) + +# This is added to remove policy CMP0054 warning (see https://stackoverflow.com/questions/45900159/how-to-use-variables-and-avoid-cmp0054-policy-violations) +cmake_policy(SET CMP0054 NEW) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + gazebo_ros + geometry_msgs + roscpp + std_msgs + gazebo_version_helpers +) + +find_package(gazebo REQUIRED) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES gazebo_grasp_fix + CATKIN_DEPENDS gazebo_ros geometry_msgs roscpp std_msgs gazebo_version_helpers + DEPENDS gazebo +) + +########### +## Build ## +########### +# check c++11 / c++0x +include(CheckCXXCompilerFlag) +CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "-std=c++11") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "-std=c++0x") +else() + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler. Suggested solution: update the pkg build-essential ") +endif() + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${GAZEBO_INCLUDE_DIRS} +) + +link_directories( + ${catkin_LIBRARY_DIRS} + ${GAZEBO_LIBRARY_DIRS} +) + +# Protobuf 2.6.1 includes were copied in kortex_gazebo/include and are necessary to build Gazebo plugins +include_directories(BEFORE ../../../kortex_gazebo/include/) +link_directories(BEFORE ../../../kortex_gazebo/lib/) + +## Declare a cpp library +add_library(gazebo_grasp_fix SHARED src/GazeboGraspFix.cpp src/GazeboGraspGripper.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(gazebo_grasp_plugin_node gazebo_grasp_plugin_generate_messages_cpp) +add_dependencies(gazebo_grasp_fix ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against + +target_link_libraries(gazebo_grasp_fix + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} + libprotobuf.so +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +install(TARGETS gazebo_grasp_fix + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(DIRECTORY launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + FILES_MATCHING PATTERN "*.launch" +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_gazebo_grasp_plugin.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspFix.h b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspFix.h new file mode 100644 index 0000000..b3e3ef3 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspFix.h @@ -0,0 +1,256 @@ +#ifndef GAZEBO_GAZEBOGRASPFIX_H +#define GAZEBO_GAZEBOGRASPFIX_H + +#include +#include +#include +#include +#include +#include +#include + +namespace gazebo +{ + +/** + * Inspired by gazebo::physics::Gripper, this plugin fixes an object which is grasped to the + * robot hand to avoid problems with physics engines and to help the object staying in + * the robot hand without slipping out. + * + * This is a *model* plugin, so you have to load the model plugin from the robot URDF: + * + * ```xml + * + * + * + * name-of-arm + * hand_link_name + * finger_index_link_1 + * finger_index_link_2 + * ... + * + * 100 + * 4 + * 4 + * 8 + * 0.005 + * false + * __default_topic__ + * + * + * ``` + * + * Description of the arguments: + * + * - ```` contains a collections of specification for each arm which can grasp one object (there may be several ```` tags): + * - ```` is the name of this arm. Has to be unique. + * - ```` has to be the link to which the finger joints are attached. + * - ```` tags have to include -all- link names of the gripper/hand which are used to + * actively grasp objects (these are the links which determine whether a "grasp" exists according to + * above described criterion). + * - ```` is the rate at which all contact points are checked against the "gripping criterion". + * Note that in-between such updates, existing contact points may be collected at + * a higher rate (the Gazebo world update rate). The ``update_rate`` is only the rate at + * which they are processed, which takes a bit of computation time, and therefore + * should be lower than the gazebo world update rate. + * - ```` is the tolerance angle (in degrees) between two force vectors to be considered + * "opposing forces". If the angle is smaller than this, they are not opposing. + * - ```` is number of times in the update loop (running at update_rate) that an object has + * to be detected as "gripped" in order to attach the object. + * Adjust this with the update rate. + * - ```` is the maximum number of a counter: + * At each update iteration (running at update_rate), if the "gripping criterion" is + * met for an object, a counter for this object is increased. ``max_grip_count`` is + * the maximum number recorded for an object. As soon as the counter goes beyond this + * number, the counter is stopped. As soon as the "gripping criterion" does not + * hold any more, the number will start to decrease again, (by 1 each time the object + * is detected as "not grasped" in an update iteration). So this counter is + * like a "buffer" which, when it is full, maintains the state, and when it is empty, + * again, the object is released. + * This should be at least double of ``grip_count_threshold``. + * - ```` is the distance which the gripper links are allowed to move away from the object + * during- a grasp without the object being detached, even if there are currently no + * actual contacts on the object. This condition can happen if the fingers "wobble" + * or move ever so slightly away from the object, and therefore the "gripping criterion" + * fails in a few subsequent update iterations. This setting is to make the behaviour more + * stable. + * Setting this number too high will also lead to the object not being detached even + * if the grippers have opened up to release it, so use this with care. + * - ```` can be used for the following: + * When an object is attached, collisions with it may be disabled, in case the + * robot still keeps wobbling. + * - ```` is the gazebo topic of contacts. Should normally be left at -\_\_default_topic\_\_-. + * + * Current limitations: + * + * - Only one object can be attached per gripper. + * - Only partial support for an object cannot be gripped with two grippers (release condition may be + * triggered wrongly, or not at all, if two grippers are involved) + * + * \author Jennifer Buehler + */ +class GazeboGraspFix : public ModelPlugin +{ + public: + GazeboGraspFix(); + GazeboGraspFix(physics::ModelPtr _model); + virtual ~GazeboGraspFix(); + + /** + * Gets called just after the object has been attached to the palm link on \e armName + */ + virtual void OnAttach(const std::string &objectName, + const std::string &armName) {} + /** + * Gets called just after the object has been detached to the palm link on \e armName + */ + virtual void OnDetach(const std::string &objectName, + const std::string &armName) {} + + private: + virtual void Init(); + virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf); + /** + * Collects for each object all forces which are currently applied on it. + * Then, for each object, checks whether of all the forces applied, + * there are opposing forces. + * This is done by calling CheckGrip() with the list of all forces applied. + * If CheckGrip() returns true, the number of "grip counts" + * is increased for the holding arm (but grip counts will never exceed \e max_grip_count). + * If the number of grip counts for this object exceeds \e grip_count_threshold, + * the object is attached by calling GazeboGraspGripper::HandleAttach(object-name), + * setting \e attached and \e attachedObjName, and \e GazeboGraspGripper::attachGripContacts + * is updated with the contact points currently existing for this object (current entry in \e contacts). + * + * Then, goes through all entries in \e gripCount, and unless it's an object + * we just detected as "gripped", the counter is decreased. + * If the counter is is smaller than \e grip_count_threshold, the object should + * potentially be released, but this criterion happens too easily + * (the fingers in gazebo may have started wobbling as the arm moves around, and although they are still + * close to the object, the grip is not detected any more). + * So to be sure, and additional criterion has to be satisfied before the object is released: + * check that the collision point (the place on the link where the contact originally + * was detected) has not moved too far from where it originally was, relative to the object. + */ + void OnUpdate(); + + void InitValues(); + + + /** + * Gets called upon detection of contacts. + * A list of contacts is passed in \_msg. One contact has two bodies, and only + * the ones where one of the bodies is a gripper link are considered. + * Each contact consists of a *list* of forces with their own origin/position each + * (e.g. when the object and gripper are colliding at several places). + * The averages of each contact's force vectors along with their origins is computed. + * This "average contact force/origin" for each contact is then added to the \e this->contacts map. + * If an entry for this object/link pair already exists, the average force (and its origin) + * is *added* to the existing force/origin, and the average count is increased. This is to get + * the average force application over time between link and object. + */ + void OnContact(const ConstContactsPtr &ptr); + +// bool CheckGrip(const std::vector &forces, float minAngleDiff, +// float lengthRatio); + + bool IsGripperLink(const std::string &linkName, std::string &gripperName) const; + + /** + * return objects (key) and the gripper (value) to which it is attached + */ + std::map GetAttachedObjects() const; + + /** + * Helper class to collect contact info per object. + * Forward declaration here. + */ + class ObjectContactInfo; + + /** + * Helper function to determine if object attached to a gripper in ObjectContactInfo. + */ + bool ObjectAttachedToGripper(const ObjectContactInfo &objContInfo, + std::string &attachedToGripper) const; + + /** + * Helper function to determine if object attached to this gripper + */ + bool ObjectAttachedToGripper(const std::string &gripperName, + std::string &attachedToGripper) const; + + + // physics::ModelPtr model; + // physics::PhysicsEnginePtr physics; + physics::WorldPtr world; + + // sorted by their name, all grippers of the robot + std::map grippers; + + event::ConnectionPtr update_connection; + transport::NodePtr node; + transport::SubscriberPtr contactSub; //subscriber to contact updates + + // tolerance (in degrees) between force vectors to + // beconsidered "opposing" + float forcesAngleTolerance; + + // when an object is attached, collisions with it may be disabled, in case the + // robot still keeps wobbling. + bool disableCollisionsOnAttach; + + // all collisions per gazebo collision link (each entry + // belongs to a physics::CollisionPtr element). The key + // is the collision link name, the value is the gripper name + // this collision link belongs to. + std::map collisions; + + + /** + * Helper class to encapsulate a collision information. Forward declaration here. + */ + class CollidingPoint; + + // Contact forces sorted by object name the gripper collides with (first key) + // and the link colliding (second key). + std::map > contacts; + boost::mutex mutexContacts; //mutex protects contacts + + // when an object was first attached, it had these colliding points. + // First key is object name, second is the link colliding, as in \e contacts. + // Only the links of *one* gripper are stored here. This indirectly imposes the + // limitation that no two grippers can grasp the object (while it would be + // possible, the release condition is tied to only one link, so the object may + // not be released properly). + std::map > + attachGripContacts; + + + // Records how many subsequent update calls the grip on that object has been recorded + // as "holding". Every loop, if a grip is not recorded, this number decreases. + // When it reaches \e grip_count_threshold, it will be attached. + // The number won't increase above max_grip_count once it has reached that number. + std::map gripCounts; + + // *maximum* number in \e gripCounts to be recorded. + int maxGripCount; + + // number of recorded "grips" in the past (in gripCount) which, when it is exceeded, counts + // as the object grasped, and when it is lower, as released. + int gripCountThreshold; + + // once an object is gripped, the relative position of the collision link surface to the + // object is remembered. As soon as this distance changes more than release_tolerance, + // the object is released. + float releaseTolerance; + + //nano seconds between two updates + common::Time updateRate; + + //last time OnUpdate() was called + common::Time prevUpdateTime; +}; + +} + +#endif // GAZEBO_GAZEBOGRASPFIX_H diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspGripper.h b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspGripper.h new file mode 100644 index 0000000..f8fdbb1 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspGripper.h @@ -0,0 +1,89 @@ +#ifndef GAZEBO_GAZEBOGRASPGRIPPER_H +#define GAZEBO_GAZEBOGRASPGRIPPER_H + +#include +#include +#include +#include +#include +#include + +namespace gazebo +{ + +/** + * \brief Helper class for GazeboGraspFix which holds information for one arm. + * Attaches /detaches objects to the palm of this arm. + * + * \author Jennifer Buehler + */ +class GazeboGraspGripper +{ + public: + GazeboGraspGripper(); + GazeboGraspGripper(const GazeboGraspGripper &o); + virtual ~GazeboGraspGripper(); + + /** + * + * \param disableCollisionsOnAttach when an object is attached, collisions with it will be disabled. This is useful + * if the robot then still keeps wobbling. + */ + bool Init(physics::ModelPtr &_model, + const std::string &_gripperName, + const std::string &palmLinkName, + const std::vector &fingerLinkNames, + bool _disableCollisionsOnAttach, + std::map &_collisions); + + const std::string &getGripperName() const; + + /** + * Has the link name (URDF) + */ + bool hasLink(const std::string &linkName) const; + + /** + * Has the collision link name (Gazebo collision element name) + */ + bool hasCollisionLink(const std::string &linkName) const; + + bool isObjectAttached() const; + + const std::string &attachedObject() const; + + /** + * \param gripContacts contact forces on the object sorted by the link name colliding. + */ + bool HandleAttach(const std::string &objName); + void HandleDetach(const std::string &objName); + + private: + + physics::ModelPtr model; + + // name of the gripper + std::string gripperName; + + // names of the gripper links + std::vector linkNames; + // names and Collision objects of the collision links in Gazebo (scoped names) + // Not necessarily equal names and size to linkNames. + std::map collisionElems; + + physics::JointPtr fixedJoint; + + physics::LinkPtr palmLink; + + // when an object is attached, collisions with it may be disabled, in case the + // robot still keeps wobbling. + bool disableCollisionsOnAttach; + + // flag holding whether an object is attached. Object name in \e attachedObjName + bool attached; + // name of the object currently attached. + std::string attachedObjName; +}; + +} +#endif // GAZEBO_GAZEBOGRASPGRIPPER_H diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/package.xml b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/package.xml new file mode 100644 index 0000000..5924275 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/package.xml @@ -0,0 +1,51 @@ + + + gazebo_grasp_plugin + 1.0.2 + + Gazebo Model plugin(s) which handle/help grasping in Gazebo. + + + + Jennifer Buehler + + + + + + GPLv3 + + + + + + + + + + Jennifer Buehler + + + + + catkin + gazebo_ros + gazebo + geometry_msgs + roscpp + std_msgs + gazebo_version_helpers + gazebo_ros + gazebo + geometry_msgs + roscpp + std_msgs + gazebo_version_helpers + + + + + + + + diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspFix.cpp b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspFix.cpp new file mode 100644 index 0000000..5162d5c --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspFix.cpp @@ -0,0 +1,948 @@ +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using gazebo::GazeboGraspFix; +using gazebo::GzVector3; + +#define DEFAULT_FORCES_ANGLE_TOLERANCE 120 +#define DEFAULT_UPDATE_RATE 5 +#define DEFAULT_MAX_GRIP_COUNT 10 +#define DEFAULT_RELEASE_TOLERANCE 0.005 +#define DEFAULT_DISABLE_COLLISIONS_ON_ATTACH false + +// Register this plugin with the simulator +GZ_REGISTER_MODEL_PLUGIN(GazeboGraspFix) + +//////////////////////////////////////////////////////////////////////////////// +GazeboGraspFix::GazeboGraspFix() +{ + InitValues(); +} + +//////////////////////////////////////////////////////////////////////////////// +GazeboGraspFix::GazeboGraspFix(physics::ModelPtr _model) +{ + InitValues(); +} + +//////////////////////////////////////////////////////////////////////////////// +GazeboGraspFix::~GazeboGraspFix() +{ + this->update_connection.reset(); + if (this->node) this->node->Fini(); + this->node.reset(); +} + +//////////////////////////////////////////////////////////////////////////////// +void GazeboGraspFix::Init() +{ + this->prevUpdateTime = common::Time::GetWallTime(); +} + +//////////////////////////////////////////////////////////////////////////////// +void GazeboGraspFix::InitValues() +{ +#if GAZEBO_MAJOR_VERSION > 2 + gazebo::common::Console::SetQuiet(false); +#endif + + // float timeDiff=0.25; + // this->releaseTolerance=0.005; + // this->updateRate = common::Time(0, common::Time::SecToNano(timeDiff)); + this->prevUpdateTime = common::Time::GetWallTime(); + //float graspedSecs=2; + //this->maxGripCount=floor(graspedSecs/timeDiff); + //this->gripCountThreshold=floor(this->maxGripCount/2); + this->node = transport::NodePtr(new transport::Node()); +} + +//////////////////////////////////////////////////////////////////////////////// +void GazeboGraspFix::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) +{ + gzmsg << "Loading grasp-fix plugin" << std::endl; + + // ++++++++++++ Read parameters and initialize fields +++++++++++++++ + + physics::ModelPtr model = _parent; + this->world = model->GetWorld(); + + sdf::ElementPtr disableCollisionsOnAttachElem = + _sdf->GetElement("disable_collisions_on_attach"); + if (!disableCollisionsOnAttachElem) + { + gzmsg << "GazeboGraspFix: Using default " << + DEFAULT_DISABLE_COLLISIONS_ON_ATTACH << + " because no element specified." << + std::endl; + this->disableCollisionsOnAttach = DEFAULT_DISABLE_COLLISIONS_ON_ATTACH; + } + else + { + std::string str = disableCollisionsOnAttachElem->Get(); + bool bVal = false; + if ((str == "true") || (str == "1")) bVal = true; + this->disableCollisionsOnAttach = bVal; + gzmsg << "GazeboGraspFix: Using disable_collisions_on_attach " << + this->disableCollisionsOnAttach << std::endl; + } + + sdf::ElementPtr forcesAngleToleranceElem = + _sdf->GetElement("forces_angle_tolerance"); + if (!forcesAngleToleranceElem) + { + gzmsg << "GazeboGraspFix: Using default tolerance of " << + DEFAULT_FORCES_ANGLE_TOLERANCE << + " because no element specified." << + std::endl; + this->forcesAngleTolerance = DEFAULT_FORCES_ANGLE_TOLERANCE * M_PI / 180; + } + else + { + this->forcesAngleTolerance = + forcesAngleToleranceElem->Get() * M_PI / 180; + } + + sdf::ElementPtr updateRateElem = _sdf->GetElement("update_rate"); + double _updateSecs; + if (!updateRateElem) + { + gzmsg << "GazeboGraspFix: Using " << DEFAULT_UPDATE_RATE << + " because no element specified." << std::endl; + _updateSecs = 1.0 / DEFAULT_UPDATE_RATE; + } + else + { + int _rate = updateRateElem->Get(); + double _updateRate = _rate; + _updateSecs = 1.0 / _updateRate; + gzmsg << "GazeboGraspFix: Using update rate " << _rate << std::endl; + } + this->updateRate = common::Time(0, common::Time::SecToNano(_updateSecs)); + + sdf::ElementPtr maxGripCountElem = _sdf->GetElement("max_grip_count"); + if (!maxGripCountElem) + { + gzmsg << "GazeboGraspFix: Using " << DEFAULT_MAX_GRIP_COUNT << + " because no element specified." << std::endl; + this->maxGripCount = DEFAULT_MAX_GRIP_COUNT; + } + else + { + this->maxGripCount = maxGripCountElem->Get(); + gzmsg << "GazeboGraspFix: Using max_grip_count " + << this->maxGripCount << std::endl; + } + + sdf::ElementPtr gripCountThresholdElem = + _sdf->GetElement("grip_count_threshold"); + if (!gripCountThresholdElem) + { + this->gripCountThreshold = floor(this->maxGripCount / 2.0); + gzmsg << "GazeboGraspFix: Using " << this->gripCountThreshold << + " because no element specified." << + std::endl; + } + else + { + this->gripCountThreshold = gripCountThresholdElem->Get(); + gzmsg << "GazeboGraspFix: Using grip_count_threshold " << + this->gripCountThreshold << std::endl; + } + + sdf::ElementPtr releaseToleranceElem = _sdf->GetElement("release_tolerance"); + if (!releaseToleranceElem) + { + gzmsg << "GazeboGraspFix: Using " << DEFAULT_RELEASE_TOLERANCE << + " because no element specified." << std::endl; + this->releaseTolerance = DEFAULT_RELEASE_TOLERANCE; + } + else + { + this->releaseTolerance = releaseToleranceElem->Get(); + gzmsg << "GazeboGraspFix: Using release_tolerance " << + this->releaseTolerance << std::endl; + } + + // will contain all names of collision entities involved from all arms + std::vector collisionNames; + + sdf::ElementPtr armElem = _sdf->GetElement("arm"); + if (!armElem) + { + gzerr << "GazeboGraspFix: Cannot load the GazeboGraspFix without any declarations" + << std::endl; + return; + } + // add all arms: + for (; armElem != NULL; armElem = armElem->GetNextElement("arm")) + { + sdf::ElementPtr armNameElem = armElem->GetElement("arm_name"); + sdf::ElementPtr handLinkElem = armElem->GetElement("palm_link"); + sdf::ElementPtr fingerLinkElem = armElem->GetElement("gripper_link"); + + if (!handLinkElem || !fingerLinkElem || !armNameElem) + { + gzerr << "ERROR: GazeboGraspFix: Cannot use a GazeboGraspFix arm because " + << "not all of , and elements specified in URDF/SDF. Skipping." + << std::endl; + continue; + } + + std::string armName = armNameElem->Get(); + std::string palmName = handLinkElem->Get(); + + // collect all finger names: + std::vector fingerLinkNames; + for (; fingerLinkElem != NULL; + fingerLinkElem = fingerLinkElem->GetNextElement("gripper_link")) + { + std::string linkName = fingerLinkElem->Get(); + fingerLinkNames.push_back(linkName); + } + + // add new gripper + if (grippers.find(armName) != grippers.end()) + { + gzerr << "GazeboGraspFix: Arm named " << armName << + " was already added, cannot add it twice." << std::endl; + } + GazeboGraspGripper &gripper = grippers[armName]; + std::map _collisions; + if (!gripper.Init(_parent, armName, palmName, fingerLinkNames, + disableCollisionsOnAttach, _collisions)) + { + gzerr << "GazeboGraspFix: Could not initialize arm " << armName << ". Skipping." + << std::endl; + grippers.erase(armName); + continue; + } + // add all the grippers's collision elements + for (std::map::iterator collIt = + _collisions.begin(); + collIt != _collisions.end(); ++collIt) + { + const std::string &collName = collIt->first; + //physics::CollisionPtr& coll=collIt->second; + std::map::iterator collIter = this->collisions.find( + collName); + if (collIter != + this->collisions.end()) //this collision was already added before + { + gzwarn << "GazeboGraspFix: Adding Gazebo collision link element " << collName << + " multiple times, the grasp plugin may not work properly" << std::endl; + continue; + } + gzmsg << "GazeboGraspFix: Adding collision scoped name " << collName << + std::endl; + this->collisions[collName] = armName; + collisionNames.push_back(collName); + } + } + + if (grippers.empty()) + { + gzerr << "ERROR: GazeboGraspFix: Cannot use a GazeboGraspFix because " + << "no arms were configured successfully. Plugin will not work." << std::endl; + return; + } + + // ++++++++++++ start up things +++++++++++++++ + + physics::PhysicsEnginePtr physics = GetPhysics(this->world); + this->node->Init(gazebo::GetName(*(this->world))); + physics::ContactManager *contactManager = physics->GetContactManager(); + contactManager->PublishContacts(); // TODO not sure this is required? + + std::string topic = contactManager->CreateFilter(model->GetScopedName(), + collisionNames); + if (!this->contactSub) + { + gzmsg << "Subscribing contact manager to topic " << topic << std::endl; + bool latching = false; + this->contactSub = this->node->Subscribe(topic, &GazeboGraspFix::OnContact, + this, latching); + } + + update_connection = event::Events::ConnectWorldUpdateEnd(boost::bind( + &GazeboGraspFix::OnUpdate, this)); +} + +//////////////////////////////////////////////////////////////////////////////// +class GazeboGraspFix::ObjectContactInfo +{ + public: + + // all forces effecting on the object + std::vector appliedForces; + + // all grippers involved in the process, along with + // a number counting the number of contact points with the + // object per gripper + std::map grippersInvolved; + + // maximum number of contacts of *any one* gripper + // (any in grippersInvolved) + int maxGripperContactCnt; + + // the gripper for maxGripperContactCnt + std::string maxContactGripper; +}; + +//////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspFix::IsGripperLink(const std::string &linkName, + std::string &gripperName) const +{ + for (std::map::const_iterator it = + grippers.begin(); it != grippers.end(); ++it) + { + if (it->second.hasLink(linkName)) + { + gripperName = it->first; + return true; + } + } + return false; +} + +//////////////////////////////////////////////////////////////////////////////// +std::map GazeboGraspFix::GetAttachedObjects() const +{ + std::map ret; + for (std::map::const_iterator it = + grippers.begin(); it != grippers.end(); ++it) + { + const std::string &gripperName = it->first; + const GazeboGraspGripper &gripper = it->second; + if (gripper.isObjectAttached()) + { + ret[gripper.attachedObject()] = gripperName; + } + } + return ret; +} + +//////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspFix::ObjectAttachedToGripper(const ObjectContactInfo + &objContInfo, std::string &attachedToGripper) const +{ + for (std::map::const_iterator gripInvIt = + objContInfo.grippersInvolved.begin(); + gripInvIt != objContInfo.grippersInvolved.end(); ++gripInvIt) + { + const std::string &gripperName = gripInvIt->first; + if (ObjectAttachedToGripper(gripperName, attachedToGripper)) + { + return true; + } + } + return false; +} + +//////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspFix::ObjectAttachedToGripper(const std::string &gripperName, + std::string &attachedToGripper) const +{ + std::map::const_iterator gIt = grippers.find( + gripperName); + if (gIt == grippers.end()) + { + gzerr << "GazeboGraspFix: Inconsistency, gripper " << gripperName << + " not found in GazeboGraspFix grippers" << std::endl; + return false; + } + const GazeboGraspGripper &gripper = gIt->second; + // gzmsg<<"Gripper "< &forces, + float minAngleDiff, float lengthRatio) +{ + if (((lengthRatio > 1) || (lengthRatio < 0)) && (lengthRatio > 1e-04 + && (fabs(lengthRatio - 1) > 1e-04))) + { + std::cerr << "ERROR: CheckGrip: always specify a lengthRatio of [0..1]" << + std::endl; + return false; + } + if (minAngleDiff < M_PI_2) + { + std::cerr << "ERROR: CheckGrip: min angle must be at least 90 degrees (PI/2)" << + std::endl; + return false; + } + std::vector::const_iterator it1, it2; + for (it1 = forces.begin(); it1 != forces.end(); ++it1) + { + GzVector3 v1 = *it1; + for (it2 = it1 + 1; it2 != forces.end(); ++it2) + { + GzVector3 v2 = *it2; + float l1 = gazebo::GetLength(v1); + float l2 = gazebo::GetLength(v2); + if ((l1 < 1e-04) || (l2 < 1e-04)) continue; + /*GzVector3 _v1=v1; + GzVector3 _v2=v2; + _v1/=l1; + _v2/=l2; + float angle=acos(_v1.Dot(_v2));*/ + float angle = AngularDistance(v1, v2); + // gzmsg<<"Angular distance between v1.len="< minAngleDiff) + { + float ratio; + if (l1 > l2) ratio = l2 / l1; + else ratio = l1 / l2; + // gzmsg<<"Got angle "<= lengthRatio) + { + // gzmsg<<"CheckGrip() is true"<prevUpdateTime) < this->updateRate) + return; + + // first, copy all contact data into local struct. Don't do the complex grip check (CheckGrip) + // within the mutex, because that slows down OnContact(). + this->mutexContacts.lock(); + std::map > contPoints( + this->contacts); + this->contacts.clear(); // clear so it can be filled anew by OnContact(). + this->mutexContacts.unlock(); + + // contPoints now contains CollidingPoint objects for each *object* and *link*. + + // Iterate through all contact points to gather all summed forces + // (and other useful information) for all the objects (so we have all forces on one object). + std::map >::iterator objIt; + std::map objectContactInfo; + + for (objIt = contPoints.begin(); objIt != contPoints.end(); ++objIt) + { + std::string objName = objIt->first; + //gzmsg<<"Examining object collisions with "<::iterator lIt; + for (lIt = objIt->second.begin(); lIt != objIt->second.end(); ++lIt) + { + std::string linkName = lIt->first; + CollidingPoint &collP = lIt->second; + GzVector3 avgForce = collP.force / collP.sum; + // gzmsg << "Found collision with "< _maxGripperContactCnt) + { + _maxGripperContactCnt = gContactCnt; + objContInfo.maxContactGripper = collP.gripperName; + } + } + } + + // ++++++++++++++++++++ Handle Attachment +++++++++++++++++++++++++++++++ + + // collect of all objects which are found to be "gripped" at the current stage. + // if they are gripped, increase the grip counter. If the grip count exceeds the + // threshold, attach the object to the gripper which has most contact points with the + // object. + std::set grippedObjects; + for (std::map::iterator ocIt = + objectContactInfo.begin(); + ocIt != objectContactInfo.end(); ++ocIt) + { + const std::string &objName = ocIt->first; + const ObjectContactInfo &objContInfo = ocIt->second; + + // gzmsg<<"Number applied forces on "<(GetEntityByName(world, objName)); + if (objColl && objColl->GetLink()) + { + auto linVel = GetWorldVelocity(objColl->GetLink()); + gzmsg << "Velocity for link " << objColl->GetLink()->GetName() + << " (collision name " << objName << "): " << linVel + << ", absolute val " << GetLength(linVel) << std::endl; + } +#endif + // ------------------- + + float minAngleDiff = this->forcesAngleTolerance; //120 * M_PI/180; + if (!CheckGrip(objContInfo.appliedForces, minAngleDiff, 0.3)) + continue; + + // add to "gripped objects" + grippedObjects.insert(objName); + + //gzmsg<<"Grasp Held: "<gripCounts[objName]<gripCounts[objName]; + if (counts < this->maxGripCount) ++counts; + + // only need to attach object if the grip count threshold is exceeded + if (counts <= this->gripCountThreshold) + continue; + + //gzmsg<<"GRIPPING "<gripCountThreshold<<")"<::iterator gIt = grippers.find( + graspingGripperName); + if (gIt == grippers.end()) + { + gzerr << "GazeboGraspFix: Inconsistency, gripper '" << graspingGripperName + << "' not found in GazeboGraspFix grippers, so cannot do attachment of object " + << objName << std::endl; + continue; + } + GazeboGraspGripper &graspingGripper = gIt->second; + + if (graspingGripper.isObjectAttached()) + { + gzerr << "GazeboGraspFix has found that object " << + graspingGripper.attachedObject() << " is already attached to gripper " << + graspingGripperName << ", so can't grasp '" << objName << "'!" << std::endl; + continue; + } + + gzmsg << "GazeboGraspFix: Attaching " << objName << " to gripper " << + graspingGripperName << "." << std::endl; + + // Store the array of contact poses which played part in the grip, sorted by colliding link. + // Filter out all link names of other grippers, otherwise if the other gripper moves + // away, this is going to trigger the release condition. + // XXX this does not consider full support for an object being gripped by two grippers (e.g. + // one left, one right). + // this->attachGripContacts[objName]=contPoints[objName]; + const std::map &contPointsTmp = + contPoints[objName]; + std::map &attGripConts = + this->attachGripContacts[objName]; + attGripConts.clear(); + std::map::const_iterator contPointsIt; + for (contPointsIt = contPointsTmp.begin(); contPointsIt != contPointsTmp.end(); + ++contPointsIt) + { + const std::string &collidingLink = contPointsIt->first; + const CollidingPoint &collidingPoint = contPointsIt->second; + // gzmsg<<"Checking initial contact with "<OnAttach(objName, graspingGripperName); + } // for all objects + + + + // ++++++++++++++++++++ Handle Detachment +++++++++++++++++++++++++++++++ + std::map attachedObjects = GetAttachedObjects(); + + // now, for all objects that are not currently gripped, + // decrease grip counter, and possibly release object. + std::map::iterator gripCntIt; + for (gripCntIt = this->gripCounts.begin(); gripCntIt != this->gripCounts.end(); + ++gripCntIt) + { + + const std::string &objName = gripCntIt->first; + + if (grippedObjects.find(objName) != grippedObjects.end()) + { + // this object is one we just detected as "gripped", so no need to check for releasing it... + // gzmsg<<"NOT considering "<second<<" (threshold "<gripCountThreshold<<")"<second > 0) --(gripCntIt->second); + + std::map::iterator attIt = attachedObjects.find( + objName); + bool isAttached = (attIt != attachedObjects.end()); + + // gzmsg<<"is attached: "<second > this->gripCountThreshold)) continue; + + const std::string &graspingGripperName = attIt->second; + + // gzmsg<<"Considering "< >::iterator + initCollIt = this->attachGripContacts.find(objName); + if (initCollIt == this->attachGripContacts.end()) + { + std::cerr << "ERROR: Consistency: Could not find attachGripContacts for " << + objName << std::endl; + continue; + } + + std::map &initColls = initCollIt->second; + int cntRelease = 0; + + // for all links which have initially been detected to collide: + std::map::iterator pointIt; + for (pointIt = initColls.begin(); pointIt != initColls.end(); ++pointIt) + { + CollidingPoint &cpInfo = pointIt->second; + // initial distance from link to contact point (relative to link) + GzVector3 relContactPos = cpInfo.pos / cpInfo.sum; + // Initial distance from link to object (relative to link) + GzVector3 relObjPos = cpInfo.objPos / cpInfo.sum; + + // Get current world pose of object + GzPose3 currObjWorldPose = + gazebo::GetWorldPose(cpInfo.collObj->GetLink()); + + // Get world pose of link + GzPose3 currLinkWorldPose = + gazebo::GetWorldPose(cpInfo.collLink->GetLink()); + + // Get transform for currLinkWorldPose as matrix + GzMatrix4 worldToLink = gazebo::GetMatrix(currLinkWorldPose); + + // Get the transform from collision link to contact point + GzMatrix4 linkToContact = gazebo::GetMatrix(relContactPos); + + // The current world position of the contact point right now is: + GzMatrix4 _currContactWorldPose = worldToLink * linkToContact; + GzVector3 currContactWorldPose = gazebo::GetPos(_currContactWorldPose); + + // The initial contact point location on the link should still correspond + // to the initial contact point location on the object. + + // Initial vector from object center to contact point (relative to link, + // because relObjPos and relContactPos are from center of link) + GzVector3 oldObjDist = relContactPos - relObjPos; + // The same vector as \e oldObjDist, but calculated by the current world pose + // of object and the current location of the initial contact location on the link. + // This is the new distance from contact to object. + GzVector3 newObjDist = currContactWorldPose - gazebo::GetPos(currObjWorldPose); + + //gzmsg<<"Obj Trans "<GetName()<<": "<GetName()<<": "<GetName()<<": "< releaseTolerance) + { + ++cntRelease; + } + } + + if (cntRelease > 0) + { + // sufficient links did not meet the criteria to be close enough to the object. + // First, get the grasping gripper: + std::map::iterator gggIt = grippers.find( + graspingGripperName); + if (gggIt == grippers.end()) + { + gzerr << "GazeboGraspFix: Inconsistency: Gazebo gripper '" << + graspingGripperName << "' not found when checking for detachment" << std::endl; + continue; + } + GazeboGraspGripper &graspingGripper = gggIt->second; + // Now, detach the object: + gzmsg << "GazeboGraspFix: Detaching " << objName << " from gripper " << + graspingGripperName << "." << std::endl; + graspingGripper.HandleDetach(objName); + this->OnDetach(objName, graspingGripperName); + gripCntIt->second = 0; + this->attachGripContacts.erase(initCollIt); + } + } + + this->prevUpdateTime = common::Time::GetWallTime(); +} + +//////////////////////////////////////////////////////////////////////////////// +void GazeboGraspFix::OnContact(const ConstContactsPtr &_msg) +{ + //gzmsg<<"CONTACT! "<contact_size(); ++i) + { + physics::CollisionPtr collision1 = + boost::dynamic_pointer_cast( + gazebo::GetEntityByName(this->world, _msg->contact(i).collision1())); + physics::CollisionPtr collision2 = + boost::dynamic_pointer_cast( + gazebo::GetEntityByName(this->world, _msg->contact(i).collision2())); + + if ((collision1 && !collision1->IsStatic()) && (collision2 + && !collision2->IsStatic())) + { + std::string name1 = collision1->GetScopedName(); + std::string name2 = collision2->GetScopedName(); + + //gzmsg<<"OBJ CONTACT! "<contact(i).position_size(); + + // Check to see if the contact arrays all have the same size. + if ((count != _msg->contact(i).normal_size()) || + (count != _msg->contact(i).wrench_size()) || + (count != _msg->contact(i).depth_size())) + { + gzerr << "GazeboGraspFix: Contact message has invalid array sizes\n" << + std::endl; + continue; + } + + std::string collidingObjName, collidingLink, gripperOfCollidingLink; + physics::CollisionPtr linkCollision; + physics::CollisionPtr objCollision; + + physics::Contact contact; + contact = _msg->contact(i); + + if (contact.count < 1) + { + std::cerr << "ERROR: GazeboGraspFix: Not enough forces given for contact of ." + << name1 << " / " << name2 << std::endl; + continue; + } + + // all force vectors which are part of this contact + std::vector force; + + // find out which part of the colliding entities is the object, *not* the gripper, + // and copy all the forces applied to it into the vector 'force'. + std::map::const_iterator gripperCollIt = + this->collisions.find(name2); + if (gripperCollIt != this->collisions.end()) + { + // collision 1 is the object + collidingObjName = name1; + collidingLink = name2; + linkCollision = collision2; + objCollision = collision1; + gripperOfCollidingLink = gripperCollIt->second; + for (int k = 0; k < contact.count; ++k) + force.push_back(contact.wrench[k].body1Force); + } + else if ((gripperCollIt = this->collisions.find(name1)) != + this->collisions.end()) + { + // collision 2 is the object + collidingObjName = name2; + collidingLink = name1; + linkCollision = collision1; + objCollision = collision2; + gripperOfCollidingLink = gripperCollIt->second; + for (int k = 0; k < contact.count; ++k) + force.push_back(contact.wrench[k].body2Force); + } + + GzVector3 avgForce; + // compute average/sum of the forces applied on the object + for (int k = 0; k < force.size(); ++k) + { + avgForce += force[k]; + } + avgForce /= force.size(); + + GzVector3 avgPos; + // compute center point (average pose) of all the origin positions of the forces appied + for (int k = 0; k < contact.count; ++k) avgPos += contact.positions[k]; + avgPos /= contact.count; + + // now, get average pose relative to the colliding link + GzPose3 linkWorldPose = gazebo::GetWorldPose(linkCollision->GetLink()); + + // To find out the collision point relative to the Link's local coordinate system, first get the Poses as 4x4 matrices + GzMatrix4 worldToLink = gazebo::GetMatrix(linkWorldPose); + + // We can assume that the contact has identity rotation because we don't care about its orientation. + // We could always set another rotation here too. + GzMatrix4 worldToContact = gazebo::GetMatrix(avgPos); + + // now, worldToLink * contactInLocal = worldToContact + // hence, contactInLocal = worldToLink.Inv * worldToContact + GzMatrix4 worldToLinkInv = worldToLink.Inverse(); + GzMatrix4 contactInLocal = worldToLinkInv * worldToContact; + GzVector3 contactPosInLocal = gazebo::GetPos(contactInLocal); + + //gzmsg<<"---------"<GetLink()); + GzMatrix4 worldToObj = gazebo::GetMatrix(objWorldPose); + + GzMatrix4 objInLocal = worldToLinkInv * worldToObj; + GzVector3 objPosInLocal = gazebo::GetPos(objInLocal); + + { + boost::mutex::scoped_lock lock(this->mutexContacts); + CollidingPoint &p = + this->contacts[collidingObjName][collidingLink]; // inserts new entry if doesn't exist + p.gripperName = gripperOfCollidingLink; + p.collLink = linkCollision; + p.collObj = objCollision; + p.force += avgForce; + p.pos += contactPosInLocal; + p.objPos += objPosInLocal; + p.sum++; + } + //gzmsg<<"Average force of contact= "< +#include +#include +#include +#include +#include +#include + +#include +#include + +using gazebo::GazeboGraspGripper; + +#define DEFAULT_FORCES_ANGLE_TOLERANCE 120 +#define DEFAULT_UPDATE_RATE 5 +#define DEFAULT_MAX_GRIP_COUNT 10 +#define DEFAULT_RELEASE_TOLERANCE 0.005 +#define DEFAULT_DISABLE_COLLISIONS_ON_ATTACH false + +/////////////////////////////////////////////////////////////////////////////// +GazeboGraspGripper::GazeboGraspGripper(): + attached(false) +{ +} + +/////////////////////////////////////////////////////////////////////////////// +GazeboGraspGripper::GazeboGraspGripper(const GazeboGraspGripper &o): + model(o.model), + gripperName(o.gripperName), + linkNames(o.linkNames), + collisionElems(o.collisionElems), + fixedJoint(o.fixedJoint), + palmLink(o.palmLink), + disableCollisionsOnAttach(o.disableCollisionsOnAttach), + attached(o.attached), + attachedObjName(o.attachedObjName) +{} + +/////////////////////////////////////////////////////////////////////////////// +GazeboGraspGripper::~GazeboGraspGripper() +{ + this->model.reset(); +} + +/////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspGripper::Init(physics::ModelPtr &_model, + const std::string &_gripperName, + const std::string &palmLinkName, + const std::vector &fingerLinkNames, + bool _disableCollisionsOnAttach, + std::map &_collisionElems) +{ + this->gripperName = _gripperName; + this->attached = false; + this->disableCollisionsOnAttach = _disableCollisionsOnAttach; + this->model = _model; + physics::PhysicsEnginePtr physics = + gazebo::GetPhysics(this->model->GetWorld()); + this->fixedJoint = physics->CreateJoint("revolute"); + + this->palmLink = this->model->GetLink(palmLinkName); + if (!this->palmLink) + { + gzerr << "GazeboGraspGripper: Palm link " << palmLinkName << + " not found. The gazebo grasp plugin will not work." << std::endl; + return false; + } + for (std::vector::const_iterator fingerIt = + fingerLinkNames.begin(); + fingerIt != fingerLinkNames.end(); ++fingerIt) + { + physics::LinkPtr link = this->model->GetLink(*fingerIt); + //gzmsg<<"Got link "<Get()<GetChildCount(); ++j) + { + physics::CollisionPtr collision = link->GetCollision(j); + std::string collName = collision->GetScopedName(); + //collision->SetContactsEnabled(true); + std::map::iterator collIter = + collisionElems.find(collName); + if (collIter != + this->collisionElems.end()) //this collision was already added before + { + gzwarn << "GazeboGraspGripper: Adding Gazebo collision link element " << + collName << " multiple times, the gazebo grasp handler may not work properly" << + std::endl; + continue; + } + this->collisionElems[collName] = collision; + _collisionElems[collName] = collision; + } + } + return !this->collisionElems.empty(); +} + +/////////////////////////////////////////////////////////////////////////////// +const std::string &GazeboGraspGripper::getGripperName() const +{ + return gripperName; +} + +/////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspGripper::hasLink(const std::string &linkName) const +{ + for (std::vector::const_iterator it = linkNames.begin(); + it != linkNames.end(); ++it) + { + if (*it == linkName) return true; + } + return false; +} + +/////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspGripper::hasCollisionLink(const std::string &linkName) const +{ + return collisionElems.find(linkName) != collisionElems.end(); +} + + +/////////////////////////////////////////////////////////////////////////////// +bool GazeboGraspGripper::isObjectAttached() const +{ + return attached; +} + +/////////////////////////////////////////////////////////////////////////////// +const std::string &GazeboGraspGripper::attachedObject() const +{ + return attachedObjName; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// #define USE_MODEL_ATTACH // this only works if the object is a model in itself, which is usually not +// the case. Leaving this in here anyway for documentation of what has been +// tried, and for and later re-evaluation. +bool GazeboGraspGripper::HandleAttach(const std::string &objName) +{ + if (!this->palmLink) + { + gzwarn << "GazeboGraspGripper: palm link not found, not enforcing grasp hack!\n" + << std::endl; + return false; + } + physics::WorldPtr world = this->model->GetWorld(); + if (!world.get()) + { + gzerr << "GazeboGraspGripper: world is NULL" << std::endl; + return false; + } +#ifdef USE_MODEL_ATTACH + physics::ModelPtr obj = world->GetModel(objName); + if (!obj.get()) + { + std::cerr << "ERROR: Object ModelPtr " << objName << + " not found in world, can't attach it" << std::endl; + return false; + } + gazebo::math::Pose diff = obj->GetLink()->GetWorldPose() - + this->palmLink->GetWorldPose(); + this->palmLink->AttachStaticModel(obj, diff); +#else + physics::CollisionPtr obj = + boost::dynamic_pointer_cast(gazebo::GetEntityByName(world, objName)); + if (!obj.get()) + { + std::cerr << "ERROR: Object " << objName << + " not found in world, can't attach it" << std::endl; + return false; + } + gazebo::GzPose3 diff = gazebo::GetWorldPose(obj->GetLink()) - + gazebo::GetWorldPose(this->palmLink); + this->fixedJoint->Load(this->palmLink, obj->GetLink(), diff); + this->fixedJoint->Init(); +#if GAZEBO_MAJOR_VERSION >= 8 + this->fixedJoint->SetUpperLimit(0, 0); + this->fixedJoint->SetLowerLimit(0, 0); +#else + this->fixedJoint->SetHighStop(0, 0); + this->fixedJoint->SetLowStop(0, 0); +#endif + + if (this->disableCollisionsOnAttach) + { + // we can disable collisions of the grasped object, because when the fingers keep colliding with + // it, the fingers keep wobbling, which can create difficulties when moving the arm. + obj->GetLink()->SetCollideMode("none"); + } +#endif // USE_MODEL_ATTACH + this->attached = true; + this->attachedObjName = objName; + return true; +} + +/////////////////////////////////////////////////////////////////////////////// +void GazeboGraspGripper::HandleDetach(const std::string &objName) +{ + physics::WorldPtr world = this->model->GetWorld(); + if (!world.get()) + { + gzerr << "GazeboGraspGripper: world is NULL" << std::endl << std::endl; + return; + } +#ifdef USE_MODEL_ATTACH + physics::ModelPtr obj = world->GetModel(objName); + if (!obj.get()) + { + std::cerr << "ERROR: Object ModelPtr " << objName << + " not found in world, can't detach it" << std::endl; + return; + } + this->palmLink->DetachStaticModel(objName); +#else + physics::CollisionPtr obj = boost::dynamic_pointer_cast + (gazebo::GetEntityByName(world, objName)); + if (!obj.get()) + { + std::cerr << "ERROR: Object " << objName << + " not found in world, can't attach it" << std::endl; + return; + } + else if (this->disableCollisionsOnAttach) + { + obj->GetLink()->SetCollideMode("all"); + } + + // TODO: remove this test print, for issue #26 ------------------- +#if 0 + if (obj && obj->GetLink()) + { + auto linVel = GetWorldVelocity(obj->GetLink()); + gzmsg << "PRE-DETACH Velocity for link " << obj->GetLink()->GetName() + << " (collision name " << objName << "): " << linVel + << ", absolute val " << GetLength(linVel) << std::endl; + } +#endif + // ------------------- + + this->fixedJoint->Detach(); + + // TODO: remove this test print, for issue #26 ------------------- +#if 0 + if (obj && obj->GetLink()) + { + auto linVel = GetWorldVelocity(obj->GetLink()); + gzmsg << "POST-DETACH Velocity for link " << obj->GetLink()->GetName() + << " (collision name " << objName << "): " << linVel + << ", absolute val " << GetLength(linVel) << std::endl; + + } +#endif + // ------------------- + +#endif // USE_MODEL_ATTACH + this->attached = false; + this->attachedObjName = ""; +} diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/CMakeLists.txt b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/CMakeLists.txt new file mode 100644 index 0000000..09e4069 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/CMakeLists.txt @@ -0,0 +1,140 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gazebo_version_helpers) + +# This is added to remove policy CMP0054 warning (see https://stackoverflow.com/questions/45900159/how-to-use-variables-and-avoid-cmp0054-policy-violations) +cmake_policy(SET CMP0054 NEW) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + gazebo_ros + roscpp +) + +find_package(gazebo REQUIRED) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES gazebo_version_helpers + CATKIN_DEPENDS gazebo_ros roscpp + DEPENDS gazebo +) + +########### +## Build ## +########### + +# check c++11 / c++0x +include(CheckCXXCompilerFlag) +CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "-std=c++11") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "-std=c++0x") +else() + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler. Suggested solution: update the pkg build-essential ") +endif() + +## Specify additional locations of header files +## Your package locations should be listed before other locations + + +link_directories(${GAZEBO_LIBRARY_DIRS}) +include_directories(${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS} include) + +# Protobuf 2.6.1 includes were copied in kortex_gazebo/include and are necessary to build Gazebo plugins +include_directories(BEFORE ../../../kortex_gazebo/include/) +link_directories(BEFORE ../../../kortex_gazebo/lib/) + +## Declare a C++ library +add_library(${PROJECT_NAME} SHARED + src/GazeboVersionHelpers.cpp +) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/gazebo_version_helpers_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + libprotobuf.so +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_gazebo_version_helpers.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/include/gazebo_version_helpers/GazeboVersionHelpers.h b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/include/gazebo_version_helpers/GazeboVersionHelpers.h new file mode 100644 index 0000000..5a8f359 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/include/gazebo_version_helpers/GazeboVersionHelpers.h @@ -0,0 +1,146 @@ +#ifndef GAZEBO_VERSIONHELPERS_H +#define GAZEBO_VERSIONHELPERS_H + +#include + +namespace gazebo +{ + +// typedefs +#if GAZEBO_MAJOR_VERSION >= 8 +namespace gz_math = ignition::math; +typedef gz_math::Pose3d GzPose3; +typedef gz_math::Vector3d GzVector3; +typedef gz_math::Quaterniond GzQuaternion; +typedef gz_math::Matrix4d GzMatrix4; +typedef gz_math::Matrix3d GzMatrix3; +#else +namespace gz_math = gazebo::math; +typedef gz_math::Pose GzPose3; +typedef gz_math::Vector3 GzVector3; +typedef gz_math::Quaternion GzQuaternion; +typedef gz_math::Matrix4 GzMatrix4; +typedef gz_math::Matrix3 GzMatrix3; +#endif + +// Helper functions +// ////////////////////////// + +/////////////////////////////////////////////////////////////////////////////// +GzPose3 GetWorldPose(const gazebo::physics::LinkPtr &link); + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 GetWorldVelocity(const gazebo::physics::LinkPtr &link); + +/////////////////////////////////////////////////////////////////////////////// +GzMatrix4 GetIdentity(); + +/////////////////////////////////////////////////////////////////////////////// +GzMatrix4 GetMatrix(const GzPose3 &pose); + +/////////////////////////////////////////////////////////////////////////////// +GzMatrix4 GetMatrix(const GzVector3 &pos); + +/////////////////////////////////////////////////////////////////////////////// +double GetLength(const GzVector3 &v); + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 GetVector(const double x, const double y, const double z); + +/////////////////////////////////////////////////////////////////////////////// +void SetX(GzVector3 &v, const double val); +void SetY(GzVector3 &v, const double val); +void SetZ(GzVector3 &v, const double val); +double GetX(const GzVector3 &v); +double GetY(const GzVector3 &v); +double GetZ(const GzVector3 &v); + + +/////////////////////////////////////////////////////////////////////////////// +void SetX(GzQuaternion &q, const double val); +void SetY(GzQuaternion &q, const double val); +void SetZ(GzQuaternion &q, const double val); +void SetW(GzQuaternion &q, const double val); +double GetX(const GzQuaternion &q); +double GetY(const GzQuaternion &q); +double GetZ(const GzQuaternion &q); +double GetW(const GzQuaternion &q); + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 GetPos(const GzPose3 &pose); +/////////////////////////////////////////////////////////////////////////////// +GzVector3 GetPos(const GzMatrix4 &mat); + +/////////////////////////////////////////////////////////////////////////////// +GzQuaternion GetRot(const GzPose3 &pose); +/////////////////////////////////////////////////////////////////////////////// +GzQuaternion GetRot(const GzMatrix4 &mat); + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::PhysicsEnginePtr GetPhysics( + const gazebo::physics::WorldPtr &world); + + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::EntityPtr GetEntityByName( + const gazebo::physics::WorldPtr &world, const std::string &name); + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::ModelPtr GetModelByName( + const gazebo::physics::WorldPtr &world, const std::string &name); + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::Model_V GetModels(const gazebo::physics::WorldPtr &world); + +/////////////////////////////////////////////////////////////////////////////// +template +GzVector3 GetSize3(const T& t) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return t.Size(); +#else + return t.GetSize(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +template +std::string GetName(const T& t) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return t.Name(); +#else + return t.GetName(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +template +gz_math::Box GetBoundingBox(const T &t) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return t.BoundingBox(); +#else + return t.GetBoundingBox(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 GetBoundingBoxDimensions(const gz_math::Box &box); + +/////////////////////////////////////////////////////////////////////////////// +template +GzPose3 GetRelativePose(const T &t) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return t.RelativePose(); +#else + return t.GetRelativePose(); +#endif +} + + + +} // namespace + +#endif // GAZEBO_VERSIONHELPERS_H diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/package.xml b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/package.xml new file mode 100644 index 0000000..2c2cc92 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/package.xml @@ -0,0 +1,64 @@ + + + gazebo_version_helpers + 0.0.0 + The gazebo_version_helpers package + + + + + jenny + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + gazebo_ros + roscpp + gazebo_ros + roscpp + gazebo_ros + roscpp + + + + + + + diff --git a/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/src/GazeboVersionHelpers.cpp b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/src/GazeboVersionHelpers.cpp new file mode 100644 index 0000000..e0ef898 --- /dev/null +++ b/ros_kortex/third_party/gazebo-pkgs/gazebo_version_helpers/src/GazeboVersionHelpers.cpp @@ -0,0 +1,325 @@ +#include +#include + +using gazebo::GzPose3; +using gazebo::GzVector3; +using gazebo::GzMatrix3; +using gazebo::GzMatrix4; + +/////////////////////////////////////////////////////////////////////////////// +GzPose3 gazebo::GetWorldPose(const gazebo::physics::LinkPtr &link) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return link->WorldPose(); +#else + return link->GetWorldPose(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 gazebo::GetWorldVelocity(const gazebo::physics::LinkPtr &link) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return link->WorldLinearVel(); +#else + return link->GetWorldLinearVel(); +#endif +} + + +/////////////////////////////////////////////////////////////////////////////// +GzMatrix4 gazebo::GetIdentity() +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return GzMatrix4::Identity; +#else + return GzMatrix4::IDENTITY; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +GzMatrix4 gazebo::GetMatrix(const GzPose3 &pose) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return GzMatrix4(pose); +#else + GzMatrix4 mat = pose.rot.GetAsMatrix4(); + mat.SetTranslate(pose.pos); + return mat; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +GzMatrix4 gazebo::GetMatrix(const GzVector3 &pos) +{ + GzMatrix4 mat = GetIdentity(); +#if GAZEBO_MAJOR_VERSION >= 8 + mat.SetTranslation(pos); +#else + mat.SetTranslate(pos); +#endif + return mat; +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetLength(const GzVector3 &v) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return v.Length(); +#else + return v.GetLength(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetX(GzVector3 &v, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + v.X(val); +#else + v.x = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetY(GzVector3 &v, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + v.Y(val); +#else + v.y = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetZ(GzVector3 &v, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + v.Z(val); +#else + v.z = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetX(const GzVector3 &v) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return v.X(); +#else + return v.x; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetY(const GzVector3 &v) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return v.Y(); +#else + return v.y; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetZ(const GzVector3 &v) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return v.Z(); +#else + return v.z; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetX(GzQuaternion &q, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + q.X(val); +#else + q.x = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetY(GzQuaternion &q, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + q.Y(val); +#else + q.y = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetZ(GzQuaternion &q, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + q.Z(val); +#else + q.z = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +void gazebo::SetW(GzQuaternion &q, const double val) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + q.W(val); +#else + q.w = val; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetX(const GzQuaternion &q) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return q.X(); +#else + return q.x; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetY(const GzQuaternion &q) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return q.Y(); +#else + return q.y; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetZ(const GzQuaternion &q) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return q.Z(); +#else + return q.z; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +double gazebo::GetW(const GzQuaternion &q) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return q.W(); +#else + return q.w; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 gazebo::GetVector(const double x, const double y, const double z) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + GzVector3 v(x, y, z); +// v.X(x); +// v.Y(y); +// v.Z(z); +#else + GzVector3 v; + v.x = x; + v.y = y; + v.z = z; +#endif + return v; +} + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 gazebo::GetPos(const GzPose3 &pose) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return pose.Pos(); +#else + return pose.pos; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::GzQuaternion gazebo::GetRot(const GzPose3 &pose) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return pose.Rot(); +#else + return pose.rot; +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +GzVector3 gazebo::GetPos(const GzMatrix4 &mat) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return mat.Translation(); +#else + return mat.GetTranslation(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::GzQuaternion gazebo::GetRot(const GzMatrix4 &mat) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return mat.Rotation(); +#else + return mat.GetRotation(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::PhysicsEnginePtr gazebo::GetPhysics( + const gazebo::physics::WorldPtr &world) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return world->Physics(); +#else + return world->GetPhysicsEngine(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::EntityPtr gazebo::GetEntityByName( + const gazebo::physics::WorldPtr &world, const std::string &name) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return world->EntityByName(name); +#else + return world->GetEntity(name); +#endif + +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::ModelPtr gazebo::GetModelByName( + const gazebo::physics::WorldPtr &world, const std::string &name) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return world->ModelByName(name); +#else + return world->GetModel(name); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::physics::Model_V gazebo::GetModels( + const gazebo::physics::WorldPtr &world) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + return world->Models(); +#else + return world->GetModels(); +#endif +} + +/////////////////////////////////////////////////////////////////////////////// +gazebo::GzVector3 gazebo::GetBoundingBoxDimensions(const gz_math::Box &box) +{ +#if GAZEBO_MAJOR_VERSION >= 8 + GzVector3 bb(box.XLength(), box.YLength(), box.ZLength()); +#else + GzVector3 bb(box.GetXLength(), box.GetYLength(), box.GetZLength()); +#endif + return bb; +} diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/CMakeLists.txt b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/CMakeLists.txt new file mode 100644 index 0000000..61918ff --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/CMakeLists.txt @@ -0,0 +1,48 @@ +cmake_minimum_required(VERSION 2.8.6 FATAL_ERROR) +project(roboticsgroup_gazebo_plugins) + +# This is added to remove policy CMP0054 warning (see https://stackoverflow.com/questions/45900159/how-to-use-variables-and-avoid-cmp0054-policy-violations) +cmake_policy(SET CMP0054 NEW) + +# Load catkin and all dependencies required for this package +find_package(catkin REQUIRED COMPONENTS + roscpp + gazebo_ros + control_toolbox +) + +# Depend on system install of Gazebo +find_package(gazebo REQUIRED) +# Gazebo cxx flags should have all the required C++ flags +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") + +find_package(Boost REQUIRED) + +catkin_package( + DEPENDS + roscpp + gazebo_ros + control_toolbox +) + +link_directories(${GAZEBO_LIBRARY_DIRS}) +include_directories(${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS} ${GAZEBO_INCLUDE_DIRS} include) + +# Protobuf 2.6.1 includes were copied in kortex_gazebo/include and are necessary to build Gazebo plugins +include_directories(BEFORE ../../kortex_gazebo/include/) +link_directories(BEFORE ../../kortex_gazebo/lib/) + +add_library(roboticsgroup_gazebo_mimic_joint_plugin src/mimic_joint_plugin.cpp) +target_link_libraries(roboticsgroup_gazebo_mimic_joint_plugin libprotobuf.so ${catkin_LIBRARIES}) + +add_library(roboticsgroup_gazebo_disable_link_plugin src/disable_link_plugin.cpp) +target_link_libraries(roboticsgroup_gazebo_disable_link_plugin libprotobuf.so ${catkin_LIBRARIES}) + +install(TARGETS roboticsgroup_gazebo_mimic_joint_plugin roboticsgroup_gazebo_disable_link_plugin + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME} + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/README.md b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/README.md new file mode 100644 index 0000000..62a5645 --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/README.md @@ -0,0 +1,83 @@ +This ROS package was cloned from https://github.com/roboticsgroup/roboticsgroup_gazebo_plugins into ros_kortex to properly simulate mimic joints in Gazebo for the Robotiq 2f 85 gripper. +The repository was cloned at commit 4d93ecd86e4415c3fe74d0027fd41c5e3b39ec44. +The original readme file follows: + +roboticsgroup_gazebo_plugins +================ + +Collection of small gazebo plugins +---------------------------------- + +MimicJointPlugin +---------------- + +A simple (Model) plugin for Gazebo in order to add to Gazebo the mimic joint functionality that exists in URDF (ROS). Inspired by code of Goncalo Cabrita. + + - *XML Parameters* + + - joint (Required) + + A **string** specifying the name of the joint to be mimic-ed. + + - mimicJoint (Required) + + A **string** specifying the name of the mimic joint. + + - multiplier + + A **double** specifying the multiplier parameter of the mimic joint. Defaults to 1.0. + + - offset + + A **double** specifying the offset parameter of the mimic joint. Defaults to 0.0. + + - maxEffort + + A **double** specifying the max effort the mimic joint can generate. Defaults to the effort limit in the sdf model. + + - sensitiveness + + A **double** specifying the sensitiveness of the mimic joint. Defaults to 0.0. It basically is the threshold of the difference between the 2 angles (joint's and mimic's) before applying the "mimicness". + + - robotNamespace + + A **string** specifying the namespace the robot is under. Defaults to "". + + - hasPID + + Determines whether the joint has PID in order to be controlled via PID position/effort controller. *\* means that the mimic joint is controlled via PID. Omit it so that the mimic joint is controlled via setAngle. Optionally, specify a value to set the pid namespace. + +DisableLinkPlugin +----------------- + +A simple (Model) plugin for Gazebo that allows you to disable a link in Gazebo's physics engine. + + - *XML Parameters* + + - link (Required) + + A **string** specifying the name of the link to be disabled. It should be a valid sdf (not urdf) link. + +### Hoping to add more plugins.... + +Usage +------ + +Standard Gazebo plugin import inside xacro/urdf. Use **libroboticsgroup_gazebo_** prefix. E.g. if you want to import MimicJointPlugin: + +``` +libroboticsgroup_gazebo_mimic_joint_plugin.so +``` + +Notes +------ + +If there is a need, please make an issue and I'll see what I can do to add that functionality/plugin. + +License +---- + +BSD + + +Copyright (c) 2014, **Konstantinos Chatzilygeroudis** diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h new file mode 100644 index 0000000..b3bd6c3 --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h @@ -0,0 +1,64 @@ +/** +Copyright (c) 2014, Konstantinos Chatzilygeroudis +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer + in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, +BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE +OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +**/ + +#ifndef ROBOTICSGROUP_GAZEBO_PLUGINS_DISABLE_LINK_PLUGIN +#define ROBOTICSGROUP_GAZEBO_PLUGINS_DISABLE_LINK_PLUGIN + +// ROS includes +#include + +// Boost includes +#include + +// Gazebo includes +#include +#include +#include +#include + +namespace gazebo { + class DisableLinkPlugin : public ModelPlugin { + public: + DisableLinkPlugin(); + ~DisableLinkPlugin(); + + void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf); + void UpdateChild(); + + private: + // Parameters + std::string link_name_; + + bool kill_sim; + + // Pointers to the joints + physics::LinkPtr link_; + + // Pointer to the model + physics::ModelPtr model_; + + // Pointer to the world + physics::WorldPtr world_; + }; +} + +#endif diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h new file mode 100644 index 0000000..39ab0fc --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h @@ -0,0 +1,73 @@ +/** +Copyright (c) 2014, Konstantinos Chatzilygeroudis +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer + in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, +BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE +OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +**/ + +#ifndef ROBOTICSGROUP_GAZEBO_PLUGINS_MIMIC_JOINT_PLUGIN +#define ROBOTICSGROUP_GAZEBO_PLUGINS_MIMIC_JOINT_PLUGIN + +// ROS includes +#include + +// ros_control +#include + +// Boost includes +#include + +// Gazebo includes +#include +#include +#include +#include + +namespace gazebo { + class MimicJointPlugin : public ModelPlugin { + public: + MimicJointPlugin(); + ~MimicJointPlugin(); + + void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf); + void UpdateChild(); + + private: + // Parameters + std::string joint_name_, mimic_joint_name_, robot_namespace_; + double multiplier_, offset_, sensitiveness_, max_effort_; + bool has_pid_; + + // PID controller if needed + control_toolbox::Pid pid_; + + // Pointers to the joints + physics::JointPtr joint_, mimic_joint_; + + // Pointer to the model + physics::ModelPtr model_; + + // Pointer to the world + physics::WorldPtr world_; + + // Pointer to the update event connection + event::ConnectionPtr updateConnection; + }; +} + +#endif diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/package.xml b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/package.xml new file mode 100644 index 0000000..c5e4733 --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/package.xml @@ -0,0 +1,51 @@ + + + + roboticsgroup_gazebo_plugins + 0.0.1 + Collection of small gazebo plugins + + Konstantinos Chatzilygeroudis + + BSD + + https://github.com/roboticsgroup/roboticsgroup_gazebo_plugins + https://github.com/roboticsgroup/roboticsgroup_gazebo_plugins/issues + + Konstantinos Chatzilygeroudis + + catkin + + + gazebo_ros + roscpp + control_toolbox + + + gazebo_ros + roscpp + control_toolbox + + + + + + diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp new file mode 100644 index 0000000..9a15838 --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp @@ -0,0 +1,64 @@ +/** +Copyright (c) 2014, Konstantinos Chatzilygeroudis +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer + in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, +BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE +OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +**/ + +#include + +namespace gazebo { + + DisableLinkPlugin::DisableLinkPlugin() + { + kill_sim = false; + + link_.reset(); + } + + DisableLinkPlugin::~DisableLinkPlugin() + { + kill_sim = true; + } + + void DisableLinkPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) + { + model_ = _parent; + world_ = model_->GetWorld(); + + // Check for link element + if (!_sdf->HasElement("link")) { + ROS_ERROR("No link element present. DisableLinkPlugin could not be loaded."); + return; + } + + link_name_ = _sdf->GetElement("link")->Get(); + + // Get pointers to joints + link_ = model_->GetLink(link_name_); + if (link_) { + link_->SetEnabled(false); + // Output some confirmation + ROS_INFO_STREAM("DisableLinkPlugin loaded! Link: \"" << link_name_); + } + else + ROS_ERROR_STREAM("Link" << link_name_ << " not found! DisableLinkPlugin could not be loaded."); + } + + GZ_REGISTER_MODEL_PLUGIN(DisableLinkPlugin); +} diff --git a/ros_kortex/third_party/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp new file mode 100644 index 0000000..ca53e2f --- /dev/null +++ b/ros_kortex/third_party/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp @@ -0,0 +1,194 @@ +/** +Copyright (c) 2014, Konstantinos Chatzilygeroudis +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer + in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, +BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT +SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE +OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +**/ + +#include + +#if GAZEBO_MAJOR_VERSION >= 8 +namespace math = ignition::math; +#else +namespace math = gazebo::math; +#endif + +namespace gazebo { + + MimicJointPlugin::MimicJointPlugin() + { + joint_.reset(); + mimic_joint_.reset(); + } + + MimicJointPlugin::~MimicJointPlugin() + { + this->updateConnection.reset(); + } + + void MimicJointPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) + { + model_ = _parent; + world_ = model_->GetWorld(); + + // Error message if the model couldn't be found + if (!model_) { + ROS_ERROR("Parent model is NULL! MimicJointPlugin could not be loaded."); + return; + } + + // Check that ROS has been initialized + if (!ros::isInitialized()) { + ROS_ERROR("A ROS node for Gazebo has not been initialized, unable to load plugin."); + return; + } + + // Check for robot namespace + robot_namespace_ = ""; + if (_sdf->HasElement("robotNamespace")) { + robot_namespace_ = _sdf->GetElement("robotNamespace")->Get(); + } + ros::NodeHandle model_nh(robot_namespace_); + + // Check for joint element + if (!_sdf->HasElement("joint")) { + ROS_ERROR("No joint element present. MimicJointPlugin could not be loaded."); + return; + } + + joint_name_ = _sdf->GetElement("joint")->Get(); + + // Check for mimicJoint element + if (!_sdf->HasElement("mimicJoint")) { + ROS_ERROR("No mimicJoint element present. MimicJointPlugin could not be loaded."); + return; + } + + mimic_joint_name_ = _sdf->GetElement("mimicJoint")->Get(); + + // Check if PID controller wanted + has_pid_ = _sdf->HasElement("hasPID"); + if (has_pid_) { + std::string name = _sdf->GetElement("hasPID")->Get(); + if (name.empty()) { + name = "gazebo_ros_control/pid_gains/" + mimic_joint_name_; + } + const ros::NodeHandle nh(model_nh, name); + pid_.init(nh); + } + + // Check for multiplier element + multiplier_ = 1.0; + if (_sdf->HasElement("multiplier")) + multiplier_ = _sdf->GetElement("multiplier")->Get(); + + // Check for offset element + offset_ = 0.0; + if (_sdf->HasElement("offset")) + offset_ = _sdf->GetElement("offset")->Get(); + + // Check for sensitiveness element + sensitiveness_ = 0.0; + if (_sdf->HasElement("sensitiveness")) + sensitiveness_ = _sdf->GetElement("sensitiveness")->Get(); + + // Get pointers to joints + joint_ = model_->GetJoint(joint_name_); + if (!joint_) { + ROS_ERROR_STREAM("No joint named \"" << joint_name_ << "\". MimicJointPlugin could not be loaded."); + return; + } + mimic_joint_ = model_->GetJoint(mimic_joint_name_); + if (!mimic_joint_) { + ROS_ERROR_STREAM("No (mimic) joint named \"" << mimic_joint_name_ << "\". MimicJointPlugin could not be loaded."); + return; + } + + // Check for max effort +#if GAZEBO_MAJOR_VERSION > 2 + max_effort_ = mimic_joint_->GetEffortLimit(0); +#else + max_effort_ = mimic_joint_->GetMaxForce(0); +#endif + if (_sdf->HasElement("maxEffort")) { + max_effort_ = _sdf->GetElement("maxEffort")->Get(); + } + + // Set max effort + if (!has_pid_) { +#if GAZEBO_MAJOR_VERSION > 2 + mimic_joint_->SetEffortLimit(0, max_effort_); +#else + mimic_joint_->SetMaxForce(0, max_effort_); +#endif + } + + // Listen to the update event. This event is broadcast every + // simulation iteration. + this->updateConnection = event::Events::ConnectWorldUpdateBegin( + boost::bind(&MimicJointPlugin::UpdateChild, this)); + + // Output some confirmation + ROS_INFO_STREAM("MimicJointPlugin loaded! Joint: \"" << joint_name_ << "\", Mimic joint: \"" << mimic_joint_name_ << "\"" + << ", Multiplier: " << multiplier_ << ", Offset: " << offset_ + << ", MaxEffort: " << max_effort_ << ", Sensitiveness: " << sensitiveness_); + } + + void MimicJointPlugin::UpdateChild() + { +#if GAZEBO_MAJOR_VERSION >= 8 + static ros::Duration period(world_->Physics()->GetMaxStepSize()); +#else + static ros::Duration period(world_->GetPhysicsEngine()->GetMaxStepSize()); +#endif + + // Set mimic joint's angle based on joint's angle +#if GAZEBO_MAJOR_VERSION >= 8 + double angle = joint_->Position(0) * multiplier_ + offset_; + double a = mimic_joint_->Position(0); +#else + double angle = joint_->GetAngle(0).Radian() * multiplier_ + offset_; + double a = mimic_joint_->GetAngle(0).Radian(); +#endif + + if (fabs(angle - a) >= sensitiveness_) { + if (has_pid_) { + if (a != a) + a = angle; + double error = angle - a; + double effort = math::clamp(pid_.computeCommand(error, period), -max_effort_, max_effort_); + mimic_joint_->SetForce(0, effort); + } + else { +#if GAZEBO_MAJOR_VERSION >= 9 + mimic_joint_->SetPosition(0, angle, true); +#elif GAZEBO_MAJOR_VERSION > 2 + ROS_WARN_ONCE("The mimic_joint plugin is using the Joint::SetPosition method without preserving the link velocity."); + ROS_WARN_ONCE("As a result, gravity will not be simulated correctly for your model."); + ROS_WARN_ONCE("Please set gazebo_pid parameters or upgrade to Gazebo 9."); + ROS_WARN_ONCE("For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612"); + mimic_joint_->SetPosition(0, angle); +#else + mimic_joint_->SetAngle(0, math::Angle(angle)); +#endif + } + } + } + + GZ_REGISTER_MODEL_PLUGIN(MimicJointPlugin); +}