diff --git a/.bumpversion.cfg b/.bumpversion.cfg index 6e46b19..9fe63ee 100644 --- a/.bumpversion.cfg +++ b/.bumpversion.cfg @@ -1,5 +1,5 @@ [bumpversion] -current_version = 0.5.0 +current_version = 0.6.0 commit = True [bumpversion:file:setup.py] diff --git a/HISTORY.rst b/HISTORY.rst index 5e8a9c7..25708d7 100644 --- a/HISTORY.rst +++ b/HISTORY.rst @@ -2,6 +2,21 @@ History ======= +0.6.0 (May 17th, 2021) +---------------------- + +Breaking changes +~~~~~~~~~~~~~~~~ + +* Example data is now fetched via the ``pooch`` library and no longer a part + of the package itself. + +New features +~~~~~~~~~~~~ +* New ``io`` module for import/export methods. +* New ``ros.RosbagWriter`` class for writing rosbag files. + + 0.5.0 (March 16th, 2021) ------------------------ diff --git a/MANIFEST.in b/MANIFEST.in index efecd14..965b2dd 100644 --- a/MANIFEST.in +++ b/MANIFEST.in @@ -9,5 +9,3 @@ recursive-exclude * __pycache__ recursive-exclude * *.py[co] recursive-include docs *.rst conf.py Makefile make.bat *.jpg *.png *.gif - -recursive-include rigid_body_motion/data * diff --git a/ci/conda_recipe/meta.yaml b/ci/conda_recipe/meta.yaml index fc760f2..128b301 100644 --- a/ci/conda_recipe/meta.yaml +++ b/ci/conda_recipe/meta.yaml @@ -32,15 +32,17 @@ test: - pandas - xarray - netcdf4 + - pooch - numba - ipywidgets - - ros-melodic-rospy # [linux and x86_64] - - ros-melodic-tf # [linux and x86_64] - - ros-melodic-tf2-ros # [linux and x86_64] - - ros-melodic-tf2-geometry-msgs # [linux and x86_64] - - ros-melodic-geometry-msgs # [linux and x86_64] - - ros-melodic-visualization-msgs # [linux and x86_64] - - ros-melodic-python-orocos-kdl # [linux and x86_64] + - ros-noetic-rospy + - ros-noetic-tf + - ros-noetic-tf2-ros + - ros-noetic-tf2-geometry-msgs + - ros-noetic-geometry-msgs + - ros-noetic-visualization-msgs + - python-orocos-kdl + - boost=1.74 - pytest - pytest-cov commands: diff --git a/ci/requirements_docs.txt b/ci/requirements_docs.txt index 281ac75..c2e9a39 100644 --- a/ci/requirements_docs.txt +++ b/ci/requirements_docs.txt @@ -4,11 +4,13 @@ netcdf4==1.5.3 numba==0.43 llvmlite==0.31.0 anytree==2.8.0 +pooch==1.3.0 -sphinx==2.4.4 +sphinx==3.5.4 sphinx_rtd_theme==0.4.3 numpydoc==0.9.1 -sphinx-autosummary-accessors==0.1.2 +sphinx-autosummary-accessors==0.2.0 nbsphinx==0.8.1 +jinja2==2.11.3 matplotlib==3.3.2 ipykernel==5.5.0 diff --git a/ci/requirements_latest.txt b/ci/requirements_latest.txt index a71c30d..96fce07 100644 --- a/ci/requirements_latest.txt +++ b/ci/requirements_latest.txt @@ -6,3 +6,4 @@ numpy-quaternion numba anytree pytest +pooch diff --git a/docs/_static/envs/example-env-ros.yml b/docs/_static/envs/example-env-ros.yml new file mode 100644 index 0000000..83fa2cb --- /dev/null +++ b/docs/_static/envs/example-env-ros.yml @@ -0,0 +1,22 @@ +name: rbm-examples-ros +channels: +- conda-forge +- robostack +- phausamann +dependencies: +- python=3.6 +- rigid-body-motion>=0.6 +- numba +- xarray +- netcdf4 +- matplotlib +- ipykernel +- ipywidgets +- ros-noetic-rospy +- ros-noetic-tf +- ros-noetic-tf2-ros +- ros-noetic-tf2-geometry-msgs +- ros-noetic-geometry-msgs +- ros-noetic-visualization-msgs +- python-orocos-kdl +- boost=1.74 diff --git a/docs/_static/envs/example-env.yml b/docs/_static/envs/example-env.yml index 46646c8..a5ec4c1 100644 --- a/docs/_static/envs/example-env.yml +++ b/docs/_static/envs/example-env.yml @@ -4,9 +4,10 @@ channels: - phausamann dependencies: - python=3.6 -- rigid-body-motion>=0.5 +- rigid-body-motion>=0.6 - numba - xarray - netcdf4 - matplotlib - ipykernel +- pooch diff --git a/docs/_static/example.rviz b/docs/_static/example.rviz new file mode 100644 index 0000000..0d9f3da --- /dev/null +++ b/docs/_static/example.rviz @@ -0,0 +1,152 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Grid1/Offset1 + - /TF1/Status1 + - /TF1/Tree1 + Splitter Ratio: 0.5 + Tree Height: 772 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 10 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: -20 + Y: -60 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /head/path + Name: Marker + Namespaces: + "": true + Queue Size: 100 + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 60 + Frames: + All Enabled: false + head: + Value: true + left_eye: + Value: false + world: + Value: true + Marker Alpha: 1 + Marker Scale: 10 + Name: TF + Show Arrows: false + Show Axes: true + Show Names: true + Tree: + world: + head: + {} + Update Interval: 0 + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 255; 255; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.20000000298023224 + Name: Pose + Queue Size: 10 + Shaft Length: 2 + Shaft Radius: 0.10000000149011612 + Shape: Arrow + Topic: /left_eye/pose + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 70.07855224609375 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -1.9384573698043823 + Y: -35.77290725708008 + Z: 4.647912979125977 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5310819149017334 + Target Frame: + Yaw: 5.843320846557617 + Saved diff --git a/docs/_static/img/rviz_0.png b/docs/_static/img/rviz_0.png new file mode 100644 index 0000000..6ddbedc Binary files /dev/null and b/docs/_static/img/rviz_0.png differ diff --git a/docs/_static/img/rviz_1.png b/docs/_static/img/rviz_1.png new file mode 100644 index 0000000..35f03e4 Binary files /dev/null and b/docs/_static/img/rviz_1.png differ diff --git a/docs/_static/img/rviz_2.png b/docs/_static/img/rviz_2.png new file mode 100644 index 0000000..7ae6392 Binary files /dev/null and b/docs/_static/img/rviz_2.png differ diff --git a/docs/api.rst b/docs/api.rst index be40fc7..d8e5c62 100644 --- a/docs/api.rst +++ b/docs/api.rst @@ -91,6 +91,18 @@ Utility functions rotate_vectors +I/O functions +------------- + +.. currentmodule:: rigid_body_motion.io + +.. autosummary:: + :nosignatures: + :toctree: _generated + + load_optitrack + + Plotting -------- @@ -112,7 +124,6 @@ xarray Accessors .. currentmodule:: xarray .. autosummary:: - :nosignatures: :toctree: _generated :template: autosummary/accessor_method.rst diff --git a/docs/conf.py b/docs/conf.py index 5b60196..df991f6 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -52,7 +52,7 @@ numpydoc_show_class_members = False nbsphinx_kernel_name = "python3" -nbsphinx_execute = "always" +nbsphinx_execute = "auto" nbsphinx_prolog = """ .. nbinfo:: diff --git a/docs/index.rst b/docs/index.rst index 7b88a98..5703b53 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -34,6 +34,7 @@ xarray_ data types. reference_frames velocities xarray + ros .. toctree:: :maxdepth: 1 diff --git a/docs/installation.rst b/docs/installation.rst index ea59a09..c5f70a2 100644 --- a/docs/installation.rst +++ b/docs/installation.rst @@ -39,11 +39,11 @@ rigid-body-motion supports xarray data types: $ pip install xarray -Loading the example datasets requires the netCDF4 library: +Loading the example datasets requires the pooch and netCDF4 libraries: .. code-block:: console - $ pip install netcdf4 + $ pip install pooch netcdf4 Plotting functions require matplotlib: @@ -51,9 +51,53 @@ Plotting functions require matplotlib: $ pip install matplotlib +ROS integration +--------------- -Example environment -------------------- +The package also integrates with ROS_, which can be installed quite +conveniently via ``conda`` thanks to the amazing work by the people from +RoboStack_. This even works on Windows and macOS! The necessary dependencies +are: + +.. code-block:: console + + $ conda install -c conda-forge -c robostack ros-noetic-rospy ros-noetic-tf ros-noetic-tf2-ros ros-noetic-tf2-geometry-msgs ros-noetic-geometry-msgs ros-noetic-visualization-msgs python-orocos-kdl boost=1.74 + +Note that these packages are only available for Python 3.6 and 3.8. + +.. _ROS: https://www.ros.org/ +.. _RoboStack: https://github.com/RoboStack + +In order to use RViz for visualization you need to install that as well: + +.. code-block:: console + + $ conda install -c conda-forge -c robostack ros-noetic-rviz + +Since ROS can communicate across conda environments, we would however recommend +installing RViz in a dedicated environment: + +.. code-block:: console + + $ conda create -n ros -c conda-forge -c robostack ros-noetic-rviz + +After installing, you can spin up a ``roscore``: + +.. code-block:: console + + $ conda activate ros + $ roscore + +and, from a second terminal, launch RViz: + +.. code-block:: console + + $ conda activate ros + $ rviz + + +Example environments +-------------------- We recommend using rigid_body_motion in a dedicated conda environment. For the examples in the user guide, we provide an @@ -64,6 +108,13 @@ that you can download and set up with: $ conda env create -f example-env.yml +There's also an example environment that includes the necessary ROS packages +(:download:`here<_static/envs/example-env-ros.yml>`) that you can set up with: + +.. code-block:: console + + $ conda env create -f example-env-ros.yml + If you download the examples as Jupyter notebooks, it is sufficient to have the Jupyter notebook server installed in your base environment alongside ``nb_conda``: @@ -73,7 +124,8 @@ the Jupyter notebook server installed in your base environment alongside $ conda install -n base nb_conda Now you can open any of the example notebooks, go to *Kernel > Change kernel* -and select *Python [conda env:rbm-examples]*. +and select *Python [conda env:rbm-examples]* +(or *Python [conda env:rbm-examples-ros]*). Pre-release version ------------------- diff --git a/docs/ros.ipynb b/docs/ros.ipynb new file mode 100644 index 0000000..6b01e9e --- /dev/null +++ b/docs/ros.ipynb @@ -0,0 +1,611 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# ROS integration\n", + "\n", + "rigid_body_motion supports certain ROS functionality, provided the Python environment has been set up with the required ROS packages. This guide assumes that you are at least somewhat familiar with ROS concepts such as nodes, publishers/subscribers and messages. If not, the [ROS tutorials](http://wiki.ros.org/ROS/Tutorials) are a good place to start.\n", + "\n", + "You also need to set up a couple of dependencies which can be done very conveniently if you are using an Anaconda Python distribution. See [the ROS dependencies installation guide](installation.rst#ros-integration) for further information." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "
\n", + "Note\n", + " \n", + "The following examples require the `pooch`, `xarray`, `netcdf4` and `ipywidgets` libraries.\n", + "
" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import pandas as pd\n", + "import rigid_body_motion as rbm\n", + "import rospy\n", + "import xarray as xr" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Loading data from rosbag files\n", + "\n", + "Data can be loaded from rosbag files into numpy arrays. So far, `geometry_msgs/TransformStamped` and `nav_msgs/Odometry` messages are supported. This is done through the `RosbagReader` class:" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "reader = rbm.ros.RosbagReader(rbm.example_data[\"rosbag\"])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The reader can be used as a context manager to facilitate opening and closing of the rosbag. The `get_topics_and_types` method returns a dict with topic names and corresponding message types:" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "{'/pupil/left_eye/transform': 'geometry_msgs/TransformStamped',\n", + " '/pupil/right_eye/transform': 'geometry_msgs/TransformStamped',\n", + " '/t265/transform': 'geometry_msgs/TransformStamped'}" + ] + }, + "execution_count": 3, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "with reader:\n", + " info = reader.get_topics_and_types()\n", + "info" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The data included in the example rosbag is from a [head/eye tracking study](https://dl.acm.org/doi/pdf/10.1145/3379156.3391365) and contains head-in-world pose estimated by the Intel RealSense T265 as well as eye-in-head pose for both eyes estimated by the Pupil Core eye tracker. " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The `load_messages` method returns a dict with the data from a specified topic:" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "{'timestamps': array([1.58060323e+09, 1.58060323e+09, 1.58060323e+09, ...,\n", + " 1.58060357e+09, 1.58060357e+09, 1.58060357e+09]),\n", + " 'position': array([[15.9316, 0.8211, 10.5429],\n", + " [15.9354, 0.8208, 10.5382],\n", + " [15.9393, 0.8204, 10.5335],\n", + " ...,\n", + " [29.8883, 2.8952, 7.6317],\n", + " [29.8888, 2.8943, 7.6249],\n", + " [29.8892, 2.8935, 7.6182]]),\n", + " 'orientation': array([[-0.9687, 0.0917, 0.2306, 0.0039],\n", + " [-0.969 , 0.0915, 0.2295, 0.005 ],\n", + " [-0.9693, 0.0912, 0.2285, 0.0061],\n", + " ...,\n", + " [-0.9915, 0.0915, 0.0929, -0.0022],\n", + " [-0.9914, 0.0922, 0.0927, -0.0017],\n", + " [-0.9913, 0.0932, 0.0925, -0.001 ]])}" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "with reader:\n", + " head = reader.load_messages(\"/t265/transform\")\n", + "head" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now we can construct a reference frame tree with this data:" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "rbm.register_frame(\"world\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The T265 uses the VR coordinate convention (x right, y up, z towards the back of the device) which differs from the default ROS convention (x forward, y left, z up):" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "R_T265_ROS = np.array([[0.0, 0.0, -1.0], [-1.0, 0.0, 0.0], [0.0, 1.0, 0.0]])\n", + "\n", + "rbm.ReferenceFrame.from_rotation_matrix(\n", + " R_T265_ROS, parent=\"world\", name=\"t265/world\"\n", + ").register()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The recorded data describes the transformation from the T265 world frame to the tracker frame:" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "rbm.register_frame(\n", + " \"t265/tracker\",\n", + " parent=\"t265/world\",\n", + " translation=head[\"position\"],\n", + " rotation=head[\"orientation\"],\n", + " timestamps=pd.to_datetime(head[\"timestamps\"], unit=\"s\"),\n", + ")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "For visualization, we define an additional `\"head\"` frame that represents the tracker pose with the ROS coordinate convention:" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "rbm.ReferenceFrame.from_rotation_matrix(\n", + " R_T265_ROS, parent=\"t265/tracker\", name=\"head\", inverse=True,\n", + ").register()" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "world\n", + "└── t265/world\n", + " └── t265/tracker\n", + " └── head\n" + ] + } + ], + "source": [ + "rbm.render_tree(\"world\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Visualization with RViz\n", + "\n", + "This section will show you how to broadcast reference frame transforms on the `/tf` topic as well as publish other messages that are useful for visualization in RViz. If you are not familiar with RViz and/or tf, check out the [RViz user guide](http://wiki.ros.org/rviz/UserGuide) and the [tf package documentation](http://wiki.ros.org/tf). You can download an `.rviz` file where all topics created in the following are already set up [here](_static/example.rviz)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We start by creating a node for this notebook through `rospy`:" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [ + "rospy.init_node(\"rbm_vis\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Transforms between reference frames can easily be broadcast on the `/tf` topic with the `ReferenceFrameTransformBroadcaster` class:" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "tf_world_head = rbm.ros.ReferenceFrameTransformBroadcaster(\"head\", base=\"world\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "When calling `publish` the transform between world and head frame will be broadcast on the `/tf` topic. Since the head frame is a moving frame this will broadcast the first valid transform between the two frames by default:" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "tf_world_head.publish()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "RViz should now show both frames:\n", + "\n", + "" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The broadcaster stores all valid transforms between the two frames in the `translation`, `rotation` and `timestamps` attributes:" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(66629, 3)" + ] + }, + "execution_count": 13, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "tf_world_head.translation.shape" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "You can broadcast the transform between two frames at different points in time by specifying an index into these arrays as an argument to `publish`:" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "tf_world_head.publish(1000)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "
\n", + "Note \n", + "\n", + "When \"going back in time\", i.e., broadcasting transforms with timestamps older than the latest broadcast timestamp, RViz will not update the tf display and you may get a `TF_OLD_DATA` warning in the console. When this happens, click on the \"Reset\" button in the lower left corner in RViz.\n", + "
" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The entire transformation between moving frames can be visualized with the `ReferenceFrameMarkerPublisher` which publishes the translation of all valid timestamps as a `visualization_msgs/Marker` message on the `//path` topic: " + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[['/head/path', 'visualization_msgs/Marker']]" + ] + }, + "execution_count": 15, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "marker_publisher = rbm.ros.ReferenceFrameMarkerPublisher(\"head\", base=\"world\")\n", + "marker_publisher.publish()\n", + "rospy.get_published_topics(\"/head\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "RViz should now show the trajectory of the head frame as a white line:\n", + "\n", + "" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Next, we will load data from the Pupil Core eye tracker to demonstrate how multiple moving frames can be visualized. With the `load_dataset` method, the data is imported as an `xarray.Dataset` and `cache=True` enables local caching in the netCDF4 format for faster loading." + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "with reader:\n", + " left_eye = reader.load_dataset(\"/pupil/left_eye/transform\", cache=True)\n", + "\n", + "left_eye = left_eye.dropna(\"time\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The transform between the T265 and the Pupil Core scene camera was determined in the study with a camera calibration routine and is provided here as hard-coded parameters:" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [], + "source": [ + "t_t265_pupil = (24.5e-3, -29e-3, 0.0)\n", + "r_t265_pupil = (-0.00125, -1.0, 6.3463e-05, 3.977e-06)\n", + "\n", + "rbm.register_frame(\n", + " \"pupil/scene_cam\",\n", + " parent=\"t265/tracker\",\n", + " translation=t_t265_pupil,\n", + " rotation=r_t265_pupil,\n", + ")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The reference frame of the left eye is constructed from the Dataset:" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [], + "source": [ + "rbm.ReferenceFrame.from_dataset(\n", + " left_eye,\n", + " \"position\",\n", + " \"orientation\",\n", + " \"time\",\n", + " parent=\"pupil/scene_cam\",\n", + " name=\"pupil/left_eye\",\n", + ").register()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The eye tracker data uses yet another coordinate convention (x right, y down, z forward) which we need to take into account when visualizing the eye frame:" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [], + "source": [ + "R_PUPIL_ROS = np.array([[0.0, -1.0, 0.0], [0.0, 0.0, -1.0], [1.0, 0.0, 0.0]])\n", + "\n", + "rbm.ReferenceFrame.from_rotation_matrix(\n", + " R_PUPIL_ROS, parent=\"pupil/left_eye\", name=\"left_eye\"\n", + ").register(update=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "world\n", + "└── t265/world\n", + " └── t265/tracker\n", + " ├── head\n", + " └── pupil/scene_cam\n", + " └── pupil/left_eye\n", + " └── left_eye\n" + ] + } + ], + "source": [ + "rbm.render_tree(\"world\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now we create another broadcaster for the transform between head and eye frame. With `publish_pose=True`, the broadcaster also publishes a `geometry_msgs/PoseStamped` message on the `//pose` topic. This message can be visualized in RViz as an arrow which avoids cluttering for frames that are close together. In order to publish messages in sync with the world/head transform, we specify `subscribe=\"head\"`. This way, the broadcaster checks for new messages on the `/tf` topic where the `child_frame_id` is `\"head\"` and publishes its own transform with the closest timestamp:" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": {}, + "outputs": [], + "source": [ + "tf_head_left_eye = rbm.ros.ReferenceFrameTransformBroadcaster(\n", + " \"left_eye\", base=\"head\", publish_pose=True, subscribe=\"head\"\n", + ")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Calling the `spin` method dispatches the broadcaster to a separate thread where it will keep checking for new world/head transforms:" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [], + "source": [ + "tf_head_left_eye.spin()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Finally, the `play_publisher` method provides a notebook widget to play back data from a broadcaster. With `step=2` it broadcasts every second transform and with `speed=0.5` the data is played back at half the recorded speed:" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "95dc9a79474a42ed98d5752c9b8b0e9a", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "HBox(children=(IntSlider(value=0, description='Index', max=66628), Button(description='◄◄', layout=Layout(widt…" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "1b76eb94cfcd4acfa3623a45b9127d95", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "Output()" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "rbm.ros.play_publisher(tf_world_head, step=2, speed=0.5)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "After pressing the play button, you should see the head frame moving along the white path, with the eye-in-head pose drawn as a yellow arrow:\n", + "\n", + "" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:rbm]", + "language": "python", + "name": "conda-env-rbm-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.6.13" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/docs/xarray.ipynb b/docs/xarray.ipynb index f1b2595..ff4cf82 100644 --- a/docs/xarray.ipynb +++ b/docs/xarray.ipynb @@ -22,7 +22,7 @@ "
\n", "Note\n", " \n", - "The following examples require the `matplotlib` and `netcdf4` libraries.\n", + "The following examples require the `matplotlib`, `xarray` and `netcdf4` libraries.\n", "
" ] }, @@ -206,7 +206,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.6.11" + "version": "3.6.13" } }, "nbformat": 4, diff --git a/environment.devenv.yml b/environment.devenv.yml index d43772c..ce0a238 100644 --- a/environment.devenv.yml +++ b/environment.devenv.yml @@ -14,15 +14,17 @@ dependencies: - quaternion=2020.9.5.14.42.2 - numba=0.48 - anytree=2.8 + - pooch=1.3.0 - pytest=6.2.2 - pytest-cov=2.7.1 - coverage=4.5.3 - - sphinx=2.4.4 + - sphinx=3.5.4 - sphinx_rtd_theme=0.4.3 - nbsphinx=0.8.1 - - sphinx-autosummary-accessors=0.1.2 + - sphinx-autosummary-accessors=0.2.0 - numpydoc=0.9.1 - matplotlib=3.3.2 + - jinja2=2.11.3 # additional dev tools {% if "RBM_DEV_TOOLS" in os.environ %} - watchdog=2.0.2 @@ -35,22 +37,15 @@ dependencies: {% endif %} # ROS dependencies {% if "RBM_ROS" in os.environ %} - - ros-melodic-rospy - - ros-melodic-tf - - ros-melodic-tf2-ros - - ros-melodic-geometry-msgs - - ros-melodic-tf2-geometry-msgs - - ros-melodic-visualization-msgs - - ros-melodic-python-orocos-kdl + - ros-noetic-rospy + - ros-noetic-tf + - ros-noetic-tf2-ros + - ros-noetic-tf2-geometry-msgs + - ros-noetic-geometry-msgs + - ros-noetic-visualization-msgs + - python-orocos-kdl + - boost=1.74 - ipywidgets - - pyyaml - - bqplot - - qt=5.9.7 - - sip=4.19.25 - - pip: - - jupyros==0.3.0 - - --editable "{{ root }}" - {% else %} + {% endif %} - pip: - --editable "{{ root }}" - {% endif %} diff --git a/requirements.txt b/requirements.txt index e232065..cebc387 100644 --- a/requirements.txt +++ b/requirements.txt @@ -6,3 +6,4 @@ numpy-quaternion==2020.9.5.14.42.2 numba==0.48.0 llvmlite==0.31.0 anytree==2.8.0 +pooch==1.3.0 diff --git a/requirements_dev.txt b/requirements_dev.txt index 90daeb5..a6b770a 100644 --- a/requirements_dev.txt +++ b/requirements_dev.txt @@ -1,12 +1,13 @@ pip==18.1 wheel==0.32.1 coverage==4.5.1 -Sphinx==2.4.4 +Sphinx==3.5.4 sphinx_rtd_theme==0.4 numpydoc==0.9.1 -sphinx-autosummary-accessors==0.1.2 +sphinx-autosummary-accessors==0.2.0 nbsphinx==0.8.1 matplotlib==3.3.2 +jinja2==2.11.3 pytest==6.2.2 pytest-cov==2.7.1 diff --git a/rigid_body_motion/__init__.py b/rigid_body_motion/__init__.py index 4754c05..f8ecec9 100644 --- a/rigid_body_motion/__init__.py +++ b/rigid_body_motion/__init__.py @@ -1,12 +1,9 @@ """Top-level package for rigid-body-motion.""" __author__ = """Peter Hausamann""" __email__ = "peter.hausamann@tum.de" -__version__ = "0.5.0" -from pathlib import Path +__version__ = "0.6.0" -from pkg_resources import resource_filename - -from . import plot, ros # noqa +from . import io, plot, ros # noqa from .coordinate_systems import ( cartesian_to_polar, cartesian_to_spherical, @@ -39,7 +36,7 @@ register_frame, render_tree, ) -from .utils import qinterp, qinv, qmean, qmul, rotate_vectors +from .utils import ExampleDataStore, qinterp, qinv, qmean, qmul, rotate_vectors try: import rigid_body_motion.accessors # noqa @@ -95,15 +92,7 @@ } -example_data = { - "head": Path(resource_filename("rigid_body_motion", "data/head.nc")), - "left_eye": Path( - resource_filename("rigid_body_motion", "data/left_eye.nc") - ), - "right_eye": Path( - resource_filename("rigid_body_motion", "data/right_eye.nc") - ), -} +example_data = ExampleDataStore() def transform_vectors( diff --git a/rigid_body_motion/data/head.nc b/rigid_body_motion/data/head.nc deleted file mode 100644 index 87ebb0d..0000000 Binary files a/rigid_body_motion/data/head.nc and /dev/null differ diff --git a/rigid_body_motion/data/left_eye.nc b/rigid_body_motion/data/left_eye.nc deleted file mode 100644 index 78cd79a..0000000 Binary files a/rigid_body_motion/data/left_eye.nc and /dev/null differ diff --git a/rigid_body_motion/data/right_eye.nc b/rigid_body_motion/data/right_eye.nc deleted file mode 100644 index 56f2f96..0000000 Binary files a/rigid_body_motion/data/right_eye.nc and /dev/null differ diff --git a/rigid_body_motion/io.py b/rigid_body_motion/io.py new file mode 100644 index 0000000..357c268 --- /dev/null +++ b/rigid_body_motion/io.py @@ -0,0 +1,116 @@ +import numpy as np +from quaternion import as_float_array, from_rotation_vector + + +def load_optitrack(filepath, import_format="numpy"): + """ Load rigid body poses from OptiTrack csv export. + + Parameters + ---------- + filepath: str or path-like + Path to csv file. + + import_format: {"numpy", "pandas", "xarray"}, default "numpy" + Import format for rigid body poses. "numpy" returns a (position, + orientation, timestamps) tuple for each body, "pandas" returns a + DataFrame and "xarray" returns a Dataset. + + Returns + ------- + data_dict: dict + Dictionary with one entry for each rigid body. See ``import_format`` + for the format of each entry. + """ + try: + import pandas as pd + except ImportError: + raise ModuleNotFoundError("Install pandas to use optitrack import") + + # parse header with metadata + header = pd.read_csv(filepath, nrows=1, header=None).values + meta = {k: v for k, v in zip(header[0][0::2], header[0][1::2])} + + # parse body with poses of rigid bodies and marker positions + df = pd.read_csv( + filepath, header=[2, 3, 5, 6], index_col=0, skip_blank_lines=False + ) + + # compute timestamps + timestamps = pd.to_datetime( + meta["Capture Start Time"], format="%Y-%m-%d %I.%M.%S.%f %p" + ) + pd.to_timedelta(df.values[:, 0], unit="s") + + # only import rigid bodies, not markers + df = df["Rigid Body"] + + # set index to timestamps and multi-index levels + df = df.set_index(timestamps).rename_axis("time") + df.columns = df.columns.set_names(["body ID", "motion type", "axis"]) + + # split dataframe into dict with one entry for each rigid body + data_dict = { + idx: gp.xs(idx, level=0, axis=1) + for idx, gp in df.groupby(level=0, axis=1) + } + + # convert cm to m (if applicable) + if meta.get("Length Units", None) == "Centimeters": + for name in data_dict: + data_dict[name]["Position"] /= 100 + + # convert orientation to quaternions + for name in data_dict: + r = np.deg2rad(data_dict[name]["Rotation"].values) + qx = from_rotation_vector( + r[:, 0][:, np.newaxis] * np.array([1, 0, 0])[np.newaxis, :] + ) + qy = from_rotation_vector( + r[:, 1][:, np.newaxis] * np.array([0, 1, 0])[np.newaxis, :] + ) + qz = from_rotation_vector( + r[:, 2][:, np.newaxis] * np.array([0, 0, 1])[np.newaxis, :] + ) + if meta.get("Rotation Type", "XYZ") == "XYZ": + q = as_float_array(qx * qy * qz) + else: + raise ValueError("Unsupported rotation type") + + position = data_dict[name]["Position"] + position.columns = position.columns.str.lower() + orientation = pd.DataFrame( + q, index=position.index, columns=["w", "x", "y", "z"] + ) + data_dict[name] = pd.concat( + {"position": position, "orientation": orientation}, axis=1, + ) + + # return in requested format + if import_format == "pandas": + return data_dict + + elif import_format == "numpy": + return { + k: (v["position"].values, v["orientation"].values, v.index.values) + for k, v in data_dict.items() + } + + elif import_format == "xarray": + import xarray as xr + + for name in data_dict: + position = xr.DataArray( + data_dict[name]["position"], + name="position", + dims=("time", "cartesian_axis"), + ) + orientation = xr.DataArray( + data_dict[name].orientation, + name="orientation", + dims=("time", "quaternion_axis"), + ) + data_dict[name] = xr.merge((position, orientation)) + + return data_dict + + else: + raise ValueError(f"Unsupported import format: {import_format}") diff --git a/rigid_body_motion/plotting.py b/rigid_body_motion/plotting.py index 4808ca6..2065431 100644 --- a/rigid_body_motion/plotting.py +++ b/rigid_body_motion/plotting.py @@ -148,7 +148,7 @@ def plot_reference_frame( return arrows -def plot_points(arr, ax=None, figsize=(6, 6), fmt=None, **kwargs): +def plot_points(arr, ax=None, figsize=(6, 6), fmt="", **kwargs): """ Plot an array of 3D points. Parameters diff --git a/rigid_body_motion/ros/__init__.py b/rigid_body_motion/ros/__init__.py index e6a6e8e..649c27c 100644 --- a/rigid_body_motion/ros/__init__.py +++ b/rigid_body_motion/ros/__init__.py @@ -21,7 +21,7 @@ pass try: - from .io import RosbagReader # noqa + from .io import RosbagReader, RosbagWriter # noqa except ImportError: if os.environ.get("RBM_ROS_DEBUG"): raise diff --git a/rigid_body_motion/ros/io.py b/rigid_body_motion/ros/io.py index 630ade3..8ba4a30 100644 --- a/rigid_body_motion/ros/io.py +++ b/rigid_body_motion/ros/io.py @@ -5,6 +5,7 @@ import rosbag from rigid_body_motion.ros.msg import ( + make_transform_msg, unpack_point_msg, unpack_quaternion_msg, unpack_vector_msg, @@ -68,9 +69,31 @@ def _write_netcdf(ds, filename, dtype="int32"): ds.to_netcdf(filename, encoding=encoding) + def get_topics_and_types(self): + """ Get topics and corresponding message types included in rosbag. + + Returns + ------- + topics: dict + Names of topics and corresponding message types included in the + rosbag. + """ + if self._bag is None: + raise RuntimeError( + "get_topics must be called from within the RosbagReader " + "context manager" + ) + + info = self._bag.get_type_and_topic_info() + + return {k: v[0] for k, v in info[1].items()} + def load_messages(self, topic): """ Load messages from topic as dict. + Only nav_msgs/Odometry and geometry_msgs/TransformStamped topics are + supported so far. + Parameters ---------- topic: str @@ -135,6 +158,9 @@ def load_messages(self, topic): def load_dataset(self, topic, cache=False): """ Load messages from topic as xarray.Dataset. + Only nav_msgs/Odometry and geometry_msgs/TransformStamped topics are + supported so far. + Parameters ---------- topic: str @@ -212,3 +238,127 @@ def export(self, topic, output_file=None): """ ds = self.load_dataset(topic, cache=False) self._write_netcdf(ds, self._get_filename(output_file, "nc")) + + +class RosbagWriter: + """ Writer for motion topics to rosbag files. """ + + def __init__(self, bag_file): + """ Constructor. + + Parameters + ---------- + bag_file: str + Path to rosbag file. + """ + self.bag_file = Path(bag_file) + + self._bag = None + + def __enter__(self): + self._bag = rosbag.Bag(self.bag_file, "w") + return self + + def __exit__(self, exc_type, exc_val, exc_tb): + self._bag.close() + self._bag = None + + def write_transform_stamped( + self, timestamps, translation, rotation, topic, frame, child_frame + ): + """ Write multiple geometry_msgs/TransformStamped messages. + + Parameters + ---------- + timestamps: array_like, shape (n_timestamps,) + Array of timestamps. + + translation: array_like, shape (n_timestamps, 3) + Array of translations. + + rotation: array_like, shape (n_timestamps, 4) + Array of rotations. + + topic: str + Topic of the messages. + + frame: str + Parent frame of the transform. + + child_frame: str + Child frame of the transform. + """ + # check timestamps + timestamps = np.asarray(timestamps) + if timestamps.ndim != 1: + raise ValueError("timestamps must be one-dimensional") + + # check translation + translation = np.asarray(translation) + if translation.shape != (len(timestamps), 3): + raise ValueError( + f"Translation must have shape ({len(timestamps)}, 3), " + f"got {translation.shape}" + ) + + # check rotation + rotation = np.asarray(rotation) + if rotation.shape != (len(timestamps), 4): + raise ValueError( + f"Rotation must have shape ({len(timestamps)}, 4), " + f"got {rotation.shape}" + ) + + # write messages to bag + for ts, t, r in zip(timestamps, translation, rotation): + msg = make_transform_msg(t, r, frame, child_frame, ts) + self._bag.write(topic, msg) + + def write_transform_stamped_dataset( + self, + ds, + topic, + frame, + child_frame, + timestamps="time", + translation="position", + rotation="orientation", + ): + """ Write a dataset as geometry_msgs/TransformStamped messages. + + Parameters + ---------- + ds: xarray.Dataset + Dataset containing timestamps, translation and rotation + + topic: str + Topic of the messages. + + frame: str + Parent frame of the transform. + + child_frame: str + Child frame of the transform. + + timestamps: str, default 'time' + Name of the dimension containing the timestamps. + + translation: str, default 'position' + Name of the variable containing the translation. + + rotation: str, default 'orientation' + Name of the variable containing the rotation. + """ + if np.issubdtype(ds[timestamps].dtype, np.datetime64): + timestamps = ds[timestamps].astype(float) / 1e9 + else: + timestamps = ds[timestamps] + + self.write_transform_stamped( + timestamps, + ds[translation], + ds[rotation], + topic, + frame, + child_frame, + ) diff --git a/rigid_body_motion/ros/transformer.py b/rigid_body_motion/ros/transformer.py index 7fb05a1..ef68382 100644 --- a/rigid_body_motion/ros/transformer.py +++ b/rigid_body_motion/ros/transformer.py @@ -34,7 +34,7 @@ ) -class Transformer(object): +class Transformer: def __init__(self, cache_time=None): """ Constructor. @@ -481,12 +481,22 @@ def _spin_blocking(self): while not rospy.is_shutdown() and not self.stopped: self.publish() self.idx = (self.idx + 1) % len(self.timestamps) - dt = ( - self.timestamps.values[self.idx].astype(float) / 1e9 - - self.timestamps.values[self.idx - 1].astype(float) / 1e9 - if self.idx > 0 - else 0.0 - ) + if isinstance(self.timestamps, pd.DatetimeIndex): + dt = ( + self.timestamps.values[self.idx].astype(float) / 1e9 + - self.timestamps.values[self.idx - 1].astype(float) + / 1e9 + if self.idx > 0 + else 0.0 + ) + else: + dt = float( + self.timestamps.values[self.idx] + - self.timestamps.values[self.idx - 1] + if self.idx > 0 + else 0.0 + ) + rospy.sleep(dt) else: rospy.spin() diff --git a/rigid_body_motion/utils.py b/rigid_body_motion/utils.py index 7986a0b..9199c41 100644 --- a/rigid_body_motion/utils.py +++ b/rigid_body_motion/utils.py @@ -1,6 +1,7 @@ """""" import operator from functools import reduce +from pathlib import Path import numpy as np from quaternion import as_float_array, as_quat_array, quaternion @@ -304,3 +305,45 @@ def is_dataset(obj, require_attrs=None): ] return all([hasattr(obj, name) for name in require_attrs]) + + +class ExampleDataStore: + """ Storage interface for example data. """ + + base_url = "https://github.com/phausamann/rbm-data/raw/main/" + + registry = { + "head": ( + "head.nc", + "874eddaa51bf775c7311f0046613c6f969adef6e34fe4aea2e1248a75ed3fee3", + ), + "left_eye": ( + "left_eye.nc", + "56d5488fb8d3ff08450663ed0136ac659c1d51eb5340a7e3ed52f5ecf019139c", + ), + "right_eye": ( + "right_eye.nc", + "b038c4cb2f6932e4334f135cdf7e24ff9c3b5789977b2ae0206ba80acf54c647", + ), + "rosbag": ( + "example.bag", + "8d27f5e554f5a0e02e0bec59b60424e582f6104380f96c3f226b4d85c107f2bc", + ), + } + + def __getitem__(self, item): + try: + import pooch + except ImportError: + raise ModuleNotFoundError( + "pooch must be installed to load example data" + ) + + try: + dataset, known_hash = self.registry[item] + except KeyError: + raise KeyError(f"'{item}' is not a valid example dataset") + + return Path( + pooch.retrieve(url=self.base_url + dataset, known_hash=known_hash) + ) diff --git a/setup.py b/setup.py index 9b2d9df..d36104e 100644 --- a/setup.py +++ b/setup.py @@ -35,6 +35,6 @@ name="rigid-body-motion", packages=find_packages(exclude=["tests"]), url="https://github.com/phausamann/rigid-body-motion", - version="0.5.0", + version="0.6.0", zip_safe=False, ) diff --git a/tests/conftest.py b/tests/conftest.py index a3c5fbb..dec25dd 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -146,6 +146,7 @@ def head_dataset(): """""" xr = pytest.importorskip("xarray") pytest.importorskip("netCDF4") + pytest.importorskip("pooch") return xr.load_dataset(rbm.example_data["head"]) @@ -155,6 +156,7 @@ def left_eye_dataset(): """""" xr = pytest.importorskip("xarray") pytest.importorskip("netCDF4") + pytest.importorskip("pooch") return xr.load_dataset(rbm.example_data["left_eye"]) @@ -175,6 +177,13 @@ def rosbag_path(): shutil.rmtree(test_data_dir / "cache", ignore_errors=True) +@pytest.fixture() +def optitrack_path(): + """""" + yield test_data_dir / "optitrack.csv" + shutil.rmtree(test_data_dir / "cache", ignore_errors=True) + + @pytest.fixture() def export_folder(): """""" diff --git a/tests/test_data/optitrack.csv b/tests/test_data/optitrack.csv new file mode 100644 index 0000000..c7f5581 --- /dev/null +++ b/tests/test_data/optitrack.csv @@ -0,0 +1,234 @@ +Format Version,1.22,Take Name,Test,Capture Frame Rate,240,Export Frame Rate,60,Capture Start Time,2020-06-16 07.51.41.245 PM,Total Frames in Take,904,Total Exported Frames,227,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,, +,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,, +,,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Rigid Body,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker,Marker +,,RigidBody 01,RigidBody 01,RigidBody 01,RigidBody 01,RigidBody 01,RigidBody 01,RigidBody 02,RigidBody 02,RigidBody 02,RigidBody 02,RigidBody 02,RigidBody 02,RigidBody 01:Marker1,RigidBody 01:Marker1,RigidBody 01:Marker1,RigidBody 01:Marker2,RigidBody 01:Marker2,RigidBody 01:Marker2,RigidBody 02:Marker2,RigidBody 02:Marker2,RigidBody 02:Marker2,RigidBody 01:Marker3,RigidBody 01:Marker3,RigidBody 01:Marker3,RigidBody 02:Marker3,RigidBody 02:Marker3,RigidBody 02:Marker3,RigidBody 01:Marker4,RigidBody 01:Marker4,RigidBody 01:Marker4,RigidBody 02:Marker4,RigidBody 02:Marker4,RigidBody 02:Marker4,RigidBody 02:Marker5,RigidBody 02:Marker5,RigidBody 02:Marker5,Unlabeled 30388,Unlabeled 30388,Unlabeled 30388,Unlabeled 30389,Unlabeled 30389,Unlabeled 30389,Unlabeled 30390,Unlabeled 30390,Unlabeled 30390 +,,751B74DC4DA011E942374A447B10C986,751B74DC4DA011E942374A447B10C986,751B74DC4DA011E942374A447B10C986,751B74DC4DA011E942374A447B10C986,751B74DC4DA011E942374A447B10C986,751B74DC4DA011E942374A447B10C986,5CDD43C6912211E942374A447B10D786,5CDD43C6912211E942374A447B10D786,5CDD43C6912211E942374A447B10D786,5CDD43C6912211E942374A447B10D786,5CDD43C6912211E942374A447B10D786,5CDD43C6912211E942374A447B10D786,FB9B0,FB9B0,FB9B0,75DABDADB04511EA42374A447B10EE86,75DABDADB04511EA42374A447B10EE86,75DABDADB04511EA42374A447B10EE86,FBAA0,FBAA0,FBAA0,75DABDAEB04511EA42374A447B10EE86,75DABDAEB04511EA42374A447B10EE86,75DABDAEB04511EA42374A447B10EE86,FB980,FB980,FB980,FB9A0,FB9A0,FB9A0,FBC10,FBC10,FBC10,FB9C0,FB9C0,FB9C0,FBCD0,FBCD0,FBCD0,FBD40,FBD40,FBD40,FBD50,FBD50,FBD50 +,,Rotation,Rotation,Rotation,Position,Position,Position,Rotation,Rotation,Rotation,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position,Position +Frame,Time (Seconds),X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z,X,Y,Z +0,0,-5.911591,29.923708,2.317891,-10.650912,155.687256,-27.749178,-0.059946,0.921748,0.35524,1.707759,155.829163,174.712875,-7.707328,157.726471,-31.802454,-13.481358,157.757736,-27.712175,-77.503494,99.802017,179.938293,-16.89493,156.646561,-24.191639,82.867477,210.939407,174.263733,-4.545262,150.60817,-27.274504,84.56871,101.468643,177.373367,-75.951958,209.549973,177.534866,6.857496,167.035782,-22.072235,13.202849,161.625412,-19.902033,,, +1,0.016667,-5.885699,29.938076,2.334441,-10.655323,155.690857,-27.733902,-0.059499,0.922225,0.355014,1.708825,155.829697,174.713913,-7.713607,157.73291,-31.785843,-13.48622,157.760696,-27.694887,-77.502625,99.801979,179.939987,-16.898575,156.646652,-24.174074,82.869957,210.93898,174.264709,-4.548605,150.61319,-27.264353,84.569702,101.469612,177.373596,-75.952538,209.55162,177.540726,6.85028,167.039719,-22.051155,13.196582,161.63147,-19.885588,,, +2,0.033333,-5.854484,29.946001,2.338602,-10.65933,155.695389,-27.719658,-0.060271,0.922556,0.355327,1.707957,155.830093,174.713196,-7.718393,157.740479,-31.771078,-13.490322,157.76506,-27.679031,-77.502151,99.801147,179.94017,-16.902117,156.648819,-24.158379,82.867226,210.94043,174.259735,-4.552174,150.617401,-27.253613,84.568314,101.469398,177.374054,-75.952705,209.552307,177.539536,6.846669,167.044403,-22.031979,13.192686,161.636627,-19.86931,,, +3,0.05,-5.830677,29.964106,2.350069,-10.661151,155.701294,-27.705717,-0.061938,0.921708,0.35526,1.708287,155.829681,174.711639,-7.721925,157.748596,-31.756762,-13.49242,157.770538,-27.663084,-77.502647,99.800835,179.939911,-16.902887,156.651993,-24.141874,82.869514,210.939484,174.261124,-4.553259,150.624115,-27.244503,84.569,101.469543,177.374313,-75.95369,209.55188,177.535934,6.844976,167.049255,-22.015015,13.189116,161.641144,-19.852501,,, +4,0.066667,-5.8102,29.977339,2.358178,-10.66293,155.707886,-27.693665,-0.062087,0.923554,0.355327,1.707352,155.830246,174.710541,-7.723901,157.757126,-31.744873,-13.494391,157.776825,-27.649462,-77.504387,99.80085,179.942062,-16.903896,156.656464,-24.127903,82.868736,210.93988,174.256393,-4.554733,150.631393,-27.236378,84.569138,101.4702,177.372116,-75.955101,209.552383,177.539337,6.842272,167.05484,-21.997749,13.186829,161.646088,-19.837994,,, +5,0.083333,-5.797923,29.985689,2.365698,-10.663685,155.713791,-27.68355,-0.062568,0.922523,0.355518,1.707589,155.830338,174.709076,-7.725099,157.764816,-31.734838,-13.495344,157.782455,-27.638325,-77.503845,99.801407,179.940247,-16.904186,156.660751,-24.116547,82.869133,210.939743,174.259109,-4.555045,150.637741,-27.228611,84.570152,101.470634,177.371521,-75.95546,209.55217,177.533569,6.840113,167.060242,-21.982193,13.185356,161.649338,-19.826096,,, +6,0.1,-5.817714,30.040478,2.423967,-10.660331,155.718918,-27.672607,-0.06297,0.92262,0.355177,1.707397,155.83017,174.708603,-7.726599,157.771301,-31.724995,-13.493553,157.785355,-27.624098,-77.503761,99.80162,179.939621,-16.897852,156.660431,-24.098959,82.869652,210.939667,174.257355,-4.548051,150.649368,-27.226654,84.569183,101.469376,177.372787,-75.955826,209.552902,177.534454,6.83639,167.064789,-21.969503,13.183339,161.65242,-19.815636,,, +7,0.116667,-5.801284,30.058132,2.42983,-10.661947,155.723694,-27.662849,-0.061642,0.923098,0.355056,1.708411,155.829956,174.711227,-7.729436,157.777847,-31.715822,-13.495271,157.789963,-27.612749,-77.503342,99.801567,179.939911,-16.898397,156.663635,-24.086914,82.870636,210.940033,174.257584,-4.549201,150.654144,-27.220409,84.569908,101.468361,177.375366,-75.954369,209.552048,177.542145,6.833564,167.068405,-21.958912,13.183279,161.656601,-19.810009,,, +8,0.133333,-5.793954,30.086086,2.445442,-10.664587,155.727463,-27.652508,-0.060617,0.923598,0.355612,1.707989,155.8302,174.710953,-7.734562,157.782867,-31.705561,-13.498267,157.793182,-27.600416,-77.502907,99.801659,179.94046,-16.899389,156.665298,-24.073151,82.869621,210.940598,174.260742,-4.550928,150.65947,-27.215143,84.570061,101.470139,177.370743,-75.95475,209.551361,177.539139,6.829044,167.072342,-21.95042,13.182819,161.662491,-19.808388,,, +9,0.15,-5.780785,30.117336,2.459309,-10.667038,155.73172,-27.643785,-0.060584,0.924033,0.355709,1.708145,155.82959,174.713058,-7.739954,157.788834,-31.69772,-13.501005,157.796997,-27.589369,-77.502808,99.798431,179.945465,-16.899963,156.667358,-24.060583,82.869339,210.940262,174.260071,-4.552333,150.664398,-27.211454,84.569969,101.469353,177.373123,-75.954941,209.551926,177.543716,6.825368,167.076385,-21.94516,13.182202,161.667755,-19.808393,,, +10,0.166667,-5.789045,30.129652,2.474937,-10.671542,155.738174,-27.6371,-0.057185,0.924934,0.355666,1.708318,155.829422,174.716583,-7.745625,157.795395,-31.691471,-13.505936,157.802841,-27.582029,-77.503708,99.798187,179.946655,-16.903818,156.672501,-24.052423,82.869431,210.940979,174.264389,-4.555896,150.672607,-27.206594,84.570053,101.468513,177.373032,-75.953232,209.550476,177.551102,6.823488,167.080276,-21.941454,13.182028,161.672348,-19.811672,,, +11,0.183333,-5.782203,30.155811,2.492302,-10.67296,155.743256,-27.633301,-0.05987,0.923978,0.355693,1.708033,155.829941,174.714035,-7.749621,157.80191,-31.688171,-13.507771,157.807297,-27.576303,-77.50251,99.798882,179.946732,-16.903709,156.675262,-24.045376,82.86972,210.941177,174.264709,-4.556002,150.679047,-27.207315,84.569275,101.469208,177.372452,-75.954369,209.552032,177.542114,6.822504,167.085129,-21.940125,13.183279,161.67807,-19.816416,,, +12,0.2,-5.768108,30.170067,2.499402,-10.674046,155.748123,-27.633015,-0.060505,0.924223,0.355701,1.708185,155.830124,174.714066,-7.75151,157.808533,-31.688515,-13.509009,157.81192,-27.57465,-77.501602,99.798523,179.948669,-16.903944,156.678528,-24.043194,82.868813,210.940674,174.263885,-4.556605,150.684113,-27.209955,84.56987,101.469185,177.372116,-75.954506,209.553391,177.540222,6.82234,167.087509,-21.939676,13.186024,161.681717,-19.822365,,, +13,0.216667,-5.754317,30.195423,2.504838,-10.673534,155.751465,-27.633646,-0.059682,0.923989,0.35565,1.708439,155.831161,174.713867,-7.75293,157.813248,-31.690029,-13.508548,157.81514,-27.573416,-77.501251,99.797775,179.948471,-16.901857,156.680603,-24.040762,82.868454,210.941284,174.263046,-4.555638,150.687454,-27.214706,84.569809,101.470421,177.371674,-75.954468,209.55574,177.542328,6.825165,167.088348,-21.942053,13.18979,161.681259,-19.829809,,, +14,0.233333,-5.741049,30.203674,2.496516,-10.673194,155.75351,-27.636751,-0.062342,0.922809,0.355849,1.707567,155.829941,174.712082,-7.75262,157.815399,-31.693502,-13.507912,157.817581,-27.575823,-77.502785,99.799515,179.946854,-16.900917,156.682953,-24.042906,82.870399,210.93988,174.268936,-4.555996,150.688644,-27.219301,84.569565,101.470718,177.370544,-75.956383,209.552002,177.533005,6.830078,167.086487,-21.947998,13.193589,161.677917,-19.837929,,, +15,0.25,-5.738342,30.224209,2.486852,-10.671408,155.753479,-27.640778,-0.062742,0.92258,0.3559,1.707177,155.830383,174.709839,-7.752257,157.814972,-31.698402,-13.505732,157.818054,-27.578957,-77.502487,99.800537,179.942245,-16.897734,156.684174,-24.044838,82.86898,210.941269,174.261948,-4.554905,150.687271,-27.225107,84.56913,101.470078,177.372314,-75.956566,209.552353,177.532379,6.836124,167.081772,-21.956802,13.198258,161.672958,-19.847185,,, +16,0.266667,-5.742171,30.226028,2.470908,-10.670789,155.751785,-27.647596,-0.061462,0.922041,0.35603,1.707376,155.829773,174.709213,-7.751181,157.811829,-31.705845,-13.504612,157.817062,-27.586184,-77.5019,99.800072,179.941376,-16.896862,156.684738,-24.051804,82.87011,210.940247,174.26944,-4.555476,150.684052,-27.230755,84.570107,101.46946,177.369232,-75.956985,209.551422,177.528244,,,,13.20356,161.665131,-19.859409,,, +17,0.283333,-5.722419,30.257301,2.448801,-10.66939,155.747131,-27.654699,-0.060915,0.921868,0.355576,1.707857,155.830566,174.711472,-7.751816,157.807129,-31.714176,-13.502383,157.813492,-27.59153,-77.501938,99.802658,179.938293,-16.893267,156.681946,-24.055592,82.87085,210.940308,174.266647,-4.555571,150.676422,-27.241219,84.569809,101.47036,177.373215,-75.956818,209.552292,177.537704,,,,13.206776,161.655518,-19.87542,,, +18,0.3,-5.745776,30.272453,2.439143,-10.67005,155.74115,-27.663195,-0.063025,0.921782,0.355786,1.707409,155.830902,174.707474,-7.752658,157.798904,-31.724754,-13.502672,157.808044,-27.60034,-77.502792,99.800835,179.941055,-16.892872,156.678802,-24.063002,82.870308,210.940887,174.263977,-4.557044,150.66954,-27.248669,84.570786,101.469978,177.371979,-75.957664,209.553604,177.528427,6.851535,167.059021,-22.000711,13.208567,161.648102,-19.89683,,, +19,0.316667,-5.78682,30.305614,2.44655,-10.671288,155.731705,-27.672365,-0.061283,0.920532,0.355464,1.708066,155.830429,174.709305,-7.755878,157.787109,-31.737446,-13.503983,157.798462,-27.60919,-77.503288,99.801018,179.93808,-16.892046,156.671371,-24.06913,82.870438,210.939713,174.266174,-4.557715,150.660736,-27.258167,84.57048,101.470505,177.372925,-75.955727,209.552841,177.531723,6.852462,167.05098,-22.021729,13.212193,161.642319,-19.921738,,, +20,0.333333,-5.798968,30.289635,2.408497,-10.679673,155.720184,-27.683207,-0.065268,0.919747,0.355889,1.70799,155.829651,174.706299,-7.762946,157.773804,-31.750568,-13.511269,157.788528,-27.622116,-77.501884,99.802208,179.936737,-16.901129,156.665192,-24.082575,82.871666,210.939667,174.266098,-4.567997,150.64389,-27.261847,84.570656,101.470123,177.373077,-75.956993,209.55072,177.520889,6.846762,167.042786,-22.04771,13.211966,161.636139,-19.949018,,, +21,0.35,-5.843351,30.338518,2.429379,-10.685352,155.70932,-27.690882,-0.061669,0.920567,0.355404,1.708358,155.829041,174.711685,-7.772268,157.761246,-31.762018,-13.517362,157.777054,-27.628517,-77.502228,99.801826,179.937057,-16.903849,156.65506,-24.085327,82.871178,210.937836,174.268173,-4.572385,150.634827,-27.27206,84.570885,101.469162,177.37532,-75.956238,209.550827,177.535126,6.83996,167.036819,-22.0783,13.21102,161.633545,-19.981163,,, +22,0.366667,-5.89084,30.362797,2.45232,-10.692047,155.699448,-27.700727,-0.064045,0.920202,0.356217,1.708535,155.828506,174.709564,-7.782092,157.749161,-31.774187,-13.52465,157.766373,-27.638363,-77.502235,99.800362,179.938583,-16.90918,156.645569,-24.092928,82.872322,210.939362,174.268158,-4.577341,150.627075,-27.281448,84.570267,101.470856,177.372879,-75.955704,209.547852,177.527328,6.834088,167.035034,-22.111338,13.208702,161.636093,-20.015318,,, +23,0.383333,-5.941385,30.390766,2.475792,-10.697192,155.687668,-27.709118,-0.062755,0.920528,0.355549,1.708383,155.828995,174.710922,-7.788823,157.735138,-31.785494,-13.530384,157.753784,-27.646669,-77.502274,99.802147,179.938858,-16.912725,156.634354,-24.098711,82.871658,210.937683,174.269577,-4.581141,150.618073,-27.290213,84.571251,101.46978,177.374603,-75.95636,209.550339,177.530411,6.827566,167.032516,-22.146141,13.206394,161.643433,-20.050514,,, +24,0.4,-6.012234,30.436344,2.505827,-10.701422,155.674728,-27.716177,-0.0625,0.920338,0.355285,1.708881,155.829987,174.71022,-7.797307,157.718414,-31.796343,-13.535319,157.739868,-27.65336,-77.502235,99.803711,179.935318,-16.914276,156.62265,-24.10148,82.872101,210.939056,174.266632,-4.583354,150.60849,-27.298105,84.571373,101.469696,177.375458,-75.955704,209.551376,177.532074,6.818757,167.029861,-22.180387,13.20552,161.650177,-20.085484,,, +25,0.416667,-6.094106,30.473091,2.527032,-10.707399,155.663864,-27.724514,-0.067014,0.920807,0.355914,1.708012,155.828781,174.706207,-7.806027,157.703186,-31.809103,-13.54177,157.728363,-27.662357,-77.501984,99.802925,179.937393,-16.918064,156.614716,-24.106825,82.871567,210.937744,174.262283,-4.587974,150.599869,-27.304516,84.571297,101.470612,177.372742,-75.957191,209.54921,177.521942,6.811168,167.026398,-22.210798,13.206051,161.653656,-20.118004,,, +26,0.433333,-6.160929,30.506577,2.541898,-10.711237,155.653473,-27.733019,-0.065309,0.920526,0.356057,1.70785,155.828674,174.707077,-7.812872,157.689163,-31.821304,-13.5459,157.71759,-27.671284,-77.502151,99.803375,179.934738,-16.919863,156.607086,-24.11256,82.870636,210.938553,174.263626,-4.590749,150.590836,-27.311451,84.571823,101.469315,177.374573,-75.956963,209.548096,177.524109,6.807558,167.021652,-22.237862,13.205714,161.652603,-20.145475,,, +27,0.45,-6.219069,30.533138,2.544494,-10.711931,155.644257,-27.741009,-0.063262,0.920927,0.355378,1.708163,155.829178,174.710571,-7.81518,157.675247,-31.832117,-13.546543,157.708466,-27.680004,-77.50296,99.802139,179.940338,-16.918859,156.601532,-24.11861,82.871399,210.938553,174.268509,-4.591518,150.582611,-27.317902,84.570488,101.468918,177.374481,-75.955139,209.550308,177.528564,6.808527,167.018021,-22.260014,13.207683,161.650345,-20.165998,,, +28,0.466667,-6.25331,30.533958,2.531515,-10.710409,155.636902,-27.74818,-0.064647,0.921246,0.35558,1.708401,155.829483,174.708908,-7.813629,157.664627,-31.840828,-13.544618,157.701706,-27.688663,-77.502586,99.803223,179.937149,-16.917177,156.597977,-24.126507,82.870743,210.938232,174.261353,-4.590858,150.574081,-27.321133,84.571465,101.470474,177.374405,-75.955345,209.550186,177.52951,6.811883,167.011963,-22.278843,13.211592,161.645889,-20.180666,,, +29,0.483333,-6.269772,30.528658,2.511122,-10.706457,155.632706,-27.755758,-0.061801,0.920709,0.355507,1.708791,155.829193,174.709702,-7.808942,157.657166,-31.84796,-13.540066,157.698364,-27.697563,-77.502411,99.802483,179.935699,-16.913395,156.597275,-24.135315,82.871735,210.939148,174.266556,-4.588634,150.568741,-27.326063,84.572052,101.468109,177.375549,-75.954987,209.549759,177.531403,6.81924,167.005356,-22.294304,13.216123,161.639725,-20.189445,,, +30,0.5,-6.276155,30.506641,2.484937,-10.701668,155.632004,-27.765953,-0.05932,0.920925,0.355137,1.71005,155.829346,174.712021,-7.802255,157.654205,-31.857418,-13.534578,157.698685,-27.709675,-77.501144,99.802544,179.934906,-16.909807,156.600006,-24.148481,82.871803,210.93779,174.266449,-4.585672,150.565765,-27.331682,84.573433,101.468216,177.376633,-75.953819,209.551361,177.539749,6.828575,167.000336,-22.302803,13.220363,161.634064,-20.194727,,, +31,0.516667,-6.274186,30.486567,2.461193,-10.695747,155.633835,-27.775824,-0.059871,0.920434,0.355118,1.708744,155.82988,174.711426,-7.794522,157.65416,-31.866211,-13.528024,157.701416,-27.721006,-77.502487,99.803307,179.934784,-16.904978,156.604431,-24.160927,82.871231,210.938766,174.269089,-4.581442,150.565826,-27.338409,84.571037,101.469124,177.374084,-75.954605,209.551376,177.535309,6.838296,166.997406,-22.305876,13.225158,161.628265,-20.194721,,, +32,0.533333,-6.269156,30.460497,2.435977,-10.68921,155.637711,-27.785631,-0.057519,0.921269,0.355493,1.709265,155.829315,174.713074,-7.785027,157.656464,-31.875294,-13.520837,157.706223,-27.732491,-77.501602,99.800743,179.936035,-16.899908,156.610825,-24.173931,82.871506,210.938782,174.270081,-4.576764,150.567673,-27.344366,84.571884,101.468872,177.373978,-75.954918,209.551025,177.542786,6.848247,166.99469,-22.305346,13.230414,161.622238,-20.19142,,, +33,0.55,-6.25738,30.441013,2.415722,-10.682187,155.641434,-27.793186,-0.060241,0.920043,0.355246,1.709031,155.829666,174.710739,-7.775463,157.659729,-31.88192,-13.513284,157.710709,-27.741041,-77.503433,99.801407,179.936722,-16.893967,156.616119,-24.183767,82.871445,210.938843,174.268417,-4.571247,150.569855,-27.349934,84.571922,101.469246,177.374893,-75.954002,209.55127,177.533142,6.857029,166.995102,-22.303009,13.234737,161.616486,-20.185465,,, +34,0.566667,-6.260243,30.497713,2.448112,-10.670414,155.64566,-27.796904,-0.061004,0.920156,0.354982,1.709045,155.829391,174.710617,-7.768773,157.664154,-31.885933,-13.502233,157.713837,-27.741333,-77.503242,99.800003,179.938461,-16.878813,156.617142,-24.180815,82.870949,210.938217,174.264999,-4.557833,150.577957,-27.362925,84.571495,101.468048,177.376694,-75.953766,209.552597,177.533554,6.864942,166.996521,-22.298389,13.23853,161.6129,-20.177532,,, +35,0.583333,-6.232895,30.473536,2.428031,-10.665999,155.651657,-27.801556,-0.061647,0.919756,0.355072,1.709078,155.830017,174.708588,-7.761879,157.670898,-31.88932,-13.497316,157.720551,-27.746647,-77.50325,99.800964,179.937225,-16.875788,156.623642,-24.187984,82.871147,210.93869,174.265198,-4.554732,150.581894,-27.365917,84.57058,101.47036,177.372314,-75.953117,209.552689,177.527756,6.871555,166.998352,-22.293678,13.240905,161.610458,-20.170099,,, +36,0.6,-6.208628,30.449461,2.41107,-10.663203,155.657257,-27.803759,-0.062583,0.919648,0.355245,1.70883,155.829788,174.708954,-7.756572,157.677002,-31.890074,-13.494115,157.72673,-27.749544,-77.50399,99.800934,179.939148,-16.874399,156.629532,-24.192686,82.873306,210.939072,174.269348,-4.553131,150.586121,-27.366749,84.571854,101.468971,177.375748,-75.955452,209.55162,177.528076,6.875854,167.000702,-22.287321,13.242785,161.609329,-20.162403,,, +37,0.616667,-6.183892,30.436543,2.396346,-10.661706,155.661469,-27.80267,-0.064151,0.918208,0.355583,1.708554,155.829117,174.70871,-7.753693,157.682449,-31.888359,-13.492227,157.731476,-27.748533,-77.50341,99.800171,179.938477,-16.873608,156.633881,-24.192846,82.87188,210.938812,174.270035,-4.552415,150.588409,-27.36508,84.571671,101.468811,177.378113,-75.955132,209.55069,177.521561,6.878872,167.001892,-22.281221,13.243005,161.608597,-20.154196,,, +38,0.633333,-6.163507,30.439566,2.388987,-10.661691,155.665207,-27.798182,-0.061636,0.919814,0.355546,1.70878,155.828583,174.710541,-7.75357,157.686707,-31.883198,-13.491967,157.735519,-27.74333,-77.50412,99.799713,179.939697,-16.873331,156.637283,-24.187824,82.871292,210.938614,174.269257,-4.553118,150.591522,-27.362541,84.572525,101.467766,177.377075,-75.953659,209.549454,177.528152,6.879049,167.003235,-22.2743,13.243511,161.608597,-20.148176,,, +39,0.65,-6.142158,30.43722,2.381729,-10.663143,155.669159,-27.791321,-0.065956,0.918847,0.355872,1.708676,155.827316,174.709854,-7.755262,157.691574,-31.875143,-13.493209,157.739746,-27.735979,-77.50322,99.799225,179.942017,-16.874872,156.640762,-24.180988,82.872993,210.937958,174.272125,-4.555022,150.594589,-27.356836,84.571739,101.467491,177.378586,-75.955048,209.547501,177.520035,6.878914,167.004776,-22.266861,13.243654,161.609161,-20.14249,,, +40,0.666667,-6.100591,30.368967,2.317913,-10.670911,155.675339,-27.784979,-0.063759,0.919603,0.355768,1.708631,155.828979,174.709259,-7.756945,157.697586,-31.866148,-13.499329,157.748276,-27.732944,-77.502579,99.799332,179.940796,-16.886473,156.65152,-24.182486,82.872894,210.938721,174.271317,-4.566767,150.594009,-27.341812,84.571358,101.469162,177.374985,-75.956329,209.55072,177.52507,6.878456,167.0065,-22.257751,13.244372,161.609589,-20.135784,,, +41,0.683333,-6.071459,30.3799,2.30001,-10.671918,155.681885,-27.775547,-0.062664,0.920202,0.355463,1.708618,155.828262,174.711395,-7.757613,157.704926,-31.856785,-13.499729,157.755615,-27.722328,-77.502647,99.800476,179.939621,-16.886618,156.658585,-24.171711,82.871719,210.938614,174.268692,-4.569182,150.598602,-27.335081,84.571426,101.466599,177.378754,-75.955017,209.549454,177.530548,6.879832,167.006683,-22.247732,13.244671,161.609024,-20.128805,,, +42,0.7,-6.034113,30.385384,2.283219,-10.672609,155.68869,-27.765316,-0.06068,0.921519,0.355683,1.708094,155.829071,174.710541,-7.75809,157.713501,-31.845802,-13.499875,157.763138,-27.710857,-77.503761,99.799622,179.941727,-16.886808,156.665207,-24.160561,82.87265,210.938766,174.272308,-4.571099,150.603348,-27.327686,84.57122,101.469254,177.371216,-75.956436,209.550186,177.53299,6.882593,167.007645,-22.235765,13.246112,161.606339,-20.120716,,, +43,0.716667,-6.004527,30.394567,2.262921,-10.673217,155.696899,-27.753794,-0.057187,0.923398,0.355129,1.708084,155.828506,174.715012,-7.758421,157.722443,-31.833782,-13.49981,157.772217,-27.698278,-77.503952,99.799057,179.94313,-16.886642,156.674194,-24.147919,82.871735,210.937378,174.27066,-4.573331,150.609512,-27.318836,84.570107,101.468315,177.371307,-75.955711,209.550568,177.547775,6.886338,167.00798,-22.221724,13.24866,161.604126,-20.111401,,, +44,0.733333,-5.972061,30.409376,2.242686,-10.672142,155.704529,-27.741219,-0.058603,0.922097,0.355006,1.708355,155.828995,174.714401,-7.757866,157.730835,-31.821341,-13.498038,157.780777,-27.684259,-77.50412,99.8004,179.941391,-16.884432,156.68248,-24.133564,82.872063,210.937805,174.269836,-4.573788,150.614624,-27.309195,84.569359,101.46991,177.371735,-75.954849,209.550934,177.543945,6.893037,167.00824,-22.207006,13.251835,161.602158,-20.099514,,, +45,0.75,-5.936036,30.420713,2.228334,-10.670238,155.71225,-27.727737,-0.059873,0.920125,0.355212,1.708698,155.828674,174.712708,-7.756142,157.740387,-31.807858,-13.495636,157.789124,-27.669245,-77.503357,99.799156,179.938293,-16.881672,156.68985,-24.118509,82.873047,210.938477,174.270416,-4.572906,150.6203,-27.298939,84.57029,101.467896,177.377457,-75.95594,209.551025,177.540176,6.899716,167.008133,-22.191753,13.256657,161.598877,-20.085352,,, +46,0.766667,-5.904432,30.435614,2.201704,-10.668167,155.720627,-27.714474,-0.061836,0.920661,0.355642,1.707666,155.829346,174.708908,-7.754292,157.749481,-31.795506,-13.492666,157.798691,-27.654707,-77.502563,99.801544,179.935379,-16.878397,156.699722,-24.103584,82.872215,210.939285,174.267776,-4.572529,150.625198,-27.287785,84.569466,101.469597,177.372406,-75.957657,209.550568,177.532455,6.906314,167.009308,-22.17672,13.262863,161.596512,-20.070135,,, +47,0.783333,-5.863067,30.445469,2.177435,-10.6651,155.730103,-27.700954,-0.058755,0.920505,0.355361,1.708424,155.829575,174.713974,-7.751041,157.75972,-31.781563,-13.488801,157.809204,-27.639759,-77.502762,99.800369,179.938171,-16.874474,156.709732,-24.088739,82.871437,210.938293,174.2724,-4.571342,150.632111,-27.277542,84.570709,101.469673,177.375504,-75.956139,209.552078,177.541199,6.913295,167.010162,-22.160852,13.268126,161.593994,-20.054657,,, +48,0.8,-5.829533,30.474276,2.154045,-10.661671,155.739838,-27.686396,-0.057596,0.921163,0.354598,1.708552,155.830353,174.713165,-7.748681,157.770218,-31.768209,-13.484508,157.820053,-27.623102,-77.503494,99.799332,179.939987,-16.868975,156.720596,-24.070927,82.872169,210.938553,174.269363,-4.569565,150.638779,-27.267307,84.570107,101.468147,177.375336,-75.955978,209.555359,177.545059,6.921029,167.012268,-22.144207,13.273203,161.592316,-20.041775,,, +49,0.816667,-5.790094,30.481861,2.133585,-10.65896,155.75145,-27.671894,-0.06142,0.921532,0.355392,1.708101,155.828781,174.711197,-7.744387,157.782394,-31.753248,-13.481125,157.832535,-27.607262,-77.502663,99.801003,179.938721,-16.865587,156.732361,-24.055304,82.872055,210.938995,174.267838,-4.568789,150.648987,-27.256668,84.570122,101.467407,177.374985,-75.956253,209.550217,177.536041,6.930283,167.014618,-22.127131,13.279149,161.591522,-20.029461,,, +50,0.833333,-5.777664,30.554722,2.169081,-10.650691,155.763458,-27.654188,-0.057314,0.923615,0.355783,1.708704,155.829208,174.714203,-7.74087,157.795898,-31.736752,-13.473608,157.843369,-27.584726,-77.502289,99.799347,179.94075,-16.852936,156.739944,-24.028894,82.871178,210.940262,174.266983,-4.558917,150.665314,-27.251846,84.571053,101.468658,177.372604,-75.955185,209.550217,177.54805,6.940199,167.017853,-22.110441,13.286641,161.593002,-20.018917,,, +51,0.85,-5.751327,30.577839,2.158218,-10.64829,155.774765,-27.638924,-0.055894,0.922495,0.355574,1.709037,155.830063,174.715485,-7.7405,157.807861,-31.720617,-13.470756,157.855225,-27.567619,-77.502411,99.80043,179.939896,-16.84894,156.75119,-24.010887,82.872025,210.939865,174.272812,-4.557447,150.675446,-27.241087,84.572372,101.469299,177.374176,-75.955795,209.551743,177.549362,6.946644,167.021744,-22.095772,13.29318,161.594086,-20.009876,,, +52,0.866667,-5.750031,30.582951,2.153723,-10.647407,155.785721,-27.624565,-0.058898,0.922202,0.355273,1.709625,155.828506,174.71524,-7.73949,157.818512,-31.705839,-13.469709,157.866409,-27.553066,-77.502846,99.799492,179.941177,-16.847687,156.76268,-23.996037,82.872345,210.937469,174.267288,-4.557268,150.686356,-27.227661,84.5718,101.469246,177.375366,-75.954109,209.550308,177.547211,6.953969,167.025925,-22.083012,13.3004,161.595566,-20.001053,,, +53,0.883333,-5.735837,30.604561,2.143667,-10.64487,155.794205,-27.60981,-0.06022,0.922832,0.355455,1.708664,155.829544,174.71402,-7.737985,157.827438,-31.691954,-13.466755,157.875397,-27.536964,-77.503578,99.798882,179.945419,-16.843657,156.771759,-23.978895,82.872269,210.93927,174.267593,-4.555549,150.693497,-27.215805,84.570656,101.469971,177.373505,-75.955376,209.551712,177.543213,6.958782,167.029663,-22.070715,13.305755,161.598007,-19.991922,,, +54,0.9,-5.715171,30.626463,2.13601,-10.642287,155.800934,-27.595642,-0.062083,0.921093,0.355427,1.708902,155.828918,174.712402,-7.736866,157.835602,-31.678919,-13.463826,157.882523,-27.521145,-77.50267,99.799934,179.941849,-16.839586,156.778366,-23.962154,82.87159,210.937927,174.267426,-4.553247,150.698547,-27.204731,84.572487,101.468216,177.37796,-75.95575,209.551407,177.536499,6.963537,167.033096,-22.059212,13.312678,161.601517,-19.983334,,, +55,0.916667,-5.68826,30.636869,2.114586,-10.640065,155.806961,-27.579933,-0.059446,0.92231,0.355343,1.708717,155.829529,174.714005,-7.735435,157.841553,-31.662611,-13.46089,157.889496,-27.504438,-77.502892,99.799255,179.943161,-16.836493,156.785461,-23.945251,82.871689,210.939163,174.268265,-4.552628,150.702209,-27.191145,84.571373,101.468338,177.375931,-75.955559,209.552353,177.543427,6.968084,167.035889,-22.047451,13.319591,161.604294,-19.974554,,, +56,0.933333,-5.660481,30.662722,2.098995,-10.636239,155.812424,-27.563021,-0.062094,0.921651,0.355218,1.708769,155.829437,174.712341,-7.733285,157.846619,-31.645098,-13.456451,157.895721,-27.485603,-77.502991,99.800018,179.942841,-16.830845,156.791397,-23.925362,82.872078,210.938843,174.265244,-4.550282,150.706497,-27.179224,84.570877,101.468781,177.376938,-75.955292,209.552261,177.538269,6.973949,167.038147,-22.035563,13.326539,161.605209,-19.965351,,, +57,0.95,-5.61599,30.59881,2.029512,-10.638709,155.817764,-27.548672,-0.059778,0.922911,0.355558,1.709466,155.829544,174.714081,-7.729472,157.851273,-31.628593,-13.457079,157.903656,-27.47434,-77.503433,99.799683,179.943726,-16.836811,156.80191,-23.918369,82.871262,210.939911,174.264404,-4.55723,150.70459,-27.156719,84.574028,101.467529,177.378708,-75.953781,209.550934,177.544052,6.982552,167.037994,-22.022957,13.332213,161.605347,-19.957273,,, +58,0.966667,-5.598697,30.620152,2.017468,-10.634698,155.824203,-27.53413,-0.059735,0.921842,0.355503,1.709706,155.828491,174.713821,-7.726431,157.85733,-31.614246,-13.452589,157.91069,-27.458399,-77.502701,99.800041,179.94104,-16.831305,156.80899,-23.901447,82.872154,210.937592,174.26886,-4.554374,150.710052,-27.14572,84.573441,101.468536,177.375656,-75.954079,209.549622,177.541153,6.991311,167.037888,-22.009554,13.337883,161.604675,-19.948906,,, +59,0.983333,-5.570509,30.638941,1.996912,-10.631314,155.831085,-27.521118,-0.062308,0.922136,0.355714,1.708929,155.829254,174.711517,-7.723827,157.865005,-31.602272,-13.448475,157.918518,-27.443907,-77.503166,99.800156,179.942444,-16.826508,156.816849,-23.886295,82.871315,210.939117,174.263885,-4.552314,150.714035,-27.135303,84.572334,101.469444,177.375122,-75.954857,209.55043,177.53656,6.998364,167.039627,-21.997267,13.344828,161.605576,-19.940216,,, +60,1,-5.548328,30.670607,1.983312,-10.627581,155.837631,-27.506737,-0.060564,0.921632,0.355514,1.709143,155.830307,174.712524,-7.721689,157.872223,-31.589464,-13.444164,157.925766,-27.427473,-77.502701,99.801422,179.940338,-16.820593,156.82402,-23.868366,82.871826,210.939651,174.266693,-4.549544,150.718597,-27.125124,84.573746,101.468788,177.378799,-75.955818,209.552307,177.540771,7.004752,167.042465,-21.98632,13.353186,161.606735,-19.932281,,, +61,1.016667,-5.522071,30.703108,1.973398,-10.622308,155.845001,-27.491205,-0.06226,0.921266,0.355324,1.708938,155.830017,174.711105,-7.717382,157.881134,-31.575853,-13.438423,157.93367,-27.409622,-77.503639,99.799438,179.944321,-16.813118,156.831284,-23.849064,82.873047,210.939331,174.267715,-4.545124,150.724243,-27.11445,84.573059,101.468102,177.378265,-75.956207,209.553146,177.535492,7.012581,167.043991,-21.974659,13.36115,161.607666,-19.925034,,, +62,1.033333,-5.502556,30.723673,1.962745,-10.617347,155.852371,-27.476418,-0.060644,0.921606,0.35556,1.709435,155.830551,174.710648,-7.713383,157.889771,-31.56242,-13.43303,157.941559,-27.393358,-77.503654,99.798477,179.944305,-16.806721,156.838959,-23.831917,82.872795,210.940094,174.267288,-4.540771,150.72966,-27.102324,84.57299,101.470291,177.373474,-75.954941,209.553284,177.536087,7.020845,167.045715,-21.962255,13.368516,161.607178,-19.915915,,, +63,1.05,-5.471647,30.742945,1.946538,-10.611872,155.859695,-27.461792,-0.061182,0.922468,0.355841,1.70811,155.829208,174.711365,-7.708074,157.898026,-31.547922,-13.426956,157.949631,-27.377029,-77.50425,99.799133,179.944016,-16.799841,156.846542,-23.814974,82.872322,210.939713,174.268204,-4.536789,150.735352,-27.091812,84.572525,101.468208,177.374985,-75.957016,209.550217,177.537415,7.030252,167.046829,-21.949667,13.376817,161.606003,-19.906723,,, +64,1.066667,-5.457504,30.800684,1.978294,-10.600195,155.866928,-27.448332,-0.061718,0.923074,0.355678,1.709072,155.829498,174.710953,-7.700558,157.907227,-31.534571,-13.415978,157.95575,-27.359509,-77.50338,99.798653,179.944824,-16.784708,156.849503,-23.794504,82.872246,210.939499,174.26297,-4.523582,150.746414,-27.089298,84.573624,101.468231,177.375885,-75.955872,209.551743,177.53949,7.041755,167.047577,-21.935637,13.387948,161.605804,-19.896656,,, +65,1.083333,-5.438236,30.814331,1.977671,-10.589743,155.87352,-27.439386,-0.059506,0.92165,0.355576,1.709483,155.830246,174.711472,-7.691515,157.915237,-31.525349,-13.405437,157.962387,-27.349207,-77.503212,99.799171,179.941742,-16.773359,156.855087,-23.783773,82.874382,210.93988,174.270004,-4.513083,150.752579,-27.083435,84.57251,101.470459,177.373032,-75.956085,209.552383,177.540634,7.053133,167.049988,-21.920332,13.399175,161.60733,-19.886005,,, +66,1.1,-5.426276,30.764771,1.965515,-10.582375,155.881836,-27.436087,-0.059818,0.920531,0.355037,1.708556,155.830002,174.713135,-7.680536,157.923477,-31.519276,-13.397941,157.970993,-27.348173,-77.504875,99.800598,179.94165,-16.769106,156.863647,-23.785809,82.872223,210.938568,174.271774,-4.506508,150.760208,-27.075212,84.573418,101.467705,177.38028,-75.956146,209.552841,177.53923,7.065639,167.052109,-21.907488,13.409072,161.605911,-19.872921,,, +67,1.116667,-5.406448,30.760393,1.960468,-10.572023,155.887527,-27.433479,-0.058286,0.92143,0.355163,1.71039,155.82988,174.713104,-7.669211,157.930237,-31.516365,-13.387455,157.976852,-27.345169,-77.502739,99.800064,179.940491,-16.758991,156.868668,-23.783421,82.874382,210.93869,174.270859,-4.496467,150.765396,-27.073633,84.573723,101.469078,177.375198,-75.95414,209.552246,177.542969,7.077558,167.052872,-21.895727,13.419172,161.601028,-19.860298,,, +68,1.133333,-5.37732,30.738297,1.93309,-10.563988,155.89502,-27.435228,-0.058969,0.921479,0.354405,1.70974,155.831741,174.711273,-7.659911,157.937592,-31.516111,-13.378676,157.985367,-27.347555,-77.503494,99.800064,179.942947,-16.752131,156.877502,-23.787525,82.872856,210.938889,174.266693,-4.490225,150.770111,-27.073702,84.573074,101.468971,177.375031,-75.954689,209.557861,177.540283,7.091445,167.051971,-21.887627,13.427259,161.593246,-19.851589,,, +69,1.15,-5.35097,30.723288,1.91074,-10.556769,155.904205,-27.440866,-0.058561,0.921367,0.354559,1.709373,155.831833,174.709839,-7.650912,157.947311,-31.520676,-13.370837,157.995407,-27.353474,-77.503708,99.799683,179.941895,-16.745672,156.887665,-23.794716,82.873901,210.939499,174.26915,-4.484625,150.777023,-27.078587,84.572983,101.468567,177.37384,-75.955956,209.557693,177.538651,7.104935,167.05162,-21.881527,13.435489,161.584824,-19.845825,,, +70,1.166667,-5.318305,30.704241,1.881522,-10.54945,155.91153,-27.4475,-0.059939,0.921166,0.354794,1.709878,155.830826,174.709732,-7.641987,157.954559,-31.525686,-13.362701,158.00383,-27.360504,-77.50267,99.800232,179.941254,-16.739309,156.896362,-23.803347,82.874298,210.938217,174.269241,-4.479126,150.781448,-27.08427,84.573906,101.468788,177.373932,-75.955986,209.555862,177.536438,7.119213,167.050232,-21.878008,13.444239,161.575577,-19.840807,,, +71,1.183333,-5.32217,30.764067,1.916376,-10.536277,155.913742,-27.450827,-0.061527,0.919206,0.354385,1.709907,155.831955,174.707977,-7.634017,157.957108,-31.529335,-13.350318,158.004837,-27.36026,-77.502686,99.800385,179.940506,-16.722584,156.895065,-23.7997,82.874451,210.939194,174.269623,-4.464149,150.787964,-27.097321,84.574333,101.467255,177.378983,-75.955933,209.55896,177.529144,7.130252,167.048462,-21.877295,13.451921,161.570206,-19.838243,,, +72,1.2,-5.319811,30.754696,1.897029,-10.531775,155.913208,-27.454536,-0.064505,0.92008,0.35564,1.708981,155.829559,174.707962,-7.628345,157.954956,-31.532267,-13.345261,158.005081,-27.364779,-77.503304,99.80085,179.941849,-16.718506,156.896698,-23.804712,82.87426,210.938736,174.270859,-4.461198,150.786057,-27.099483,84.574173,101.468643,177.376648,-75.957054,209.551376,177.524704,7.139107,167.045593,-21.88213,13.458025,161.564056,-19.839603,,, +73,1.216667,-5.33187,30.770357,1.890385,-10.53039,155.911285,-27.457327,-0.059002,0.920825,0.355114,1.709896,155.830338,174.712128,-7.628092,157.95166,-31.536293,-13.343592,158.00354,-27.367395,-77.503197,99.799301,179.941986,-16.716038,156.89653,-23.806141,82.873619,210.93927,174.271194,-4.460326,150.783325,-27.10236,84.573822,101.468361,177.376862,-75.954788,209.553879,177.538971,7.142863,167.040665,-21.891945,13.460207,161.557434,-19.850212,,, +74,1.233333,-5.340576,30.78688,1.888428,-10.532626,155.907578,-27.459583,-0.057513,0.921015,0.354712,1.711055,155.830399,174.713867,-7.630977,157.947205,-31.539621,-13.345686,158,-27.369204,-77.502769,99.799774,179.941422,-16.717178,156.893784,-23.806805,82.874954,210.938354,174.271973,-4.462895,150.77951,-27.105686,84.574875,101.468277,177.377319,-75.953568,209.554413,177.544785,7.142068,167.035919,-21.905539,13.460587,161.551804,-19.867538,,, +75,1.25,-5.369114,30.817978,1.894696,-10.533548,155.897629,-27.460407,-0.06055,0.920436,0.354499,1.710196,155.831329,174.710632,-7.633298,157.93512,-31.54283,-13.346646,157.98996,-27.36941,-77.503242,99.80098,179.940369,-16.716137,156.885193,-23.80467,82.874352,210.939102,174.267059,-4.463854,150.77063,-27.108156,84.573814,101.468315,177.378754,-75.95459,209.55629,177.537872,7.137339,167.031143,-21.922611,13.461557,161.554749,-19.884586,,, +76,1.266667,-5.380018,30.835344,1.887736,-10.531605,155.87706,-27.462006,-0.059642,0.920108,0.354848,1.710387,155.830948,174.711197,-7.631181,157.913391,-31.546131,-13.344399,157.969803,-27.370716,-77.503281,99.801239,179.938812,-16.712996,156.866379,-23.804712,82.874123,210.939194,174.268799,-4.462637,150.749649,-27.110577,84.574615,101.468826,177.37851,-75.954407,209.554504,177.538483,,,,13.464104,161.560471,-19.898664,,, +77,1.283333,-5.435171,30.787577,1.854317,-10.531973,155.847733,-27.4638,-0.060845,0.921018,0.355081,1.710278,155.829895,174.711258,-7.629319,157.878983,-31.54858,-13.343967,157.941757,-27.377617,-77.502525,99.80085,179.93837,-16.716152,156.844238,-23.813183,82.874748,210.938263,174.266098,-4.464552,150.71637,-27.098698,84.57428,101.46862,177.378845,-75.955666,209.552902,177.542206,7.12232,167.020081,-21.963507,13.465543,161.570099,-19.910366,,, +78,1.3,-5.557611,30.79875,1.891058,-10.527324,155.813461,-27.463058,-0.06182,0.920851,0.355234,1.710202,155.829926,174.712967,-7.627572,157.837769,-31.550962,-13.340406,157.906158,-27.379967,-77.502747,99.801132,179.941376,-16.71113,156.813309,-23.812719,82.87532,210.938782,174.269211,-4.45721,150.686676,-27.090887,84.573799,101.469315,177.379852,-75.95562,209.552078,177.541153,7.111423,167.01384,-21.989462,13.462147,161.576843,-19.920593,,, +79,1.316667,-5.673535,30.770573,1.93848,-10.526012,155.78157,-27.470291,-0.062839,0.918946,0.354998,1.710063,155.829102,174.710983,-7.623948,157.80162,-31.561848,-13.340709,157.872253,-27.391726,-77.502571,99.802849,179.9366,-16.712107,156.782562,-23.82415,82.875534,210.936783,174.272247,-4.452426,150.660202,-27.087433,84.57328,101.469292,177.378204,-75.955322,209.550568,177.53183,7.098338,167.008163,-22.018654,13.455826,161.584503,-19.933653,,, +80,1.333333,-5.822804,30.740543,1.999653,-10.527235,155.753174,-27.482515,-0.060828,0.920939,0.354981,1.710326,155.829163,174.714371,-7.624094,157.76712,-31.576023,-13.343981,157.841309,-27.409464,-77.5037,99.799873,179.943726,-16.715864,156.755692,-23.841095,82.875969,210.93808,174.272125,-4.449438,150.63974,-27.087896,84.57383,101.467751,177.380295,-75.954941,209.551315,177.542694,7.084166,167.004578,-22.044733,13.448414,161.595566,-19.946878,,, +81,1.35,-5.95982,30.734312,2.066873,-10.530231,155.728775,-27.499638,-0.05794,0.921362,0.354467,1.710669,155.830078,174.715317,-7.628794,157.738083,-31.596386,-13.349093,157.814163,-27.430338,-77.502167,99.801659,179.940506,-16.719891,156.731552,-23.860043,82.875557,210.93808,174.272156,-4.447516,150.622589,-27.096182,84.573921,101.466942,177.380203,-75.954773,209.553787,177.548904,7.070003,167.004623,-22.070398,13.437438,161.603973,-19.961267,,, +82,1.366667,-6.021711,30.729111,2.08735,-10.532362,155.711014,-27.518255,-0.06084,0.919688,0.355015,1.709591,155.829712,174.712982,-7.631245,157.717346,-31.617344,-13.351886,157.795578,-27.450991,-77.503769,99.801865,179.939682,-16.722551,156.715088,-23.879921,82.874847,210.938171,174.274216,-4.44789,150.606964,-27.109575,84.573814,101.468231,177.380371,-75.955498,209.551666,177.536835,7.056229,167.003586,-22.094271,13.426234,161.609283,-19.976299,,, +83,1.383333,-6.067245,30.69331,2.095934,-10.535643,155.698914,-27.536615,-0.057536,0.92049,0.354721,1.710728,155.829697,174.715332,-7.632568,157.702805,-31.635395,-13.35561,157.78299,-27.472561,-77.502426,99.801506,179.939941,-16.728237,156.704422,-23.902767,82.87542,210.937973,174.276718,-4.450379,150.596329,-27.120527,84.574158,101.467644,177.378601,-75.953812,209.552246,177.543823,7.046692,167.002563,-22.113163,13.414882,161.610367,-19.986456,,, +84,1.4,-6.100223,30.639341,2.098257,-10.539091,155.690796,-27.555647,-0.059409,0.919739,0.355215,1.710627,155.829941,174.71431,-7.633132,157.693085,-31.65259,-13.359396,157.774521,-27.49538,-77.502296,99.801674,179.938599,-16.735207,156.697479,-23.928135,82.875755,210.938782,174.276047,-4.453292,150.588867,-27.130758,84.573509,101.469948,177.377838,-75.954475,209.551315,177.540344,7.039864,167.002213,-22.12919,13.40682,161.612503,-19.994604,,, +85,1.416667,-6.099471,30.570019,2.061745,-10.547187,155.684509,-27.571985,-0.06055,0.920768,0.355486,1.710045,155.829926,174.711731,-7.636522,157.686005,-31.667387,-13.366697,157.769424,-27.515924,-77.502014,99.802055,179.937454,-16.747454,156.694901,-23.952606,82.873726,210.939102,174.268707,-4.463159,150.578293,-27.135887,84.573975,101.469421,177.37706,-75.95504,209.551163,177.538589,7.034402,167.000885,-22.144604,13.40141,161.613708,-20.004475,,, +86,1.433333,-6.132623,30.573423,2.07309,-10.553584,155.681915,-27.584414,-0.060127,0.920665,0.354971,1.710233,155.829773,174.714096,-7.644257,157.682281,-31.680922,-13.373431,157.766403,-27.529129,-77.50251,99.800529,179.941513,-16.753736,156.693024,-23.965036,82.874435,210.937576,174.271805,-4.46846,150.576462,-27.145979,84.572998,101.469681,177.37706,-75.954643,209.552795,177.541107,7.030035,166.99823,-22.157436,13.395296,161.608337,-20.016014,,, +87,1.45,-6.157394,30.581404,2.073445,-10.563481,155.680984,-27.591906,-0.060384,0.920605,0.354921,1.70999,155.829712,174.712189,-7.655077,157.680008,-31.689993,-13.383299,157.765518,-27.537125,-77.503838,99.800201,179.939697,-16.763119,156.69371,-23.972101,82.874596,210.938385,174.26799,-4.478188,150.575211,-27.151628,84.573647,101.468071,177.379486,-75.954933,209.552338,177.541702,7.024576,166.993195,-22.168055,13.388339,161.600082,-20.02762,,, +88,1.466667,-6.172085,30.604378,2.07498,-10.576148,155.682083,-27.594896,-0.059518,0.921824,0.355219,1.709227,155.829544,174.712402,-7.668909,157.679489,-31.694174,-13.395903,157.766693,-27.539492,-77.503632,99.802078,179.939621,-16.774313,156.695816,-23.972855,82.873764,210.938141,174.271271,-4.491049,150.576904,-27.156464,84.573044,101.469208,177.373795,-75.955551,209.550613,177.540131,7.017256,166.987305,-22.176556,13.380168,161.590714,-20.040327,,, +89,1.483333,-6.174375,30.652172,2.081598,-10.592472,155.687027,-27.594078,-0.059034,0.921651,0.355362,1.709201,155.829391,174.715347,-7.687583,157.684097,-31.695805,-13.412198,157.771606,-27.536264,-77.503113,99.80162,179.941269,-16.787601,156.700638,-23.96681,82.873825,210.938339,174.273972,-4.507337,150.582535,-27.161461,84.57299,101.468933,177.377441,-75.95636,209.550613,177.545242,7.006589,166.984299,-22.184452,13.370344,161.583893,-20.055563,,, +90,1.5,-6.156335,30.710638,2.097888,-10.610367,155.69635,-27.592394,-0.061833,0.92024,0.355744,1.709241,155.829041,174.712448,-7.709455,157.695694,-31.696537,-13.430309,157.780533,-27.530687,-77.502594,99.79985,179.941513,-16.801855,156.707458,-23.958214,82.873329,210.938171,174.272293,-4.524192,150.592636,-27.168598,84.572777,101.469925,177.377029,-75.956192,209.550522,177.535156,6.993906,166.984924,-22.189701,13.358431,161.582199,-20.072674,,, +91,1.516667,-6.135373,30.76569,2.119627,-10.62671,155.706757,-27.589577,-0.061369,0.920673,0.35565,1.709131,155.829819,174.712067,-7.73051,157.709091,-31.695637,-13.447051,157.790298,-27.523911,-77.501778,99.801422,179.940216,-16.814819,156.714462,-23.948702,82.872444,210.939789,174.270935,-4.539075,150.604004,-27.174383,84.57206,101.469162,177.376373,-75.955193,209.551056,177.533463,6.979811,166.990143,-22.192379,13.347754,161.589172,-20.089317,,, +92,1.533333,-6.110442,30.825914,2.146921,-10.641134,155.716843,-27.584845,-0.06135,0.919247,0.355127,1.709874,155.829163,174.711685,-7.750931,157.723022,-31.692356,-13.462014,157.7995,-27.514692,-77.502541,99.80127,179.939178,-16.825571,156.720261,-23.936552,82.873741,210.937637,174.273422,-4.551361,150.615234,-27.179399,84.573273,101.468369,177.377747,-75.954628,209.551453,177.531448,6.963843,166.998444,-22.193501,13.338041,161.601669,-20.104105,,, +93,1.55,-6.084765,30.875198,2.181593,-10.656078,155.725601,-27.582607,-0.059736,0.920964,0.354771,1.710012,155.829636,174.712814,-7.770581,157.736298,-31.691288,-13.477778,157.806992,-27.50831,-77.502701,99.801376,179.940079,-16.837614,156.723602,-23.927925,82.872818,210.937637,174.269135,-4.563808,150.626129,-27.186424,84.573334,101.46804,177.376846,-75.953415,209.552689,177.538483,6.949497,167.006012,-22.194893,13.327345,161.612061,-20.11698,,, +94,1.566667,-6.068398,30.905842,2.207946,-10.67171,155.734222,-27.584305,-0.061797,0.920068,0.355497,1.709568,155.829651,174.711288,-7.790403,157.748108,-31.692991,-13.494065,157.814621,-27.507301,-77.501518,99.802483,179.937912,-16.851484,156.728241,-23.92556,82.872818,210.938507,174.270462,-4.577328,150.636261,-27.193951,84.573929,101.468658,177.378265,-75.955688,209.551498,177.532608,6.934693,167.010529,-22.19696,13.316146,161.618073,-20.13216,,, +95,1.583333,-6.056427,30.942745,2.235461,-10.685188,155.740311,-27.588978,-0.062771,0.920262,0.355126,1.709329,155.829803,174.711212,-7.807423,157.756439,-31.698318,-13.508201,157.819717,-27.509096,-77.50251,99.803589,179.93869,-16.862797,156.73056,-23.925554,82.872208,210.938568,174.267105,-4.588981,150.644638,-27.205505,84.573639,101.467583,177.37999,-75.95433,209.551651,177.531937,6.922522,167.013779,-22.200172,13.303679,161.619812,-20.145744,,, +96,1.6,-6.043008,30.943172,2.254095,-10.696774,155.743668,-27.598083,-0.060095,0.920438,0.355337,1.709722,155.829315,174.713089,-7.820003,157.762451,-31.706758,-13.520357,157.822266,-27.517262,-77.501213,99.802147,179.938644,-16.874521,156.730728,-23.934034,82.872704,210.938553,174.272079,-4.59905,150.649338,-27.216646,84.574409,101.466476,177.380508,-75.955322,209.551529,177.537201,6.912229,167.015625,-22.202921,13.293721,161.61998,-20.154673,,, +97,1.616667,-6.030323,30.933626,2.261991,-10.703334,155.745834,-27.610767,-0.063181,0.921181,0.355718,1.708806,155.8284,174.708862,-7.825547,157.766373,-31.71888,-13.527211,157.82402,-27.529774,-77.502655,99.800323,179.938858,-16.881775,156.731003,-23.947378,82.873093,210.938263,174.26593,-4.605038,150.652267,-27.22995,84.5746,101.465881,177.379227,-75.957642,209.549927,177.532608,6.904095,167.017548,-22.206625,13.28548,161.621246,-20.161121,,, +98,1.633333,-6.034035,30.909185,2.275913,-10.705889,155.746384,-27.625313,-0.060981,0.920521,0.355617,1.709681,155.829178,174.71167,-7.826547,157.767899,-31.732273,-13.530323,157.823868,-27.54533,-77.503029,99.801147,179.940613,-16.886053,156.729767,-23.964352,82.873192,210.938721,174.272507,-4.60658,150.654449,-27.242466,84.574821,101.467941,177.377533,-75.954941,209.550125,177.532516,6.899038,167.019211,-22.210068,13.278844,161.621552,-20.162457,,, +99,1.65,-6.020341,30.871243,2.262957,-10.705853,155.747849,-27.641991,-0.06178,0.921349,0.355602,1.709341,155.829956,174.711334,-7.823029,157.769257,-31.746916,-13.530085,157.825653,-27.563671,-77.501907,99.80249,179.938034,-16.888378,156.731552,-23.985104,82.871719,210.939072,174.265823,-4.607398,150.655365,-27.255848,84.57354,101.469406,177.376694,-75.955116,209.551239,177.535873,6.897256,167.021698,-22.213995,13.273615,161.620636,-20.162201,,, +100,1.666667,-6.007357,30.822191,2.240762,-10.704554,155.750275,-27.659115,-0.062385,0.921672,0.35598,1.709184,155.828949,174.71199,-7.817691,157.771225,-31.761667,-13.528352,157.828766,-27.583239,-77.502838,99.801338,179.94046,-16.890081,156.735367,-24.007681,82.872261,210.939621,174.266861,-4.607668,150.656113,-27.267492,84.573013,101.469254,177.376648,-75.95475,209.548187,177.535553,6.897912,167.023788,-22.218546,13.270352,161.619583,-20.159317,,, +101,1.683333,-6.01007,30.775265,2.219933,-10.704288,155.750244,-27.674654,-0.058894,0.922301,0.355965,1.7098,155.829163,174.714294,-7.813112,157.769745,-31.775507,-13.527681,157.829391,-27.601656,-77.501602,99.801041,179.938766,-16.892683,156.737579,-24.028692,82.872368,210.940125,174.268661,-4.608808,150.65477,-27.276655,84.574196,101.467873,177.378128,-75.95475,209.548874,177.545349,6.898773,167.024048,-22.225285,13.267653,161.615906,-20.158958,,, +102,1.7,-6.020947,30.756144,2.19509,-10.705898,155.747131,-27.685612,-0.059886,0.921926,0.355488,1.709591,155.829681,174.713394,-7.811955,157.764297,-31.786686,-13.528622,157.82724,-27.614515,-77.50235,99.802673,179.939178,-16.895313,156.738037,-24.042353,82.873146,210.939072,174.269699,-4.612287,150.649689,-27.28323,84.573593,101.469131,177.376312,-75.954895,209.550125,177.54126,6.898651,167.019531,-22.235657,13.263752,161.610489,-20.163757,,, +103,1.716667,-6.049006,30.756332,2.181508,-10.710005,155.742386,-27.693275,-0.058335,0.921613,0.355828,1.710113,155.829346,174.713333,-7.815574,157.756378,-31.795231,-13.532308,157.823105,-27.623501,-77.50177,99.801613,179.935318,-16.899288,156.736771,-24.050734,82.872818,210.939926,174.267487,-4.617432,150.644135,-27.287903,84.574394,101.4683,177.378174,-75.95472,209.549194,177.546036,6.896463,167.012024,-22.249933,13.25878,161.602112,-20.171875,,, +104,1.733333,-6.078469,30.765207,2.172548,-10.716018,155.736542,-27.696222,-0.061208,0.921268,0.355626,1.709437,155.829224,174.712204,-7.82189,157.748032,-31.799963,-13.537997,157.817734,-27.627289,-77.501854,99.801361,179.939743,-16.90464,156.734009,-24.053408,82.87207,210.939362,174.268387,-4.624105,150.637405,-27.288458,84.573494,101.467636,177.377899,-75.954727,209.550293,177.535721,6.892147,167.005127,-22.263554,13.255617,161.5961,-20.182133,,, +105,1.75,-6.117672,30.798491,2.172678,-10.722178,155.729675,-27.694061,-0.061459,0.920857,0.356033,1.708433,155.828888,174.71228,-7.83082,157.737808,-31.799988,-13.543995,157.811096,-27.62492,-77.502243,99.801956,179.938171,-16.908636,156.730011,-24.048353,82.871536,210.939285,174.271301,-4.630497,150.630737,-27.286629,84.573341,101.468193,177.378464,-75.956688,209.548706,177.534637,6.887802,166.997223,-22.275362,13.253043,161.591125,-20.193726,,, +106,1.766667,-6.148446,30.830648,2.180168,-10.730441,155.723434,-27.687359,-0.060247,0.921563,0.355856,1.708804,155.829803,174.710449,-7.841973,157.729736,-31.795353,-13.552326,157.804733,-27.617588,-77.502724,99.801872,179.938004,-16.914871,156.725159,-24.038597,82.870552,210.939972,174.267624,-4.638312,150.625076,-27.28112,84.573975,101.468483,177.374619,-75.954834,209.550308,177.533173,6.882016,166.989197,-22.282814,13.249474,161.585541,-20.203663,,, +107,1.783333,-6.159847,30.869255,2.183242,-10.739907,155.719971,-27.678072,-0.059175,0.922109,0.355813,1.709404,155.828979,174.715042,-7.853848,157.725281,-31.78829,-13.561689,157.801361,-27.606756,-77.502693,99.801376,179.938934,-16.921848,156.722504,-24.025309,82.870697,210.939758,174.266617,-4.647784,150.62175,-27.275291,84.573288,101.468338,177.378601,-75.953506,209.548325,177.544632,6.876565,166.984055,-22.286745,13.245241,161.57933,-20.214045,,, +108,1.8,-6.157389,30.91711,2.182048,-10.75001,155.719925,-27.667204,-0.056272,0.922597,0.355715,1.709191,155.829651,174.715347,-7.866979,157.72435,-31.779251,-13.571507,157.80162,-27.593481,-77.502151,99.802246,179.937576,-16.928812,156.722992,-24.009287,82.870918,210.939911,174.271515,-4.658344,150.621613,-27.270159,84.573273,101.468491,177.374893,-75.954117,209.549454,177.546265,6.872465,166.979416,-22.286774,13.241381,161.571823,-20.219528,,, +109,1.816667,-6.120564,30.877398,2.128184,-10.765203,155.726303,-27.659857,-0.059404,0.92133,0.355826,1.708926,155.828583,174.71312,-7.878382,157.730164,-31.770472,-13.585239,157.810028,-27.58799,-77.501694,99.801781,179.935196,-16.946108,156.733292,-24.006573,82.871124,210.939163,174.268616,-4.677044,150.622253,-27.257553,84.572151,101.467812,177.376511,-75.955185,209.548325,177.540771,6.868753,166.97731,-22.281002,13.238419,161.567993,-20.221359,,, +110,1.833333,-6.071446,30.891361,2.115399,-10.769703,155.734024,-27.651987,-0.05925,0.922018,0.356043,1.708907,155.828537,174.713318,-7.882883,157.740173,-31.761938,-13.589273,157.818298,-27.577946,-77.502541,99.801003,179.939178,-16.949581,156.739624,-23.996582,82.872093,210.938766,174.271515,-4.682605,150.628525,-27.254972,84.573135,101.468895,177.37439,-75.955673,209.547714,177.540451,6.86808,166.977814,-22.271282,13.236979,161.566208,-20.217155,,, +111,1.85,-6.014062,30.889219,2.106954,-10.769679,155.744446,-27.645281,-0.061018,0.92065,0.355839,1.708467,155.828735,174.711533,-7.882054,157.754669,-31.75379,-13.589001,157.828995,-27.569452,-77.502289,99.802528,179.9366,-16.949619,156.747406,-23.989258,82.872017,210.939026,174.272278,-4.683084,150.637527,-27.252439,84.572029,101.468315,177.375458,-75.955986,209.548096,177.532532,6.869583,166.981094,-22.256214,13.236928,161.566742,-20.204639,,, +112,1.866667,-5.952594,30.864075,2.077977,-10.76722,155.757965,-27.641859,-0.06142,0.92065,0.355787,1.708438,155.828339,174.711365,-7.877249,157.770874,-31.747648,-13.585772,157.843536,-27.565691,-77.502144,99.80191,179.936859,-16.948532,156.760345,-23.987999,82.871902,210.938644,174.271088,-4.682547,150.647858,-27.249754,84.572708,101.467003,177.377563,-75.956429,209.548599,177.533035,6.873333,166.987564,-22.233932,13.23798,161.566376,-20.183908,,, +113,1.883333,-5.902211,30.850643,2.051611,-10.763741,155.772858,-27.638514,-0.061731,0.921156,0.35594,1.708667,155.829132,174.70993,-7.872225,157.787323,-31.742424,-13.581547,157.859436,-27.561775,-77.502022,99.802544,179.936081,-16.945686,156.775162,-23.985703,82.872406,210.938843,174.268921,-4.680831,150.659958,-27.24773,84.572838,101.469353,177.374222,-75.956535,209.548996,177.533005,6.881473,166.992645,-22.210169,13.240191,161.565796,-20.16275,,, +114,1.9,-5.8543,30.822964,2.022815,-10.759353,155.786652,-27.635422,-0.062974,0.920309,0.355576,1.708007,155.830246,174.707184,-7.865908,157.802719,-31.736645,-13.576405,157.874252,-27.558956,-77.502602,99.802292,179.934555,-16.942831,156.7892,-23.985275,82.871017,210.940033,174.263458,-4.67832,150.670654,-27.243778,84.571579,101.468811,177.375366,-75.95723,209.552185,177.529022,6.88984,166.997498,-22.186762,13.241995,161.564713,-20.1392,,, +115,1.916667,-5.858204,30.8426,2.053767,-10.749454,155.798584,-27.629423,-0.060943,0.919541,0.355199,1.708776,155.8302,174.709366,-7.858041,157.81546,-31.729725,-13.567366,157.884964,-27.551428,-77.502304,99.8032,179.933411,-16.931942,156.797745,-23.976665,82.872612,210.93869,174.26944,-4.66675,150.686508,-27.242733,84.572754,101.468536,177.377441,-75.956833,209.552475,177.532883,6.897276,166.999329,-22.16396,13.244883,161.562119,-20.113642,,, +116,1.933333,-5.803699,30.805237,2.017547,-10.743507,155.809601,-27.622705,-0.061145,0.919834,0.355428,1.708713,155.829437,174.709656,-7.847868,157.82782,-31.720022,-13.560486,157.897263,-27.545383,-77.503029,99.803078,179.933121,-16.928093,156.809387,-23.973673,82.873062,210.938553,174.268814,-4.663486,150.694397,-27.23493,84.573059,101.468262,177.377457,-75.957253,209.550354,177.534882,6.907454,167.001877,-22.141752,13.24701,161.555725,-20.08543,,, +117,1.95,-5.78734,30.745028,1.991414,-10.739223,155.82193,-27.615753,-0.058983,0.920951,0.355239,1.709277,155.829178,174.712692,-7.838098,157.839645,-31.710239,-13.555691,157.9104,-27.541378,-77.503471,99.802223,179.936035,-16.927479,156.823288,-23.973381,82.872879,210.938995,174.270111,-4.660999,150.704941,-27.221636,84.573349,101.466927,177.378342,-75.954666,209.549744,177.540573,6.919211,167.002853,-22.114283,13.251699,161.548477,-20.054562,,, +118,1.966667,-5.723143,30.69058,1.953906,-10.731832,155.831055,-27.606037,-0.061385,0.920106,0.355935,1.70915,155.829193,174.708542,-7.826074,157.8508,-31.696051,-13.547402,157.920761,-27.532843,-77.502083,99.800125,179.93631,-16.923269,156.832428,-23.969082,82.872452,210.939499,174.268646,-4.656255,150.710632,-27.209599,84.57296,101.468788,177.374222,-75.955757,209.550095,177.529724,6.932224,167.004578,-22.088131,13.25668,161.5439,-20.023727,,, +119,1.983333,-5.674008,30.668724,1.928933,-10.724268,155.840546,-27.592602,-0.05939,0.920277,0.355361,1.70984,155.829147,174.711197,-7.815873,157.861496,-31.6798,-13.539169,157.931152,-27.519253,-77.501938,99.801636,179.934311,-16.916887,156.841675,-23.95759,82.872604,210.938339,174.269455,-4.650691,150.718277,-27.197323,84.573776,101.46772,177.376846,-75.954453,209.550522,177.537048,6.939353,167.006744,-22.061596,13.260788,161.541672,-19.993359,,, +120,2,-5.629266,30.645109,1.909438,-10.719242,155.85051,-27.579535,-0.058738,0.92006,0.355411,1.709301,155.830719,174.71048,-7.807356,157.873505,-31.664991,-13.533651,157.941788,-27.506149,-77.502777,99.801804,179.935715,-16.913206,156.850983,-23.946634,82.871994,210.940521,174.270493,-4.647262,150.726578,-27.184826,84.572365,101.469673,177.374313,-75.954002,209.552261,177.533859,6.94514,167.012177,-22.03405,13.262842,161.541656,-19.966244,,, +121,2.016667,-5.597638,30.649183,1.90389,-10.715681,155.86145,-27.564833,-0.057998,0.920278,0.355105,1.71019,155.830902,174.712479,-7.804332,157.886169,-31.649885,-13.529899,157.952942,-27.490219,-77.502434,99.802658,179.93576,-16.909328,156.860657,-23.931042,82.873383,210.94072,174.271103,-4.643792,150.736359,-27.17256,84.572945,101.469101,177.376266,-75.953064,209.552307,177.539322,6.948959,167.016586,-22.005199,13.26615,161.541397,-19.942457,,, +122,2.033333,-5.544642,30.671083,1.888951,-10.713665,155.873611,-27.546957,-0.057425,0.920498,0.355524,1.70954,155.829376,174.713348,-7.802688,157.900772,-31.63208,-13.527309,157.965775,-27.469679,-77.503273,99.80024,179.936737,-16.905746,156.871552,-23.910154,82.872131,210.939819,174.27153,-4.64304,150.746628,-27.160852,84.572617,101.468399,177.376312,-75.953117,209.549744,177.540237,6.953821,167.021027,-21.976406,13.269006,161.542984,-19.921715,,, +123,2.05,-5.48057,30.679745,1.875639,-10.713436,155.884521,-27.525944,-0.06012,0.920175,0.355431,1.709964,155.829559,174.710907,-7.803305,157.914932,-31.608204,-13.526625,157.977219,-27.446205,-77.502327,99.800957,179.936768,-16.904827,156.880157,-23.887331,82.873047,210.939545,174.268936,-4.643929,150.756149,-27.146193,84.573074,101.468483,177.376465,-75.953491,209.550568,177.534439,6.956151,167.025009,-21.95104,13.271661,161.543884,-19.901497,,, +124,2.066667,-5.426695,30.699778,1.861785,-10.715508,155.893585,-27.502167,-0.060049,0.920457,0.355131,1.710014,155.829803,174.711182,-7.806398,157.926636,-31.582474,-13.528167,157.986877,-27.419794,-77.502266,99.800697,179.937393,-16.905466,156.887741,-23.86071,82.872406,210.93895,174.26619,-4.647457,150.76387,-27.129164,84.572327,101.469055,177.375275,-75.953293,209.552307,177.536774,6.957314,167.026581,-21.92964,13.272156,161.543793,-19.883734,,, +125,2.083333,-5.390924,30.726255,1.857359,-10.716506,155.901413,-27.477711,-0.059638,0.920666,0.355748,1.709903,155.829163,174.71138,-7.808691,157.936279,-31.557869,-13.528898,157.994965,-27.392838,-77.501778,99.800552,179.9375,-16.904701,156.894104,-23.832863,82.872948,210.940506,174.270782,-4.649015,150.771179,-27.110905,84.572731,101.467812,177.375153,-75.953148,209.54924,177.533768,,,,13.273676,161.542542,-19.866913,,, +126,2.1,-5.3594,30.758818,1.855191,-10.717122,155.90863,-27.451797,-0.059028,0.920441,0.355628,1.710214,155.829437,174.712509,-7.812149,157.945633,-31.532728,-13.529285,158.00238,-27.364231,-77.503021,99.800529,179.937958,-16.903179,156.899918,-23.802942,82.873375,210.939438,174.271179,-4.649621,150.7771,-27.090487,84.573662,101.469566,177.375885,-75.953262,209.5495,177.538071,,,,13.276641,161.543961,-19.849419,,, +127,2.116667,-5.33041,30.7728,1.845265,-10.716853,155.914185,-27.423424,-0.059965,0.920554,0.355298,1.709759,155.829544,174.712036,-7.81178,157.95256,-31.50473,-13.528639,158.008377,-27.334339,-77.50264,99.801811,179.937103,-16.901907,156.905014,-23.772738,82.873444,210.939651,174.269699,-4.650281,150.781555,-27.065681,84.572258,101.468422,177.376373,-75.953712,209.550125,177.537445,,,,13.282294,161.545822,-19.832384,,, +128,2.133333,-5.318108,30.790384,1.851869,-10.711594,155.915588,-27.393833,-0.060216,0.921144,0.355586,1.709643,155.82872,174.712097,-7.807532,157.954742,-31.475548,-13.523499,158.009567,-27.303291,-77.501884,99.801048,179.939575,-16.895567,156.904984,-23.740929,82.873466,210.938217,174.273163,-4.644643,150.783691,-27.03973,84.572372,101.469101,177.37262,-75.954269,209.549088,177.533981,6.971391,167.031647,-21.835211,13.28925,161.547607,-19.811523,,, +129,2.15,-5.326945,30.776617,1.849118,-10.706302,155.917053,-27.36524,-0.059217,0.920624,0.355611,1.709753,155.829865,174.711685,-7.79982,157.955307,-31.446859,-13.518188,158.011108,-27.275757,-77.502319,99.800026,179.93956,-16.891142,156.907211,-23.714014,82.874046,210.940384,174.273346,-4.639912,150.785629,-27.009249,84.572556,101.468887,177.374573,-75.954597,209.551025,177.536011,6.975843,167.031311,-21.812231,13.298241,161.55098,-19.78783,,, +130,2.166667,-5.319928,30.801596,1.842822,-10.698096,155.916351,-27.338007,-0.060435,0.919673,0.355714,1.709857,155.829865,174.711533,-7.792803,157.953827,-31.42041,-13.509664,158.010757,-27.247187,-77.502609,99.800537,179.939087,-16.881252,156.907089,-23.684088,82.873581,210.939865,174.274521,-4.632397,150.784653,-26.985491,84.57354,101.469574,177.375931,-75.954224,209.550644,177.531372,6.98075,167.033386,-21.788603,13.307206,161.555893,-19.764788,,, +131,2.183333,-5.328133,30.81587,1.840088,-10.687967,155.913284,-27.311754,-0.061904,0.919721,0.355422,1.710447,155.8284,174.71109,-7.784632,157.949585,-31.394661,-13.499377,158.007889,-27.220598,-77.502098,99.800728,179.938126,-16.870167,156.905029,-23.65649,82.874977,210.937912,174.27211,-4.622351,150.781082,-26.959709,84.574112,101.46769,177.377625,-75.954216,209.549088,177.531891,,,,13.31679,161.559113,-19.740587,,, +132,2.2,-5.320459,30.817268,1.835377,-10.676076,155.909515,-27.2852,-0.062083,0.920504,0.35537,1.710438,155.829208,174.710052,-7.77305,157.945602,-31.367376,-13.487333,158.004318,-27.193802,-77.502045,99.801018,179.938416,-16.858139,156.901382,-23.629736,82.874832,210.938507,174.268417,-4.610946,150.777069,-26.933929,84.573471,101.469185,177.374649,-75.95488,209.550858,177.533203,6.997086,167.032806,-21.746218,13.32656,161.562088,-19.717587,,, +133,2.216667,-5.327724,30.82855,1.834163,-10.663574,155.904999,-27.259228,-0.062503,0.920875,0.355534,1.710103,155.830307,174.70961,-7.761248,157.93988,-31.341499,-13.474737,157.999908,-27.16757,-77.501038,99.800957,179.939178,-16.844891,156.897598,-23.602697,82.873535,210.939621,174.264862,-4.598794,150.772949,-26.909044,84.572868,101.470245,177.375031,-75.955231,209.552811,177.53421,,,,13.338037,161.564499,-19.69313,,, +134,2.233333,-5.345024,30.830177,1.833659,-10.655119,155.902008,-27.237711,-0.060571,0.920236,0.355451,1.709769,155.829651,174.711243,-7.754344,157.935745,-31.320385,-13.466257,157.996979,-27.14662,-77.503067,99.800613,179.93837,-16.836323,156.895782,-23.581314,82.873329,210.939529,174.268982,-4.589984,150.769394,-26.88554,84.574089,101.467957,177.378983,-75.954857,209.551193,177.536224,,,,13.348148,161.565689,-19.671,,, +135,2.25,-5.356826,30.833206,1.831861,-10.646618,155.899399,-27.217901,-0.059293,0.921389,0.355273,1.709599,155.829315,174.711929,-7.746133,157.9328,-31.302013,-13.457685,157.994492,-27.127134,-77.503609,99.801315,179.937454,-16.827606,156.894196,-23.561415,82.872093,210.939102,174.266174,-4.581289,150.765961,-26.864132,84.574112,101.467308,177.377945,-75.953773,209.550507,177.540176,,,,13.355525,161.564667,-19.653082,,, +136,2.266667,-5.353495,30.828596,1.823013,-10.638456,155.897278,-27.199387,-0.059672,0.920269,0.355419,1.709598,155.82959,174.713242,-7.737107,157.930405,-31.283102,-13.449271,157.992722,-27.108925,-77.503082,99.801109,179.938751,-16.819658,156.892914,-23.543497,82.873413,210.939667,174.272614,-4.573896,150.763184,-26.845133,84.574165,101.467224,177.380798,-75.955063,209.550858,177.539047,,,,13.363173,161.563538,-19.634527,,, +137,2.283333,-5.314685,30.743446,1.749947,-10.636787,155.896133,-27.182817,-0.057693,0.920456,0.355602,1.709876,155.830353,174.712616,-7.726988,157.92746,-31.26322,-13.445745,157.994232,-27.096745,-77.503708,99.801949,179.936249,-16.822815,156.897552,-23.53668,82.873489,210.940521,174.272247,-4.577236,150.755356,-26.818148,84.574654,101.469063,177.377655,-75.954468,209.550217,177.54155,7.037464,167.023636,-21.654247,13.369714,161.560501,-19.61615,,, +138,2.3,-5.319096,30.742491,1.748415,-10.63046,155.894501,-27.165047,-0.059735,0.920045,0.355402,1.70944,155.828873,174.713547,-7.720149,157.925369,-31.245268,-13.439375,157.992691,-27.079218,-77.503075,99.801109,179.938553,-16.816534,156.896393,-23.519115,82.873962,210.938736,174.275284,-4.571237,150.753937,-26.800152,84.573288,101.467384,177.378983,-75.955162,209.549423,177.537582,7.04644,167.020111,-21.635977,13.375226,161.557297,-19.597977,,, +139,2.316667,-5.320023,30.751377,1.744761,-10.62535,155.894333,-27.149111,-0.057597,0.92076,0.355374,1.710286,155.830521,174.712936,-7.71476,157.925186,-31.230942,-13.434106,157.992691,-27.062965,-77.503983,99.800919,179.938934,-16.810812,156.896835,-23.502306,82.874153,210.940689,174.272369,-4.566403,150.753067,-26.784479,84.574249,101.469124,177.376511,-75.953117,209.551071,177.540894,7.054632,167.018753,-21.619152,13.380405,161.556,-19.578552,,, +140,2.333333,-5.313944,30.751257,1.744653,-10.619348,155.894028,-27.133947,-0.05966,0.919417,0.355132,1.710453,155.830429,174.711609,-7.708533,157.926086,-31.216549,-13.428102,157.992401,-27.04759,-77.503044,99.802269,179.936432,-16.804815,156.896149,-23.487051,82.87487,210.939789,174.272598,-4.560193,150.752121,-26.769192,84.573898,101.469208,177.377563,-75.953819,209.551651,177.535751,7.060304,167.020309,-21.603117,13.38608,161.557083,-19.558144,,, +141,2.35,-5.305038,30.748596,1.745884,-10.613665,155.895096,-27.120462,-0.0577,0.919805,0.355332,1.710379,155.8293,174.713608,-7.702396,157.92865,-31.203619,-13.42247,157.993378,-27.033878,-77.502594,99.803314,179.931992,-16.799316,156.896469,-23.473675,82.874313,210.938782,174.273636,-4.554291,150.752655,-26.755619,84.574478,101.468208,177.378876,-75.954239,209.548691,177.543427,7.063685,167.021484,-21.587299,13.391315,161.559158,-19.541967,,, +142,2.366667,-5.292495,30.744776,1.745733,-10.609124,155.896744,-27.106363,-0.059733,0.92046,0.355322,1.709917,155.829208,174.711746,-7.697803,157.931107,-31.18833,-13.417943,157.99501,-27.01951,-77.5019,99.802399,179.93483,-16.795021,156.897308,-23.45977,82.87532,210.939316,174.272339,-4.549796,150.75441,-26.742455,84.572685,101.467773,177.376678,-75.955185,209.549408,177.538986,7.067125,167.022629,-21.570911,13.394234,161.559036,-19.526529,,, +143,2.383333,-5.275711,30.746769,1.743795,-10.604364,155.898514,-27.092869,-0.057397,0.920315,0.355005,1.710511,155.830338,174.713776,-7.692763,157.93338,-31.173893,-13.413114,157.996826,-27.005348,-77.503845,99.802063,179.936508,-16.790113,156.898254,-23.445801,82.87529,210.940002,174.273102,-4.545441,150.756454,-26.731173,84.573662,101.468765,177.377945,-75.953194,209.550766,177.544205,7.069148,167.02562,-21.556728,13.397357,161.559158,-19.51173,,, +144,2.4,-5.256511,30.743256,1.737694,-10.600612,155.899734,-27.082029,-0.06143,0.91969,0.355075,1.710176,155.829651,174.709579,-7.688431,157.935196,-31.161667,-13.409187,157.99826,-26.994116,-77.502457,99.801491,179.937332,-16.78653,156.898987,-23.435112,82.874825,210.93924,174.270065,-4.542337,150.757462,-26.721876,84.574509,101.466263,177.379425,-75.954796,209.551819,177.531815,7.072174,167.027039,-21.541893,13.40061,161.559647,-19.498772,,, +145,2.416667,-5.254934,30.734858,1.744758,-10.598368,155.90094,-27.072668,-0.061018,0.919837,0.355282,1.70959,155.829132,174.710068,-7.686175,157.937454,-31.151793,-13.407205,157.999146,-26.984945,-77.503952,99.80146,179.937317,-16.784903,156.899124,-23.426502,82.875275,210.938934,174.272659,-4.539382,150.759094,-26.711935,84.573051,101.468102,177.376083,-75.954933,209.549332,177.532288,7.074834,167.026382,-21.528112,13.401623,161.559677,-19.488453,,, +146,2.433333,-5.256999,30.743652,1.754798,-10.596679,155.901276,-27.063953,-0.0621,0.92067,0.355759,1.709499,155.828918,174.710419,-7.685966,157.93869,-31.143307,-13.405787,157.999084,-26.975649,-77.503616,99.801781,179.938324,-16.78274,156.898438,-23.416704,82.875092,210.939056,174.271103,-4.536783,150.759933,-26.704247,84.572968,101.469925,177.374268,-75.955345,209.547806,177.533463,7.076833,167.024689,-21.515512,13.402596,161.557037,-19.479107,,, +147,2.45,-5.260717,30.748007,1.763144,-10.595834,155.899902,-27.057379,-0.062033,0.919592,0.355526,1.710215,155.828552,174.710129,-7.68537,157.937866,-31.13726,-13.405182,157.997391,-26.968813,-77.500305,99.801231,179.934814,-16.781694,156.896301,-23.40958,82.873878,210.939072,174.268906,-4.535316,150.759277,-26.698204,84.572586,101.466957,177.378174,-75.954163,209.54953,177.531357,7.077538,167.022675,-21.506384,13.404218,161.555573,-19.473034,,, +148,2.466667,-5.265494,30.75086,1.771942,-10.594062,155.897339,-27.052549,-0.064036,0.919423,0.355522,1.709951,155.828171,174.710388,-7.683785,157.935806,-31.133169,-13.403669,157.994476,-26.963818,-77.501869,99.802353,179.936356,-16.779823,156.892975,-23.404373,82.875038,210.938568,174.270355,-4.532762,150.757309,-26.693562,84.572372,101.467911,177.378418,-75.954346,209.547684,177.52861,7.078454,167.020157,-21.499058,13.405134,161.553604,-19.467777,,, +149,2.483333,-5.277138,30.741632,1.777796,-10.5931,155.892868,-27.049583,-0.059809,0.920964,0.354701,1.709763,155.830307,174.71022,-7.683073,157.930939,-31.129629,-13.402936,157.989716,-26.961597,-77.502838,99.802414,179.936844,-16.779522,156.888397,-23.4025,82.874779,210.939697,174.268509,-4.531258,150.753387,-26.688826,84.571602,101.468025,177.374405,-75.954002,209.552643,177.536728,7.07915,167.016678,-21.49399,13.406096,161.549271,-19.461369,,, +150,2.5,-5.295452,30.731985,1.787293,-10.592175,155.886612,-27.046814,-0.061541,0.920467,0.355705,1.709356,155.829666,174.710541,-7.681573,157.923752,-31.126543,-13.402355,157.983047,-26.959757,-77.501801,99.802734,179.935974,-16.779316,156.88205,-23.400921,82.874237,210.940643,174.270462,-4.529773,150.748627,-26.684317,84.571335,101.469376,177.374893,-75.955147,209.549164,177.5336,7.079881,167.0112,-21.491184,13.405042,161.543732,-19.454765,,, +151,2.516667,-5.313294,30.72072,1.793529,-10.591041,155.878296,-27.045933,-0.061778,0.92073,0.355863,1.709038,155.829102,174.709167,-7.680149,157.914139,-31.125099,-13.401469,157.974426,-26.959934,-77.503067,99.802147,179.936005,-16.778975,156.873962,-23.401451,82.873924,210.940094,174.269073,-4.5282,150.741486,-26.681387,84.571907,101.469467,177.373093,-75.955307,209.547836,177.531677,7.079119,167.005569,-21.489513,13.403404,161.537582,-19.449789,,, +152,2.533333,-5.326181,30.71314,1.803226,-10.590721,155.868286,-27.046257,-0.061819,0.920386,0.355799,1.709779,155.8302,174.708557,-7.679342,157.903915,-31.126043,-13.401489,157.964005,-26.960882,-77.50209,99.801888,179.936432,-16.779242,156.863495,-23.402647,82.873825,210.940903,174.268127,-4.527053,150.7323,-26.680023,84.5737,101.468956,177.375534,-75.954689,209.550507,177.530045,7.075925,167.000412,-21.488661,13.400422,161.534744,-19.445484,,, +153,2.55,-5.354495,30.696512,1.829641,-10.591301,155.857452,-27.049589,-0.062995,0.920568,0.355342,1.708629,155.8311,174.705841,-7.680402,157.892471,-31.128613,-13.402973,157.951996,-26.965466,-77.502754,99.801804,179.938156,-16.781157,156.850998,-23.407797,82.873093,210.940689,174.266495,-4.525575,150.72438,-26.680664,84.572594,101.468513,177.373596,-75.956482,209.554001,177.524979,7.070189,166.995102,-21.489408,13.395946,161.531464,-19.444353,,, +154,2.566667,-5.385851,30.685823,1.866453,-10.594143,155.846924,-27.054871,-0.063269,0.920984,0.355933,1.709185,155.829269,174.707825,-7.683821,157.882111,-31.133293,-13.407016,157.93988,-26.971582,-77.502701,99.802383,179.938095,-16.785053,156.837738,-23.414124,82.875191,210.940384,174.271225,-4.525754,150.717972,-26.684607,84.571487,101.470497,177.369431,-75.955101,209.547729,177.525726,7.061805,166.991501,-21.490005,13.38847,161.528458,-19.444735,,, +155,2.583333,-5.400962,30.659868,1.896794,-10.599984,155.836182,-27.062876,-0.062124,0.919789,0.355245,1.709363,155.829956,174.710022,-7.688668,157.873123,-31.140093,-13.413928,157.92775,-26.980722,-77.503929,99.801025,179.940887,-16.79287,156.823914,-23.424648,82.876015,210.940002,174.274872,-4.529273,150.710266,-26.690248,84.572731,101.468109,177.376892,-75.955605,209.551315,177.529663,7.050118,166.986664,-21.494543,13.378559,161.526413,-19.44701,,, +156,2.6,-5.427457,30.637537,1.94652,-10.607528,155.8246,-27.073076,-0.059313,0.920657,0.355479,1.709123,155.830658,174.710785,-7.695885,157.864243,-31.149944,-13.423128,157.913986,-26.991859,-77.503098,99.801933,179.93837,-16.802338,156.807571,-23.436838,82.875153,210.940979,174.276871,-4.53299,150.703339,-26.698347,84.572334,101.469078,177.372986,-75.955894,209.551285,177.533554,,,,13.366967,161.525635,-19.45104,,, +157,2.616667,-5.457406,30.633587,1.996089,-10.61699,155.812515,-27.083895,-0.061292,0.919548,0.355548,1.709333,155.8302,174.7099,-7.706581,157.854202,-31.160931,-13.434153,157.899796,-27.002844,-77.503319,99.801147,179.938751,-16.812525,156.791153,-23.447723,82.873932,210.941071,174.273056,-4.538715,150.695862,-26.708824,84.572945,101.46817,177.377151,-75.95462,209.551025,177.52858,,,,13.352683,161.526077,-19.455873,,, +158,2.633333,-5.484768,30.618208,2.057569,-10.626462,155.798416,-27.096233,-0.059595,0.92089,0.355516,1.70905,155.829742,174.712418,-7.716936,157.843536,-31.172878,-13.44561,157.883041,-27.015543,-77.503242,99.801216,179.939697,-16.82357,156.77095,-23.461105,82.87352,210.940338,174.273483,-4.543445,150.687378,-26.720318,84.573456,101.467026,177.378555,-75.955627,209.550613,177.537491,,,,13.338536,161.529617,-19.464052,,, +159,2.65,-5.487935,30.616234,2.112522,-10.630079,155.780304,-27.106688,-0.059469,0.920519,0.355391,1.708865,155.831223,174.709457,-7.723125,157.829697,-31.183317,-13.450941,157.862549,-27.024967,-77.503853,99.802017,179.937393,-16.827826,156.746155,-23.470863,82.873009,210.941742,174.270798,-4.542469,150.673401,-26.732388,84.571579,101.469872,177.372559,-75.954544,209.552353,177.532501,6.980345,166.980942,-21.516636,13.326152,161.537308,-19.469177,,, +160,2.666667,-5.514996,30.567621,2.171607,-10.628544,155.765671,-27.120924,-0.057585,0.92087,0.355465,1.708766,155.829895,174.712387,-7.720981,157.817978,-31.194893,-13.451475,157.845184,-27.041239,-77.504379,99.800789,179.938553,-16.829977,156.725342,-23.489758,82.87339,210.939789,174.274658,-4.53625,150.664597,-26.742247,84.572479,101.469063,177.374023,-75.955696,209.550766,177.539658,,,,13.317187,161.55072,-19.469284,,, +161,2.683333,-5.555635,30.48933,2.219524,-10.620719,155.752045,-27.137535,-0.061699,0.920861,0.355653,1.708266,155.82988,174.711212,-7.710005,157.805145,-31.207264,-13.445515,157.829208,-27.062086,-77.503334,99.800934,179.941208,-16.827646,156.707489,-23.514648,82.873604,210.94043,174.273819,-4.524714,150.656799,-26.750177,84.57151,101.46859,177.375549,-75.956909,209.550888,177.532272,6.954587,166.995483,-21.523872,13.313568,161.567657,-19.463093,,, +162,2.7,-5.559944,30.371113,2.189304,-10.61286,155.73732,-27.151724,-0.059905,0.92096,0.355569,1.708969,155.829544,174.710983,-7.694846,157.789536,-31.216728,-13.43728,157.815201,-27.082911,-77.503448,99.800743,179.939789,-16.827129,156.695557,-23.542192,82.874123,210.939621,174.273102,-4.518075,150.639038,-26.748249,84.571823,101.469383,177.372742,-75.955917,209.550308,177.535461,6.952961,166.99971,-21.526443,13.312846,161.578613,-19.453287,,, +163,2.716667,-5.617266,30.393021,2.242862,-10.59373,155.721207,-27.157984,-0.058386,0.921261,0.355628,1.709077,155.83046,174.713242,-7.678498,157.771774,-31.22337,-13.41971,157.796951,-27.08897,-77.503113,99.801865,179.93869,-16.807076,156.67659,-23.546103,82.873451,210.940048,174.274231,-4.495649,150.629654,-26.756584,84.572517,101.470474,177.373795,-75.955894,209.550858,177.541092,,,,13.314903,161.577194,-19.440496,,, +164,2.733333,-5.645491,30.336367,2.218426,-10.582861,155.708206,-27.16296,-0.060106,0.920787,0.355336,1.708789,155.829605,174.712234,-7.662827,157.755096,-31.22646,-13.408349,157.784775,-27.098297,-77.504234,99.800018,179.941055,-16.799629,156.667831,-23.558098,82.873787,210.938904,174.272034,-4.486616,150.615555,-26.752087,84.571686,101.469612,177.375122,-75.956116,209.551285,177.538269,,,,13.319077,161.564804,-19.428003,,, +165,2.75,-5.675326,30.294048,2.187874,-10.575998,155.700485,-27.165199,-0.060117,0.920566,0.355783,1.708984,155.830093,174.712341,-7.651027,157.742859,-31.228123,-13.400735,157.778198,-27.104382,-77.503426,99.801338,179.939789,-16.795206,156.665344,-23.56595,82.873352,210.939758,174.273575,-4.482325,150.606247,-26.745983,84.572304,101.471153,177.374451,-75.956024,209.550507,177.536499,,,,13.323461,161.55014,-19.416601,,, +166,2.766667,-5.684574,30.284367,2.153424,-10.573367,155.698166,-27.164438,-0.056566,0.921363,0.355605,1.709442,155.829742,174.715698,-7.646681,157.737778,-31.228374,-13.397079,157.777313,-27.105206,-77.503296,99.800407,179.939178,-16.792883,156.667801,-23.567005,82.874321,210.940033,174.276428,-4.482006,150.600525,-26.740965,84.57251,101.46936,177.376083,-75.955597,209.550049,177.548141,,,,13.326672,161.538208,-19.411732,,, +167,2.783333,-5.678185,30.22369,2.086822,-10.580565,155.702271,-27.164534,-0.059628,0.921176,0.355269,1.709274,155.829758,174.71373,-7.647762,157.738312,-31.227222,-13.402481,157.783966,-27.109545,-77.503357,99.801491,179.940063,-16.803354,156.679184,-23.574736,82.875076,210.939438,174.273483,-4.493731,150.598251,-26.730419,84.572853,101.46804,177.378769,-75.956635,209.550949,177.543381,,,,13.328579,161.529572,-19.414341,,, +168,2.8,-5.670135,30.248596,2.080403,-10.586121,155.709656,-27.162434,-0.059065,0.921719,0.355595,1.709165,155.830307,174.712402,-7.655843,157.745071,-31.225512,-13.407723,157.791733,-27.106077,-77.502296,99.803017,179.937866,-16.807255,156.687134,-23.569921,82.874489,210.939835,174.274261,-4.499691,150.604767,-26.731318,84.57148,101.471222,177.370636,-75.955963,209.550217,177.539688,,,,13.328285,161.525803,-19.422705,,, +169,2.816667,-5.647131,30.29747,2.083853,-10.595776,155.718887,-27.159431,-0.060575,0.921507,0.355874,1.708602,155.829132,174.712082,-7.668796,157.756348,-31.224846,-13.417262,157.801041,-27.099764,-77.503754,99.800232,179.940323,-16.813807,156.695007,-23.561186,82.87394,210.939285,174.271225,-4.508998,150.61322,-26.73527,84.572052,101.469872,177.374847,-75.957123,209.549194,177.540085,,,,13.326411,161.526703,-19.436901,,, +170,2.833333,-5.621195,30.354933,2.10284,-10.607854,155.728577,-27.157358,-0.059922,0.920551,0.354937,1.709212,155.829926,174.711166,-7.685967,157.769257,-31.224546,-13.429664,157.810165,-27.093506,-77.502632,99.801483,179.936676,-16.822369,156.701309,-23.552128,82.874268,210.939575,174.269791,-4.519634,150.623444,-26.742214,84.572968,101.46582,177.380325,-75.956688,209.552979,177.539917,,,,13.323003,161.530914,-19.456308,,, +171,2.85,-5.603714,30.403156,2.133275,-10.620029,155.735184,-27.155622,-0.057662,0.920702,0.354803,1.709229,155.830505,174.712112,-7.701439,157.779419,-31.224701,-13.442559,157.815689,-27.088085,-77.501991,99.80146,179.938126,-16.831728,156.703522,-23.544355,82.874336,210.939606,174.275879,-4.529819,150.632263,-26.748901,84.572472,101.466324,177.376297,-75.956223,209.554199,177.538864,,,,13.319042,161.535843,-19.473898,,, +172,2.866667,-5.591925,30.449413,2.16745,-10.628821,155.737381,-27.154345,-0.057098,0.920899,0.354826,1.709728,155.830292,174.713837,-7.714383,157.785233,-31.225065,-13.452193,157.81662,-27.08334,-77.502388,99.80172,179.936249,-16.837851,156.701202,-23.537285,82.873711,210.938477,174.271713,-4.536066,150.636856,-26.755371,84.572777,101.468422,177.377182,-75.955536,209.553528,177.546768,,,,13.315424,161.541855,-19.490671,6.961214,166.97287,-21.551258 +173,2.883333,-5.590379,30.487556,2.197977,-10.633065,155.734772,-27.153343,-0.055627,0.921686,0.35457,1.709312,155.831223,174.714218,-7.721931,157.785202,-31.225756,-13.457201,157.812881,-27.079725,-77.503166,99.80323,179.93689,-16.839912,156.695068,-23.531607,82.873154,210.939331,174.273056,-4.538202,150.636475,-26.760139,84.572372,101.468506,177.375031,-75.954857,209.55426,177.547318,,,,13.312758,161.546188,-19.50255,6.951904,166.97403,-21.555719 +174,2.9,-5.600084,30.50577,2.224377,-10.633783,155.72789,-27.15238,-0.061476,0.920702,0.355272,1.708884,155.830215,174.710724,-7.724358,157.779831,-31.226089,-13.45865,157.804962,-27.077627,-77.503342,99.800941,179.940216,-16.839693,156.685699,-23.528379,82.873421,210.939972,174.268921,-4.536956,150.631729,-26.761618,84.572418,101.468109,177.377945,-75.956306,209.552673,177.535599,,,,13.312194,161.548279,-19.510633,6.948453,166.973633,-21.5604 +175,2.916667,-5.615423,30.506214,2.234206,-10.631013,155.720459,-27.152617,-0.06197,0.919698,0.355163,1.709501,155.829697,174.709717,-7.721685,157.771759,-31.226471,-13.456181,157.797134,-27.078173,-77.502769,99.800232,179.93985,-16.836981,156.678024,-23.528648,82.874336,210.938385,174.271255,-4.533636,150.625748,-26.761528,84.574066,101.467323,177.378799,-75.956635,209.55307,177.531799,,,,13.313829,161.548538,-19.512398,6.947281,166.970413,-21.563345 +176,2.933333,-5.629127,30.48641,2.23439,-10.62477,155.71347,-27.153206,-0.06118,0.91972,0.355322,1.708924,155.829224,174.710022,-7.715062,157.764084,-31.226297,-13.45004,157.79007,-27.080229,-77.502861,99.801125,179.937653,-16.832022,156.671661,-23.531599,82.873787,210.938782,174.27301,-4.527061,150.618652,-26.758421,84.572334,101.467514,177.376297,-75.956467,209.551193,177.53096,,,,13.317184,161.548264,-19.509279,6.950193,166.968262,-21.565172 +177,2.95,-5.645313,30.469086,2.223977,-10.617271,155.708344,-27.153954,-0.062668,0.920001,0.355626,1.70912,155.82991,174.70813,-7.706306,157.757233,-31.22673,-13.442302,157.785309,-27.082649,-77.503487,99.800552,179.940872,-16.825544,156.668671,-23.53467,82.874794,210.938995,174.273071,-4.520234,150.612717,-26.755217,84.573349,101.470078,177.373032,-75.956619,209.55159,177.526016,,,,13.321885,161.548096,-19.503016,6.95633,166.96666,-21.566082 +178,2.966667,-5.6651,30.448471,2.213856,-10.610152,155.705765,-27.154564,-0.064015,0.919254,0.355637,1.709458,155.829269,174.707947,-7.697227,157.752747,-31.227531,-13.434967,157.783096,-27.085215,-77.502785,99.801468,179.938629,-16.819664,156.668396,-23.538015,82.874573,210.939072,174.271698,-4.513776,150.609482,-26.751205,84.5728,101.46946,177.374557,-75.955109,209.549881,177.522324,,,,13.327251,161.547409,-19.498217,6.96316,166.96582,-21.565855 +179,2.983333,-5.690861,30.518375,2.256828,-10.59951,155.703918,-27.151125,-0.060567,0.919888,0.355294,1.709059,155.829651,174.709778,-7.692185,157.750381,-31.225828,-13.425321,157.77977,-27.07831,-77.502365,99.801788,179.936127,-16.804897,156.663544,-23.526711,82.873688,210.939194,174.272385,-4.50082,150.612823,-26.757282,84.572037,101.468208,177.374863,-75.955673,209.551422,177.531509,,,,13.330558,161.54686,-19.495415,6.968647,166.965454,-21.565908 +180,3,-5.698954,30.522217,2.256375,-10.597112,155.704391,-27.149221,-0.062114,0.919074,0.355268,1.709159,155.829926,174.708481,-7.6903,157.749817,-31.224119,-13.422889,157.780304,-27.076521,-77.501968,99.801956,179.935867,-16.802246,156.664627,-23.524534,82.874275,210.938766,174.27243,-4.498522,150.613434,-26.755154,84.571907,101.469131,177.374847,-75.956306,209.552246,177.527481,,,,13.333138,161.547119,-19.49609,6.971807,166.966385,-21.566269 +181,3.016667,-5.687163,30.463064,2.220781,-10.603676,155.706406,-27.147633,-0.061152,0.920373,0.355324,1.708191,155.830582,174.707291,-7.692042,157.751907,-31.221537,-13.428638,157.783539,-27.078211,-77.503937,99.801872,179.937317,-16.812311,156.669708,-23.529758,82.873245,210.939819,174.269928,-4.506878,150.611099,-26.744614,84.571091,101.469971,177.370926,-75.956429,209.552414,177.528015,,,,13.33536,161.549408,-19.500029,6.971797,166.967178,-21.566509 +182,3.033333,-5.704307,30.568378,2.284643,-10.599419,155.706146,-27.140675,-0.063816,0.920441,0.355565,1.70887,155.830124,174.707657,-7.696274,157.753418,-31.217909,-13.425845,157.781082,-27.065262,-77.502686,99.800179,179.940033,-16.801823,156.663696,-23.510603,82.873322,210.939972,174.265594,-4.49888,150.617188,-26.752537,84.571144,101.470123,177.373505,-75.956108,209.552429,177.527802,,,,13.337059,161.553116,-19.506847,6.969434,166.968918,-21.567902 +183,3.05,-5.682972,30.538404,2.26025,-10.60824,155.707489,-27.135826,-0.06249,0.919392,0.355069,1.709658,155.829102,174.709015,-7.703402,157.755859,-31.212727,-13.434058,157.783295,-27.061663,-77.502228,99.800728,179.936691,-16.812365,156.666412,-23.509058,82.87352,210.937912,174.2677,-4.508677,150.614807,-26.743233,84.572418,101.467827,177.376694,-75.95507,209.551956,177.529907,,,,13.337235,161.556458,-19.514137,6.965309,166.970016,-21.567526 +184,3.066667,-5.670243,30.571281,2.282861,-10.610569,155.707367,-27.130566,-0.063164,0.920369,0.355356,1.709023,155.829086,174.708527,-7.708073,157.758636,-31.20896,-13.436926,157.782333,-27.053816,-77.502663,99.80098,179.938431,-16.812767,156.662994,-23.499643,82.872795,210.937912,174.265457,-4.509408,150.616135,-26.74365,84.571815,101.469269,177.374146,-75.955727,209.55127,177.529739,,,,13.337668,161.559921,-19.520247,6.96131,166.970642,-21.566368 +185,3.083333,-5.659174,30.596052,2.303708,-10.612265,155.70845,-27.126682,-0.06098,0.921767,0.355374,1.709504,155.829529,174.709885,-7.711466,157.761963,-31.206003,-13.439142,157.782623,-27.047846,-77.502686,99.802185,179.9375,-16.813046,156.661041,-23.492538,82.872833,210.939026,174.264832,-4.50976,150.618958,-26.744667,84.573326,101.468369,177.374649,-75.954453,209.550308,177.535873,,,,13.338793,161.562622,-19.525146,6.958497,166.971268,-21.562437 +186,3.1,-5.650136,30.689102,2.368343,-10.606084,155.710022,-27.122465,-0.058195,0.92094,0.35463,1.710042,155.82959,174.712585,-7.713137,157.767929,-31.204208,-13.434494,157.781876,-27.03727,-77.502945,99.80085,179.937881,-16.801399,156.654968,-23.477018,82.874001,210.938217,174.269943,-4.499419,150.626358,-26.755869,84.572525,101.467278,177.376312,-75.953606,209.552597,177.542084,,,,13.340968,161.565582,-19.527924,6.95786,166.973618,-21.558365 +187,3.116667,-5.641435,30.703812,2.384185,-10.602589,155.713837,-27.121168,-0.056811,0.921332,0.354665,1.709511,155.830185,174.712296,-7.711149,157.773224,-31.202837,-13.431412,157.785065,-27.034578,-77.502533,99.803635,179.932785,-16.797085,156.656403,-23.473717,82.872955,210.938614,174.269653,-4.494947,150.631668,-26.758047,84.571281,101.468765,177.372559,-75.95369,209.552032,177.543793,,,,13.343477,161.569931,-19.52672,6.960096,166.978439,-21.552927 +188,3.133333,-5.619296,30.687616,2.379836,-10.596279,155.717773,-27.122005,-0.059073,0.920043,0.354776,1.709644,155.830048,174.710327,-7.703867,157.778748,-31.202274,-13.425049,157.789078,-27.035507,-77.502823,99.801971,179.934982,-16.79179,156.659302,-23.476007,82.873146,210.938614,174.269028,-4.488812,150.634903,-26.758602,84.572815,101.467552,177.376312,-75.954369,209.552979,177.536224,,,,13.348579,161.574173,-19.522148,6.965089,166.981812,-21.546482 +189,3.15,-5.612029,30.670712,2.375241,-10.587006,155.720261,-27.122711,-0.059794,0.920256,0.355379,1.709692,155.828522,174.712082,-7.694234,157.781525,-31.201866,-13.41572,157.791656,-27.036884,-77.502014,99.801872,179.934875,-16.783575,156.661713,-23.478497,82.873634,210.938049,174.271545,-4.479485,150.636749,-26.757515,84.572884,101.467552,177.376907,-75.954948,209.549026,177.538101,,,,13.354169,161.576706,-19.512154,6.974667,166.985062,-21.539951 +190,3.166667,-5.600535,30.641148,2.357426,-10.57571,155.720657,-27.121534,-0.057441,0.9197,0.354959,1.709854,155.831268,174.711258,-7.6805,157.781494,-31.198982,-13.404024,157.792679,-27.037148,-77.502098,99.803909,179.932022,-16.774042,156.6633,-23.480623,82.87323,210.940811,174.271652,-4.469325,150.635651,-26.753145,84.573067,101.468231,177.377228,-75.954147,209.553223,177.538528,,,,13.361928,161.57753,-19.500362,6.984174,166.987503,-21.531927 +191,3.183333,-5.620857,30.653719,2.385284,-10.558848,155.720596,-27.119562,-0.060827,0.919553,0.355125,1.708847,155.830338,174.708328,-7.665197,157.779877,-31.195747,-13.387958,157.791489,-27.034664,-77.502769,99.802803,179.934448,-16.756607,156.661179,-23.477144,82.87339,210.939362,174.269409,-4.451172,150.640076,-26.754269,84.571533,101.468948,177.374649,-75.95607,209.552628,177.53125,,,,13.370213,161.578323,-19.486618,6.993609,166.989151,-21.525133 +192,3.2,-5.611437,30.625452,2.36725,-10.546265,155.719727,-27.116722,-0.059994,0.919047,0.35468,1.710059,155.830841,174.708481,-7.649869,157.77832,-31.191147,-13.37496,157.791245,-27.033278,-77.502563,99.803802,179.93335,-16.745701,156.661652,-23.477507,82.874252,210.938889,174.271255,-4.439931,150.638031,-26.748547,84.572388,101.469864,177.372879,-75.953346,209.553238,177.52919,,,,13.379555,161.578949,-19.473207,7.003918,166.989197,-21.517786 +193,3.216667,-5.600882,30.606552,2.351875,-10.536563,155.720001,-27.11297,-0.057873,0.919769,0.354342,1.709652,155.831192,174.710388,-7.638323,157.778214,-31.186462,-13.364877,157.792084,-27.03042,-77.502686,99.802925,179.934509,-16.737087,156.662994,-23.475885,82.873596,210.938934,174.271271,-4.431304,150.637085,-26.742836,84.572723,101.467575,177.376038,-75.954834,209.555679,177.537369,,,,13.388033,161.577225,-19.461721,7.012852,166.989319,-21.511755 +194,3.233333,-5.581017,30.596045,2.333263,-10.531226,155.722702,-27.108686,-0.061845,0.919304,0.355371,1.709729,155.829376,174.707474,-7.631527,157.780594,-31.180828,-13.359017,157.795502,-27.026356,-77.50267,99.799881,179.936768,-16.732267,156.666641,-23.472733,82.873627,210.939056,174.268402,-4.427548,150.638428,-26.738501,84.573242,101.46772,177.375702,-75.95446,209.551483,177.526611,,,,13.394298,161.574524,-19.455486,7.020445,166.987976,-21.50543 +195,3.25,-5.556447,30.593708,2.312074,-10.528634,155.727127,-27.103043,-0.058748,0.919061,0.355173,1.710056,155.828934,174.711349,-7.628517,157.785217,-31.174465,-13.355783,157.800797,-27.020412,-77.50238,99.801193,179.932831,-16.729639,156.672134,-23.467306,82.872856,210.938187,174.270523,-4.426405,150.640564,-26.733366,84.573822,101.466965,177.378937,-75.953987,209.550613,177.536728,,,,13.398274,161.570587,-19.452465,7.02752,166.985077,-21.499989 +196,3.266667,-5.565109,30.604641,2.321189,-10.528059,155.733673,-27.096182,-0.061129,0.918846,0.355166,1.710335,155.829208,174.709671,-7.628535,157.791183,-31.167984,-13.355435,157.807022,-27.013123,-77.502213,99.802338,179.933884,-16.728437,156.678207,-23.459249,82.873543,210.937927,174.269562,-4.425417,150.648483,-26.728006,84.574112,101.468231,177.377899,-75.953499,209.550507,177.530487,,,,13.403724,161.568817,-19.450521,,, +197,3.283333,-5.540799,30.609484,2.313076,-10.528783,155.739944,-27.090132,-0.062614,0.918833,0.355283,1.709878,155.829391,174.710175,-7.629117,157.799011,-31.161478,-13.355884,157.813629,-27.00614,-77.502434,99.802574,179.935501,-16.728775,156.684006,-23.452419,82.872536,210.938889,174.268311,-4.426809,150.653656,-26.724138,84.574242,101.467194,177.381653,-75.953506,209.550476,177.528107,,,,13.406441,161.568863,-19.449116,7.035993,166.987106,-21.489975 +198,3.3,-5.516622,30.626207,2.314918,-10.52878,155.745621,-27.082979,-0.056804,0.919655,0.354501,1.710877,155.830688,174.71376,-7.62999,157.806305,-31.154018,-13.355856,157.819275,-26.99725,-77.503906,99.801758,179.936691,-16.727707,156.688095,-23.443035,82.873672,210.939163,174.271713,-4.426845,150.659515,-26.72134,84.574364,101.467918,177.379425,-75.951401,209.553482,177.542267,,,,13.409467,161.570068,-19.447548,7.038596,166.988037,-21.483978 +199,3.316667,-5.492651,30.636602,2.310846,-10.528556,155.749588,-27.075895,-0.062712,0.919315,0.355034,1.709286,155.82962,174.707977,-7.629767,157.81221,-31.147682,-13.355454,157.823425,-26.988878,-77.504562,99.801102,179.938934,-16.72677,156.691147,-23.434507,82.873306,210.938354,174.26915,-4.426866,150.662384,-26.716766,84.574104,101.467499,177.377838,-75.954109,209.551865,177.525055,,,,13.412682,161.571198,-19.445164,7.041728,166.989273,-21.476704 +200,3.333333,-5.471709,30.646076,2.30497,-10.526482,155.752472,-27.069368,-0.062553,0.91959,0.355416,1.709037,155.828995,174.708878,-7.628558,157.815964,-31.140778,-13.353151,157.826569,-26.981262,-77.504692,99.800621,179.938889,-16.724031,156.693527,-23.42672,82.872925,210.938675,174.269104,-4.425233,150.664459,-26.7127,84.574028,101.467537,177.37822,-75.954521,209.550018,177.526779,,,,13.415564,161.571854,-19.438999,7.044791,166.989471,-21.470169 +201,3.35,-5.463599,30.656734,2.301526,-10.524122,155.756027,-27.064308,-0.061123,0.919149,0.355154,1.709815,155.829361,174.711304,-7.626509,157.820038,-31.136766,-13.350633,157.830307,-26.975462,-77.503586,99.801994,179.937317,-16.720951,156.697113,-23.420437,82.874214,210.939026,174.272842,-4.422975,150.667206,-26.708866,84.572205,101.468742,177.377228,-75.952736,209.549667,177.530075,,,,13.4174,161.570419,-19.431173,7.048598,166.990234,-21.462181 +202,3.366667,-5.445652,30.641909,2.29462,-10.520837,155.760956,-27.062967,-0.059561,0.919935,0.355022,1.709801,155.829895,174.711426,-7.622597,157.826614,-31.134773,-13.347207,157.835434,-26.974354,-77.503113,99.801376,179.937149,-16.718565,156.701614,-23.420517,82.87294,210.939285,174.270569,-4.419816,150.670731,-26.706345,84.573868,101.466957,177.378799,-75.953545,209.552078,177.534805,,,,13.41966,161.571365,-19.423151,7.052372,166.992889,-21.454071 +203,3.383333,-5.424906,30.626627,2.290272,-10.516502,155.766449,-27.063774,-0.063479,0.918886,0.354694,1.709196,155.829803,174.70755,-7.616987,157.833511,-31.134212,-13.342815,157.841019,-26.97526,-77.50415,99.80146,179.939026,-16.715183,156.706177,-23.422703,82.874092,210.937668,174.269745,-4.415741,150.675735,-26.70706,84.572739,101.468155,177.376251,-75.95549,209.553619,177.524155,,,,13.422662,161.575775,-19.415224,7.055966,166.998444,-21.446573 +204,3.4,-5.404294,30.614895,2.285946,-10.511925,155.771851,-27.065117,-0.061181,0.919603,0.355563,1.708559,155.828995,174.710068,-7.611623,157.840469,-31.134388,-13.338162,157.846527,-26.976526,-77.504341,99.801926,179.937439,-16.711327,156.710678,-23.425045,82.87339,210.93927,174.275116,-4.411373,150.680466,-26.708496,84.57283,101.467751,177.375931,-75.955322,209.548569,177.527863,,,,13.425858,161.578369,-19.407845,7.059813,167.002548,-21.440819 +205,3.416667,-5.378533,30.593657,2.272572,-10.508362,155.776947,-27.068388,-0.062015,0.919577,0.354738,1.708726,155.830292,174.709015,-7.606652,157.846481,-31.135717,-13.334291,157.852051,-26.980209,-77.50499,99.801979,179.939056,-16.709021,156.715607,-23.430412,82.873619,210.938553,174.270157,-4.408669,150.684219,-26.710897,84.572411,101.468262,177.376556,-75.955284,209.553024,177.528778,,,,13.428152,161.579208,-19.401413,7.063522,167.006271,-21.435244 +206,3.433333,-5.359856,30.588282,2.257814,-10.506036,155.781479,-27.071894,-0.060136,0.919545,0.354718,1.708757,155.829849,174.709274,-7.603786,157.851364,-31.138411,-13.331534,157.857162,-26.983631,-77.504684,99.801979,179.936569,-16.706911,156.720749,-23.434443,82.872879,210.937668,174.270813,-4.407269,150.68721,-26.714552,84.571869,101.468719,177.373764,-75.954994,209.552643,177.530792,,,,13.428727,161.579025,-19.397533,7.067255,167.007629,-21.432146 +207,3.45,-5.351383,30.575905,2.248415,-10.505089,155.78569,-27.076138,-0.060883,0.919862,0.354822,1.708876,155.829926,174.710022,-7.601726,157.855301,-31.141636,-13.330359,157.86171,-26.988388,-77.5047,99.803314,179.934402,-16.70668,156.725464,-23.440041,82.87262,210.93779,174.26741,-4.407143,150.690765,-26.717876,84.573273,101.468506,177.377609,-75.955429,209.551712,177.535309,,,,13.429997,161.578537,-19.39695,7.069144,167.009064,-21.432724 +208,3.466667,-5.340833,30.570721,2.242655,-10.505386,155.788162,-27.081558,-0.063092,0.918882,0.355096,1.708578,155.830444,174.707275,-7.602061,157.857864,-31.14591,-13.330503,157.864395,-26.993809,-77.504013,99.801949,179.936508,-16.70726,156.727936,-23.445946,82.873177,210.939117,174.268082,-4.407836,150.69278,-26.723444,84.572678,101.468483,177.378082,-75.956566,209.553177,177.526123,,,,13.429565,161.577423,-19.400644,7.070426,167.008942,-21.435379 +209,3.483333,-5.328703,30.565889,2.227639,-10.507348,155.789673,-27.086962,-0.065711,0.918799,0.355451,1.708003,155.829544,174.703934,-7.602598,157.858948,-31.150896,-13.332023,157.866501,-26.999346,-77.503693,99.802055,179.936005,-16.7094,156.730515,-23.451925,82.872406,210.938126,174.267166,-4.41116,150.693207,-26.728893,84.573021,101.468346,177.375076,-75.957565,209.551819,177.516388,,,,13.429499,161.574722,-19.406361,7.071866,167.00827,-21.440496 +210,3.5,-5.324086,30.576962,2.215552,-10.510879,155.790131,-27.092371,-0.060341,0.919901,0.354998,1.708738,155.830826,174.708145,-7.606418,157.858398,-31.156212,-13.335127,157.867538,-27.004314,-77.50428,99.80265,179.934479,-16.712107,156.7323,-23.45627,82.872131,210.93895,174.266998,-4.415824,150.692886,-26.735699,84.572914,101.469444,177.374405,-75.955666,209.553314,177.531937,,,,13.427547,161.570175,-19.414265,7.071723,167.004532,-21.447739 +211,3.516667,-5.331339,30.590839,2.206794,-10.517002,155.790085,-27.097378,-0.061204,0.919796,0.355488,1.708578,155.829697,174.708893,-7.612561,157.857025,-31.162766,-13.34091,157.86795,-27.0091,-77.503891,99.80146,179.934448,-16.717253,156.733948,-23.460051,82.872131,210.939957,174.266129,-4.422667,150.692093,-26.741112,84.572533,101.467575,177.378464,-75.955917,209.550476,177.533218,,,,13.425094,161.56456,-19.423794,7.069344,167.000092,-21.455795 +212,3.533333,-5.331028,30.615257,2.204852,-10.524445,155.790161,-27.100849,-0.058153,0.921531,0.355107,1.710302,155.830429,174.711472,-7.621524,157.856918,-31.167576,-13.348171,157.86821,-27.011404,-77.503273,99.801277,179.935211,-16.723097,156.734497,-23.46092,82.872681,210.940582,174.26178,-4.430323,150.691727,-26.747025,84.573517,101.468208,177.377731,-75.952866,209.55191,177.545959,,,,13.420062,161.560516,-19.43832,7.06426,166.996582,-21.468115 +213,3.55,-5.328286,30.630575,2.200456,-10.53438,155.791122,-27.106512,-0.058717,0.921021,0.354956,1.709959,155.830017,174.712799,-7.632221,157.857605,-31.173956,-13.357896,157.869415,-27.016315,-77.504143,99.80127,179.937912,-16.731998,156.735962,-23.464962,82.873573,210.939484,174.266602,-4.440656,150.692245,-26.754454,84.572807,101.468719,177.377792,-75.953438,209.551483,177.544327,,,,13.413741,161.559082,-19.456619,7.057258,166.994827,-21.4809 +214,3.566667,-5.33234,30.658485,2.20577,-10.544496,155.792725,-27.112997,-0.059406,0.921164,0.354769,1.709595,155.831436,174.711792,-7.644337,157.85939,-31.182039,-13.368039,157.870926,-27.02146,-77.502892,99.802818,179.936676,-16.740353,156.737457,-23.468416,82.87265,210.940674,174.264221,-4.450389,150.693954,-26.76372,84.572906,101.467789,177.380035,-75.954514,209.554474,177.543015,,,,13.406751,161.560089,-19.475883,7.048546,166.995712,-21.496332 +215,3.583333,-5.338067,30.679455,2.210814,-10.554769,155.792374,-27.11952,-0.061965,0.919575,0.355357,1.708911,155.830276,174.708969,-7.656106,157.858856,-31.189919,-13.378363,157.870468,-27.027046,-77.503464,99.801338,179.936905,-16.74931,156.737061,-23.472694,82.872452,210.940094,174.267014,-4.46038,150.693924,-26.772207,84.572098,101.468918,177.377228,-75.955292,209.552246,177.530411,,,,13.399837,161.561249,-19.491459,7.038236,166.996582,-21.51055 +216,3.6,-5.35025,30.704809,2.221615,-10.565092,155.791122,-27.124643,-0.061157,0.920589,0.355508,1.70881,155.829971,174.709244,-7.667801,157.857727,-31.197157,-13.388893,157.868896,-27.031126,-77.504425,99.801758,179.937317,-16.758085,156.735474,-23.475103,82.872421,210.940247,174.267456,-4.470002,150.693436,-26.77952,84.572495,101.469025,177.374863,-75.954163,209.550049,177.531067,,,,13.392033,161.563202,-19.504744,7.027641,166.995911,-21.522713 +217,3.616667,-5.363933,30.729,2.24111,-10.573816,155.789764,-27.129385,-0.062101,0.920387,0.355649,1.709442,155.829788,174.710541,-7.678998,157.856232,-31.203259,-13.398099,157.866821,-27.034739,-77.504402,99.800423,179.93898,-16.765413,156.732803,-23.477135,82.872948,210.939697,174.265045,-4.477332,150.693817,-26.786715,84.573013,101.47036,177.377228,-75.95459,209.550232,177.53569,,,,13.383572,161.566803,-19.518232,7.018132,166.996948,-21.533585 +218,3.633333,-5.364674,30.726078,2.253707,-10.58326,155.788773,-27.136391,-0.059648,0.920759,0.355351,1.709173,155.829865,174.711945,-7.688803,157.855591,-31.20924,-13.407946,157.86528,-27.041632,-77.504799,99.799965,179.940277,-16.77516,156.73024,-23.484251,82.872726,210.939713,174.268768,-4.486007,150.694473,-26.794565,84.572784,101.46904,177.377029,-75.954414,209.551208,177.538681,,,,13.376316,161.571793,-19.529533,7.007792,166.998322,-21.54273 +219,3.65,-5.356688,30.729527,2.257343,-10.591247,155.789658,-27.144661,-0.060258,0.919874,0.355101,1.708397,155.830948,174.71019,-7.697081,157.857559,-31.217518,-13.416026,157.866013,-27.049362,-77.503014,99.801704,179.937119,-16.782953,156.730209,-23.491959,82.870461,210.939713,174.268036,-4.493757,150.69545,-26.803923,84.573074,101.467384,177.379517,-75.956406,209.554871,177.534042,,,,13.368562,161.574417,-19.538492,6.998668,167.000381,-21.548992 +220,3.666667,-5.344,30.730913,2.258631,-10.599073,155.791489,-27.15303,-0.058701,0.921302,0.355199,1.709366,155.830795,174.71312,-7.704993,157.860703,-31.225903,-13.423887,157.867767,-27.057175,-77.503716,99.800575,179.941208,-16.790703,156.731064,-23.499949,82.871368,210.93924,174.268417,-4.50129,150.697037,-26.813421,84.571869,101.471619,177.373322,-75.953468,209.55336,177.54071,,,,13.361202,161.57515,-19.54549,6.991023,167.00235,-21.555222 +221,3.683333,-5.338277,30.736671,2.257182,-10.607352,155.795044,-27.160538,-0.058528,0.921915,0.355235,1.709839,155.82991,174.713242,-7.714722,157.86441,-31.232687,-13.432092,157.871399,-27.064222,-77.503288,99.79998,179.940414,-16.798595,156.734497,-23.506765,82.871239,210.939148,174.264832,-4.509681,150.700256,-26.821909,84.572609,101.469711,177.374908,-75.952568,209.552002,177.54332,,,,13.352757,161.57338,-19.552553,6.98312,167.003448,-21.562689 +222,3.7,-5.326179,30.74231,2.253692,-10.616302,155.799622,-27.168406,-0.05993,0.921685,0.35526,1.708459,155.830063,174.712891,-7.722975,157.869705,-31.240984,-13.440906,157.876129,-27.071455,-77.503326,99.799744,179.942368,-16.807144,156.7388,-23.513889,82.871033,210.939529,174.26741,-4.519027,150.704559,-26.831371,84.571495,101.468216,177.376892,-75.955505,209.553223,177.539841,,,,13.344197,161.572296,-19.560612,6.976274,167.004715,-21.568811 +223,3.716667,-5.304957,30.750738,2.247175,-10.625857,155.804108,-27.175669,-0.063396,0.92253,0.355484,1.708286,155.830444,174.707932,-7.732841,157.875076,-31.248007,-13.450217,157.88092,-27.077681,-77.50351,99.800407,179.943802,-16.816095,156.742828,-23.520008,82.871376,210.93924,174.261902,-4.529157,150.708267,-26.841003,84.57177,101.470581,177.370926,-75.95594,209.553238,177.529922,,,,13.337111,161.570053,-19.569128,6.96744,167.005081,-21.574741 +224,3.733333,-5.274624,30.79254,2.241451,-10.634457,155.806839,-27.181015,-0.062186,0.919494,0.354924,1.709283,155.83078,174.709946,-7.744281,157.879456,-31.254652,-13.458427,157.884033,-27.080006,-77.501816,99.802803,179.938934,-16.821922,156.744766,-23.520458,82.87204,210.938339,174.270218,-4.538194,150.709717,-26.853006,84.572289,101.469658,177.375717,-75.954742,209.554474,177.527267,,,,13.328478,161.567474,-19.579428,6.959423,167.006119,-21.581415 +225,3.75,-5.262324,30.80999,2.238716,-10.646255,155.810577,-27.186811,-0.06093,0.919291,0.355014,1.709159,155.830658,174.709381,-7.757066,157.884506,-31.262074,-13.470052,157.887939,-27.084558,-77.503433,99.800667,179.938507,-16.83256,156.74823,-23.524221,82.872833,210.938858,174.270935,-4.549984,150.712189,-26.860697,84.5737,101.468262,177.377899,-75.955757,209.554642,177.530426,,,,13.319344,161.56543,-19.58897,6.951331,167.005661,-21.587368 +226,3.766667,-5.268614,30.829668,2.246521,-10.656032,155.813583,-27.190845,-0.059323,0.917948,0.354932,1.708827,155.830688,174.709091,-7.768586,157.888,-31.267536,-13.47997,157.890717,-27.087683,-77.503929,99.802734,179.931458,-16.841125,156.750854,-23.526114,82.872566,210.93924,174.272614,-4.559124,150.715317,-26.866257,84.573074,101.468048,177.37822,-75.955994,209.553345,177.531006,,,,13.313119,161.564362,-19.596916,6.944162,167.005188,-21.591803 diff --git a/tests/test_io.py b/tests/test_io.py new file mode 100644 index 0000000..914a4fe --- /dev/null +++ b/tests/test_io.py @@ -0,0 +1,33 @@ +import numpy as np +import pytest + +from rigid_body_motion.io import load_optitrack + + +class TestIO: + def test_load_optitrack(self, optitrack_path): + """""" + pytest.importorskip("pandas") + + # numpy + data = load_optitrack(optitrack_path) + assert set(data.keys()) == {"RigidBody 01", "RigidBody 02"} + assert data["RigidBody 01"][0].shape == (227, 3) + assert data["RigidBody 01"][1].shape == (227, 4) + assert data["RigidBody 01"][2].shape == (227,) + assert np.issubdtype(data["RigidBody 01"][2].dtype, np.datetime64) + + # pandas + data = load_optitrack(optitrack_path, "pandas") + assert set(data.keys()) == {"RigidBody 01", "RigidBody 02"} + assert data["RigidBody 01"].shape == (227, 7) + + def test_load_optitrack_xr(self, optitrack_path): + """""" + pytest.importorskip("pandas") + pytest.importorskip("xarray") + + data = load_optitrack(optitrack_path, "xarray") + assert set(data.keys()) == {"RigidBody 01", "RigidBody 02"} + assert data["RigidBody 01"].position.shape == (227, 3) + assert data["RigidBody 01"].orientation.shape == (227, 4) diff --git a/tests/test_ros.py b/tests/test_ros.py index bdb7a69..a998b3f 100644 --- a/tests/test_ros.py +++ b/tests/test_ros.py @@ -48,7 +48,7 @@ def Transformer(): return tf.Transformer -class TestTransformer(object): +class TestTransformer: def test_moving_reference_frame(self, Transformer, head_dataset): """""" rbm.register_frame("world") @@ -202,6 +202,13 @@ def RosbagReader(): return io.RosbagReader +@pytest.fixture() +def RosbagWriter(): + """""" + io = pytest.importorskip("rigid_body_motion.ros.io") + return io.RosbagWriter + + class TestRosbagReader: def test_get_msg_type(self, RosbagReader, rosbag_path): """""" @@ -218,6 +225,19 @@ def test_get_msg_type(self, RosbagReader, rosbag_path): == "geometry_msgs/TransformStamped" ) + def test_get_topics_and_types(self, RosbagReader, rosbag_path): + """""" + with RosbagReader(rosbag_path) as reader: + info = reader.get_topics_and_types() + + assert info == { + "/camera/accel/sample": "sensor_msgs/Imu", + "/camera/gyro/sample": "sensor_msgs/Imu", + "/camera/odom/sample": "nav_msgs/Odometry", + "/vicon/t265_tracker/t265_tracker": "geometry_msgs/" + "TransformStamped", + } + def test_load_msgs(self, RosbagReader, rosbag_path): """""" # odometry @@ -291,6 +311,37 @@ def test_write_netcdf(self, RosbagReader, rosbag_path, export_folder): assert output_file.exists() +class TestRosbagWriter: + def test_write_transform_stamped(self, RosbagWriter, tmpdir): + """""" + rosbag_path = tmpdir / "test.bag" + + with RosbagWriter(rosbag_path) as writer: + writer.write_transform_stamped( + np.arange(10), + np.zeros((10, 3)), + np.zeros((10, 4)), + "/test", + "world", + "body", + ) + + assert rosbag_path.exists() + + def test_write_transform_stamped_dataset( + self, RosbagWriter, head_dataset, tmpdir + ): + """""" + rosbag_path = tmpdir / "test.bag" + + with RosbagWriter(rosbag_path) as writer: + writer.write_transform_stamped_dataset( + head_dataset.isel(time=range(100)), "/test", "world", "body", + ) + + assert rosbag_path.exists() + + # -- utils module -- # class MockPublisher: def __init__(self, n_msgs): diff --git a/tests/test_toplevel.py b/tests/test_toplevel.py index d6cc401..9b26b23 100644 --- a/tests/test_toplevel.py +++ b/tests/test_toplevel.py @@ -21,11 +21,14 @@ def test_example_data(self): """""" xr = pytest.importorskip("xarray") pytest.importorskip("netCDF4") + pytest.importorskip("pooch") xr.load_dataset(rbm.example_data["head"]) xr.load_dataset(rbm.example_data["left_eye"]) xr.load_dataset(rbm.example_data["right_eye"]) + assert rbm.example_data["rosbag"].exists() + def test_transform_points(self, rf_tree): """""" arr_child2 = (1.0, 1.0, 1.0)