├── .gitignore ├── BashScripts ├── imu.sh └── ipconfig.sh ├── CMakeLists.txt ├── README.md ├── include └── convert.h ├── launch └── slip_experiment.launch ├── offline ├── data │ ├── ATLAS_01ground.csv │ ├── ATLAS_01ground_003slip.csv │ ├── ATLAS_01ground_3steps.csv │ ├── GO1_matress.csv │ ├── GO1_normal_surface.csv │ ├── GO1_slippery_surface.csv │ └── info.txt └── src │ ├── atlas_contact_estimation.py │ └── go1_contact_estimation.py ├── package.xml └── src ├── check_forces.cpp ├── go1_pce.py ├── imuBias.txt ├── init_imu_force.cpp └── slip_recovery.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | __pycache__/ 2 | .vscode/* 3 | .history/ 4 | .~lock* 5 | -------------------------------------------------------------------------------- /BashScripts/imu.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | USBARG=$(ls -l /dev/ttyACM*) 4 | echo "${USBARG}" 5 | 6 | sudo chmod 777 /dev/ttyACM0 7 | rosrun rosserial_python serial_node.py /dev/ttyACM0 8 | -------------------------------------------------------------------------------- /BashScripts/ipconfig.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | sudo ifconfig lo multicast 4 | sudo route add -net 224.0.0.0 netmask 240.0.0.0 dev lo 5 | 6 | sudo ifconfig enp59s0 down 7 | sudo ifconfig enp59s0 up 192.168.123.162 netmask 255.255.255.0 8 | 9 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(pce) 3 | 4 | add_compile_options(-std=c++11) 5 | 6 | 7 | find_package(catkin REQUIRED COMPONENTS 8 | roscpp 9 | rospy 10 | unitree_legged_msgs 11 | geometry_msgs 12 | ) 13 | 14 | find_package(Boost REQUIRED COMPONENTS system) 15 | 16 | 17 | catkin_package( 18 | INCLUDE_DIRS include 19 | LIBRARIES ${PROJECT_NAME} 20 | CATKIN_DEPENDS roscpp rospy std_msgs unitree_legged_msgs 21 | DEPENDS system_lib 22 | ) 23 | 24 | 25 | # message("-- CMAKE_SYSTEM_PROCESSOR: ${CMAKE_SYSTEM_PROCESSOR}") 26 | # if("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "x86_64.*") 27 | # set(ARCH amd64) 28 | # else() 29 | # set(ARCH arm64) 30 | # endif() 31 | # set(LEGGED_SDK_NAME -pthread libunitree_legged_sdk_${ARCH}.so lcm) 32 | 33 | # set(EXTRA_LIBS ${LEGGED_SDK_NAME} lcm) 34 | 35 | 36 | # set(CMAKE_CXX_FLAGS "-O3 -fPIC") 37 | 38 | include_directories( 39 | include 40 | ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} 41 | ${unitree_legged_msgs_INCLUDE_DIRS} 42 | /unitree_legged_sdk/include 43 | ) 44 | link_directories(//unitree_legged_sdk/lib) 45 | link_directories($(catkin_LIB_DIRS) lib) 46 | 47 | add_executable(slip_recovery src/slip_recovery.cpp) 48 | target_link_libraries(slip_recovery ${EXTRA_LIBS} ${catkin_LIBRARIES}) 49 | add_dependencies(slip_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 50 | 51 | add_executable(init_imu_force src/init_imu_force.cpp) 52 | target_link_libraries(init_imu_force ${EXTRA_LIBS} ${catkin_LIBRARIES}) 53 | add_dependencies(init_imu_force ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 54 | 55 | add_executable(check_forces src/check_forces.cpp) 56 | target_link_libraries(check_forces ${EXTRA_LIBS} ${catkin_LIBRARIES}) 57 | add_dependencies(check_forces ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 58 | 59 | catkin_install_python(PROGRAMS src/go1_pce.py 60 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 61 | ) 62 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Probabilistic Contact Estimation 2 | 3 | This ROS package contains: 4 | 5 | * A **real-time contact detection module** that operates in real-time(~500hz) and uses only IMU mounted on the foot of the robot. It has been tested on a quadrupedal GO1, a real TALOS humanoid robot and a simulated ATLAS humanoid. 6 | * **Datasets** (*./offline/data/*) from an ATLAS simulated humanoid in RAISIM and a real GO1 quadruped on various terrains 7 | * An offline contact probability estimator module to test on custom datasets. 8 | 9 | The published manuscript can be found at: 10 | https://ieeexplore.ieee.org/document/10161485 11 | # Setup 12 | The only dependency for the offline module is *sklearn*. Run: 13 | ``` 14 | $ pip install -U scikit-learn 15 | ``` 16 | Then define the data filename you want to use at *offline/src/filename.py* and: 17 | ``` 18 | $ ./atlas_contact_estimation.py 19 | or 20 | $ ./go1_contact_estimation.py 21 | ``` 22 | Please note in case you are using another robot, you will need to fine-tune the threshold parameters inside the file by extracting them from a normal gait pattern (no slip). These thresholds are robot/control specific.(More details about how to extract them will be added soon) 23 | 24 | # Datasets 25 | ### **ATLAS bipedal** 26 | All files at ./offline/data/ATLAS_ have the same structure: \ 27 | Fx | Fy | Fz | Tx | Ty | Tz | ax | ay | az | wx | wy | wz | label 28 | 29 | The refresh rate of the meausurements is 1000 hz 30 | 31 | Description 32 | * ATLAS_01ground.csv : 0.1 static friction coef., ATLAS walking around. 33 | * ATLAS_01ground_3steps.csv: 0.1 static friction, 3 steps of ATLAS 34 | * ATLAS_01ground_003slip.csv: 0.1 ground static friction, 0.03 static friction on extremely slippery surface. 35 | 36 | ### **GO1 quadrupedal** 37 | All files at ./offline/data/GO1_ have the same structure: \ 38 | | Fz | ax | ay | az | wx | wy | wz | 39 | 40 | The refresh rate is 250 hz for the IMU and 500 hz for the Fz 41 | 42 | * *GO1_matress.csv*: Walking on soft terrain (a matress) 43 | * *GO1_normal_surface.csv*: Walking on a normal surface.(these data are unsynchronized) 44 | * *GO1_slippery_surface.csv*: Walking on a low friction surface. A greased smooth surface, extremely slippery. 45 | 46 | 47 | # Real-time Probabilistic Contact State Estimation 48 | 49 | Using Unitree's Go1 quadrupedal robot and low-end IMU sensor (Arduino RP2040 integrated IMU) mounted on the foot. 50 | 51 | ## Description 52 | 53 | An analytical package description of the real experiment with the Go1 robotic dog of Unitree. This package is developed to extra support the theoretical analysis and the simulated experiments of the submitted paper to ICRA 2022 with title "Probabilistic Contact State Estimation for Legged Robots using Inertial Information". 54 | 55 | 56 | # Dependencies 57 | ## Unitree's Go1 legged robot: 58 | 59 | * [unitree_ros_to_real](https://github.com/unitreerobotics/unitree_ros_to_real) 60 | * [unitree\_ros](https://github.com/unitreerobotics/unitree_ros) 61 | * [unitree_legged_sdk](https://github.com/unitreerobotics/unitree_legged_sdk) 62 | ## Arduino Nano RP2040's IMU: 63 | * [rosserial_python](http://wiki.ros.org/rosserial_python) 64 | 65 | ## System 66 | * Ubuntu 20.04 67 | * ROS Noetic 68 | 69 | # Installing 70 | 71 | * Follow the instructions of the above listed depended packages. 72 | * Under your 'workspace/src', git clone ProbabilisticContactEstimation package. 73 | ``` 74 | git clone https://github.com/MichaelMarav/ProbabilisticContactEstimation 75 | ``` 76 | Rename the package to "pce" (Compatible name for catkin package) 77 | # Executing program 78 | 79 | ## Terminal 1 80 | Connect to the real Go1 robot 81 | ``` 82 | sudo pce/BashScripts/ipconfig.sh 83 | ``` 84 | ``` 85 | roslaunch unitree_legged_real real.launch 86 | ``` 87 | ## Terminal 2 88 | Arduino pubs IMU data at ```\imu``` 89 | ``` 90 | sudo pce/BashScripts/imu.sh 91 | ``` 92 | 93 | ## Terminal 3 94 | Initialize IMU bias info 95 | * Set your path of "/.. /src/pce/src/imuBias.txt", at line 137 of 'init_imu_force.cpp' . 96 | ``` 97 | rosrun pce init_imu_force 98 | ``` 99 | ``` 100 | rosrun pce slip_recovery 101 | ``` 102 | # Experiment setup 103 | 104 | Mount IMU on a leg (or multiple legs) of Go1 Unitree's. Set the communication between Arduino Nano PR2040 and your Laptop through USB - micro cable. 105 | 106 | # Citation 107 | If you are using this work please use the following citation: 108 | ``` 109 | @INPROCEEDINGS{10161485, 110 | 111 | author={Maravgakis, Michael and Argiropoulos, Despina-Ekaterini and Piperakis, Stylianos and Trahanias, Panos}, 112 | 113 | booktitle={2023 IEEE International Conference on Robotics and Automation (ICRA)}, 114 | 115 | title={Probabilistic Contact State Estimation for Legged Robots using Inertial Information}, 116 | 117 | year={2023}, 118 | 119 | volume={}, 120 | 121 | number={}, 122 | 123 | pages={12163-12169}, 124 | 125 | doi={10.1109/ICRA48891.2023.10161485}} 126 | 127 | ``` 128 | -------------------------------------------------------------------------------- /include/convert.h: -------------------------------------------------------------------------------- 1 | /************************************************************************ 2 | Copyright (c) 2018-2019, Unitree Robotics.Co.Ltd. All rights reserved. 3 | Use of this source code is governed by the MPL-2.0 license, see LICENSE. 4 | ************************************************************************/ 5 | 6 | #ifndef _CONVERT_H_ 7 | #define _CONVERT_H_ 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include "unitree_legged_sdk/unitree_legged_sdk.h" 19 | #include 20 | #include 21 | 22 | UNITREE_LEGGED_SDK::BmsCmd rosMsg2Cmd(const unitree_legged_msgs::BmsCmd &msg) 23 | { 24 | UNITREE_LEGGED_SDK::BmsCmd cmd; 25 | 26 | cmd.off = msg.off; 27 | 28 | for (int i(0); i < 3; i++) 29 | { 30 | cmd.reserve[i] = msg.reserve[i]; 31 | } 32 | 33 | return cmd; 34 | } 35 | 36 | UNITREE_LEGGED_SDK::HighCmd rosMsg2Cmd(const unitree_legged_msgs::HighCmd::ConstPtr &msg) 37 | { 38 | UNITREE_LEGGED_SDK::HighCmd cmd; 39 | 40 | for (int i(0); i < 2; i++) 41 | { 42 | cmd.head[i] = msg->head[i]; 43 | cmd.SN[i] = msg->SN[i]; 44 | cmd.version[i] = msg->version[i]; 45 | cmd.position[i] = msg->position[i]; 46 | cmd.velocity[i] = msg->velocity[i]; 47 | } 48 | 49 | for (int i(0); i < 3; i++) 50 | { 51 | cmd.euler[i] = msg->euler[i]; 52 | } 53 | 54 | for (int i(0); i < 4; i++) 55 | { 56 | cmd.led[i].r = msg->led[i].r; 57 | cmd.led[i].g = msg->led[i].g; 58 | cmd.led[i].b = msg->led[i].b; 59 | } 60 | 61 | for (int i(0); i < 40; i++) 62 | { 63 | cmd.wirelessRemote[i] = msg->wirelessRemote[i]; 64 | } 65 | 66 | cmd.levelFlag = msg->levelFlag; 67 | cmd.frameReserve = msg->frameReserve; 68 | cmd.bandWidth = msg->bandWidth; 69 | cmd.mode = msg->mode; 70 | cmd.gaitType = msg->gaitType; 71 | cmd.speedLevel = msg->speedLevel; 72 | cmd.footRaiseHeight = msg->footRaiseHeight; 73 | cmd.bodyHeight = msg->bodyHeight; 74 | cmd.yawSpeed = msg->yawSpeed; 75 | cmd.reserve = msg->reserve; 76 | cmd.crc = msg->crc; 77 | 78 | cmd.bms = rosMsg2Cmd(msg->bms); 79 | 80 | return cmd; 81 | } 82 | 83 | UNITREE_LEGGED_SDK::MotorCmd rosMsg2Cmd(const unitree_legged_msgs::MotorCmd &msg) 84 | { 85 | UNITREE_LEGGED_SDK::MotorCmd cmd; 86 | 87 | cmd.mode = msg.mode; 88 | cmd.q = msg.q; 89 | cmd.dq = msg.dq; 90 | cmd.tau = msg.tau; 91 | cmd.Kp = msg.Kp; 92 | cmd.Kd = msg.Kd; 93 | 94 | for (int i(0); i < 3; i++) 95 | { 96 | cmd.reserve[i] = msg.reserve[i]; 97 | } 98 | 99 | return cmd; 100 | } 101 | 102 | UNITREE_LEGGED_SDK::LowCmd rosMsg2Cmd(const unitree_legged_msgs::LowCmd::ConstPtr &msg) 103 | { 104 | UNITREE_LEGGED_SDK::LowCmd cmd; 105 | 106 | for (int i(0); i < 2; i++) 107 | { 108 | cmd.head[i] = msg->head[i]; 109 | cmd.SN[i] = msg->SN[i]; 110 | cmd.version[i] = msg->version[i]; 111 | } 112 | 113 | for (int i(0); i < 40; i++) 114 | { 115 | cmd.wirelessRemote[i] = msg->wirelessRemote[i]; 116 | } 117 | 118 | for (int i(0); i < 20; i++) 119 | { 120 | cmd.motorCmd[i] = rosMsg2Cmd(msg->motorCmd[i]); 121 | } 122 | 123 | cmd.bms = rosMsg2Cmd(msg->bms); 124 | 125 | cmd.levelFlag = msg->levelFlag; 126 | cmd.frameReserve = msg->frameReserve; 127 | cmd.bandWidth = msg->bandWidth; 128 | cmd.reserve = msg->reserve; 129 | cmd.crc = msg->crc; 130 | 131 | return cmd; 132 | } 133 | 134 | unitree_legged_msgs::MotorState state2rosMsg(UNITREE_LEGGED_SDK::MotorState &state) 135 | { 136 | unitree_legged_msgs::MotorState ros_msg; 137 | 138 | ros_msg.mode = state.mode; 139 | ros_msg.q = state.q; 140 | ros_msg.dq = state.dq; 141 | ros_msg.ddq = state.ddq; 142 | ros_msg.tauEst = state.tauEst; 143 | ros_msg.q_raw = state.q_raw; 144 | ros_msg.dq_raw = state.dq_raw; 145 | ros_msg.ddq_raw = state.ddq_raw; 146 | ros_msg.temperature = state.temperature; 147 | 148 | ros_msg.reserve[0] = state.reserve[0]; 149 | ros_msg.reserve[1] = state.reserve[1]; 150 | 151 | return ros_msg; 152 | } 153 | 154 | unitree_legged_msgs::IMU state2rosMsg(UNITREE_LEGGED_SDK::IMU &state) 155 | { 156 | unitree_legged_msgs::IMU ros_msg; 157 | 158 | for (int i(0); i < 4; i++) 159 | { 160 | ros_msg.quaternion[i] = state.quaternion[i]; 161 | } 162 | 163 | for (int i(0); i < 3; i++) 164 | { 165 | ros_msg.gyroscope[i] = state.gyroscope[i]; 166 | ros_msg.accelerometer[i] = state.accelerometer[i]; 167 | ros_msg.rpy[i] = state.rpy[i]; 168 | } 169 | 170 | ros_msg.temperature = state.temperature; 171 | 172 | return ros_msg; 173 | } 174 | 175 | unitree_legged_msgs::BmsState state2rosMsg(UNITREE_LEGGED_SDK::BmsState &state) 176 | { 177 | unitree_legged_msgs::BmsState ros_msg; 178 | 179 | for (int i(0); i < 2; i++) 180 | { 181 | ros_msg.BQ_NTC[i] = state.BQ_NTC[i]; 182 | ros_msg.MCU_NTC[i] = state.MCU_NTC[i]; 183 | } 184 | 185 | for (int i(0); i < 10; i++) 186 | { 187 | ros_msg.cell_vol[i] = state.cell_vol[i]; 188 | } 189 | 190 | ros_msg.version_h = state.version_h; 191 | ros_msg.version_l = state.version_l; 192 | ros_msg.bms_status = state.bms_status; 193 | ros_msg.SOC = state.SOC; 194 | ros_msg.current = state.current; 195 | ros_msg.cycle = state.cycle; 196 | 197 | return ros_msg; 198 | } 199 | 200 | unitree_legged_msgs::LowState state2rosMsg(UNITREE_LEGGED_SDK::LowState &state) 201 | { 202 | unitree_legged_msgs::LowState ros_msg; 203 | 204 | for (int i(0); i < 2; i++) 205 | { 206 | ros_msg.head[i] = state.head[i]; 207 | ros_msg.SN[i] = state.SN[i]; 208 | ros_msg.version[i] = state.version[i]; 209 | } 210 | 211 | for (int i(0); i < 4; i++) 212 | { 213 | ros_msg.footForce[i] = state.footForce[i]; 214 | ros_msg.footForceEst[i] = state.footForceEst[i]; 215 | } 216 | 217 | for (int i(0); i < 40; i++) 218 | { 219 | ros_msg.wirelessRemote[i] = state.wirelessRemote[i]; 220 | } 221 | 222 | for (int i(0); i < 20; i++) 223 | { 224 | ros_msg.motorState[i] = state2rosMsg(state.motorState[i]); 225 | } 226 | 227 | ros_msg.imu = state2rosMsg(state.imu); 228 | 229 | ros_msg.bms = state2rosMsg(state.bms); 230 | 231 | ros_msg.tick = state.tick; 232 | ros_msg.reserve = state.reserve; 233 | ros_msg.crc = state.crc; 234 | 235 | return ros_msg; 236 | } 237 | 238 | unitree_legged_msgs::Cartesian state2rosMsg(UNITREE_LEGGED_SDK::Cartesian &state) 239 | { 240 | unitree_legged_msgs::Cartesian ros_msg; 241 | 242 | ros_msg.x = state.x; 243 | ros_msg.y = state.y; 244 | ros_msg.z = state.z; 245 | 246 | return ros_msg; 247 | } 248 | 249 | unitree_legged_msgs::HighState state2rosMsg(UNITREE_LEGGED_SDK::HighState &state) 250 | { 251 | unitree_legged_msgs::HighState ros_msg; 252 | 253 | for (int i(0); i < 2; i++) 254 | { 255 | ros_msg.head[i] = state.head[i]; 256 | ros_msg.SN[i] = state.SN[i]; 257 | ros_msg.version[i] = state.version[i]; 258 | } 259 | 260 | for (int i(0); i < 4; i++) 261 | { 262 | ros_msg.footForce[i] = state.footForce[i]; 263 | ros_msg.footForceEst[i] = state.footForceEst[i]; 264 | ros_msg.rangeObstacle[i] = state.rangeObstacle[i]; 265 | ros_msg.footPosition2Body[i] = state2rosMsg(state.footPosition2Body[i]); 266 | ros_msg.footSpeed2Body[i] = state2rosMsg(state.footSpeed2Body[i]); 267 | } 268 | 269 | for (int i(0); i < 3; i++) 270 | { 271 | ros_msg.position[i] = state.position[i]; 272 | ros_msg.velocity[i] = state.velocity[i]; 273 | } 274 | 275 | for (int i(0); i < 40; i++) 276 | { 277 | ros_msg.wirelessRemote[i] = state.wirelessRemote[i]; 278 | } 279 | 280 | for (int i(0); i < 20; i++) 281 | { 282 | ros_msg.motorState[i] = state2rosMsg(state.motorState[i]); 283 | } 284 | 285 | ros_msg.imu = state2rosMsg(state.imu); 286 | 287 | ros_msg.bms = state2rosMsg(state.bms); 288 | 289 | ros_msg.levelFlag = state.levelFlag; 290 | ros_msg.frameReserve = state.frameReserve; 291 | ros_msg.bandWidth = state.bandWidth; 292 | ros_msg.mode = state.mode; 293 | ros_msg.progress = state.progress; 294 | ros_msg.gaitType = state.gaitType; 295 | ros_msg.footRaiseHeight = state.footRaiseHeight; 296 | ros_msg.bodyHeight = state.bodyHeight; 297 | ros_msg.yawSpeed = state.yawSpeed; 298 | ros_msg.reserve = state.reserve; 299 | ros_msg.crc = state.crc; 300 | 301 | return ros_msg; 302 | } 303 | 304 | UNITREE_LEGGED_SDK::HighCmd rosMsg2Cmd(const geometry_msgs::Twist::ConstPtr &msg) 305 | { 306 | UNITREE_LEGGED_SDK::HighCmd cmd; 307 | 308 | cmd.head[0] = 0xFE; 309 | cmd.head[1] = 0xEF; 310 | cmd.levelFlag = UNITREE_LEGGED_SDK::HIGHLEVEL; 311 | cmd.mode = 0; 312 | cmd.gaitType = 0; 313 | cmd.speedLevel = 0; 314 | cmd.footRaiseHeight = 0; 315 | cmd.bodyHeight = 0; 316 | cmd.euler[0] = 0; 317 | cmd.euler[1] = 0; 318 | cmd.euler[2] = 0; 319 | cmd.velocity[0] = 0.0f; 320 | cmd.velocity[1] = 0.0f; 321 | cmd.yawSpeed = 0.0f; 322 | cmd.reserve = 0; 323 | 324 | cmd.velocity[0] = msg->linear.x; 325 | cmd.velocity[1] = msg->linear.y; 326 | cmd.yawSpeed = msg->angular.z; 327 | 328 | cmd.mode = 2; 329 | cmd.gaitType = 1; 330 | 331 | return cmd; 332 | } 333 | 334 | #endif // _CONVERT_H_ 335 | -------------------------------------------------------------------------------- /launch/slip_experiment.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /offline/data/GO1_matress.csv: -------------------------------------------------------------------------------- 1 | 251,-0.1651611328125,-0.9501953125,0.33544921875,0.30517578125,0.06103515625,0.30517578125 2 | 251,-0.1651611328125,-0.9501953125,0.33544921875,0.30517578125,0.06103515625,0.30517578125 3 | 251,-0.1651611328125,-0.9501953125,0.33544921875,0.30517578125,0.06103515625,0.30517578125 4 | 251,-0.1651611328125,-0.9501953125,0.33544921875,0.30517578125,0.06103515625,0.30517578125 5 | 251,-0.1651611328125,-0.9501953125,0.33544921875,0.30517578125,0.18310546875,0.30517578125 6 | 251,-0.16943359375,-0.945556640625,0.336181640625,0.30517578125,0.18310546875,0.30517578125 7 | 251,-0.16943359375,-0.945556640625,0.336181640625,0.30517578125,0.18310546875,0.30517578125 8 | 251,-0.16943359375,-0.945556640625,0.336181640625,0.30517578125,0.18310546875,0.30517578125 9 | 250,-0.16943359375,-0.945556640625,0.336181640625,0.30517578125,0.18310546875,0.30517578125 10 | 250,-0.16943359375,-0.945556640625,0.336181640625,0.3662109375,0,0.244140625 11 | 250,-0.17236328125,-0.947265625,0.3287353515625,0.3662109375,0,0.244140625 12 | 250,-0.17236328125,-0.947265625,0.3287353515625,0.3662109375,0,0.244140625 13 | 250,-0.17236328125,-0.947265625,0.3287353515625,0.3662109375,0,0.244140625 14 | 250,-0.17236328125,-0.947265625,0.3287353515625,0.3662109375,0,0.244140625 15 | 250,-0.1712646484375,-0.9482421875,0.3326416015625,0.42724609375,0,0.244140625 16 | 250,-0.1712646484375,-0.9482421875,0.3326416015625,0.42724609375,0,0.244140625 17 | 250,-0.1712646484375,-0.9482421875,0.3326416015625,0.42724609375,0,0.244140625 18 | 250,-0.1712646484375,-0.9482421875,0.3326416015625,0.42724609375,0,0.244140625 19 | 250,-0.1712646484375,-0.9482421875,0.3326416015625,0.42724609375,0.06103515625,0.18310546875 20 | 250,-0.1669921875,-0.9539794921875,0.326416015625,0.42724609375,0.06103515625,0.18310546875 21 | 250,-0.1669921875,-0.9539794921875,0.326416015625,0.42724609375,0.06103515625,0.18310546875 22 | 250,-0.1669921875,-0.9539794921875,0.326416015625,0.42724609375,0.06103515625,0.18310546875 23 | 250,-0.1669921875,-0.9539794921875,0.326416015625,0.42724609375,0.06103515625,0.18310546875 24 | 250,-0.1669921875,-0.9539794921875,0.326416015625,0.42724609375,0.06103515625,0.244140625 25 | 250,-0.1671142578125,-0.9481201171875,0.3297119140625,0.42724609375,0.06103515625,0.244140625 26 | 250,-0.1671142578125,-0.9481201171875,0.3297119140625,0.42724609375,0.06103515625,0.244140625 27 | 250,-0.1671142578125,-0.9481201171875,0.3297119140625,0.42724609375,0.06103515625,0.244140625 28 | 250,-0.1671142578125,-0.9481201171875,0.3297119140625,0.42724609375,0.06103515625,0.244140625 29 | 251,-0.1671142578125,-0.9481201171875,0.3297119140625,0.42724609375,0,0.30517578125 30 | 251,-0.1707763671875,-0.9454345703125,0.3321533203125,0.42724609375,0,0.30517578125 31 | 251,-0.1707763671875,-0.9454345703125,0.3321533203125,0.42724609375,0,0.30517578125 32 | 251,-0.1707763671875,-0.9454345703125,0.3321533203125,0.42724609375,0,0.30517578125 33 | 251,-0.1707763671875,-0.9454345703125,0.3321533203125,0.42724609375,0,0.30517578125 34 | 251,-0.1717529296875,-0.948486328125,0.3311767578125,0.3662109375,0.06103515625,0.244140625 35 | 251,-0.1717529296875,-0.948486328125,0.3311767578125,0.3662109375,0.06103515625,0.244140625 36 | 251,-0.1717529296875,-0.948486328125,0.3311767578125,0.3662109375,0.06103515625,0.244140625 37 | 251,-0.1717529296875,-0.948486328125,0.3311767578125,0.3662109375,0.06103515625,0.244140625 38 | 251,-0.1717529296875,-0.948486328125,0.3311767578125,0.3662109375,0.06103515625,0.244140625 39 | 251,-0.1702880859375,-0.94677734375,0.33447265625,0.244140625,0.06103515625,0.18310546875 40 | 251,-0.1702880859375,-0.94677734375,0.33447265625,0.244140625,0.06103515625,0.18310546875 41 | 251,-0.1707763671875,-0.9461669921875,0.3309326171875,0.48828125,0,0.244140625 42 | 251,-0.1734619140625,-0.944580078125,0.3321533203125,0.48828125,0.1220703125,0.244140625 43 | 251,-0.1734619140625,-0.944580078125,0.3321533203125,0.48828125,0.1220703125,0.244140625 44 | 251,-0.1734619140625,-0.944580078125,0.3321533203125,0.48828125,0.1220703125,0.244140625 45 | 251,-0.1734619140625,-0.944580078125,0.3321533203125,0.48828125,0.1220703125,0.244140625 46 | 251,-0.1734619140625,-0.944580078125,0.3321533203125,0.42724609375,0,0.18310546875 47 | 251,-0.168212890625,-0.9481201171875,0.333984375,0.42724609375,0,0.18310546875 48 | 251,-0.168212890625,-0.9481201171875,0.333984375,0.42724609375,0,0.18310546875 49 | 251,-0.168212890625,-0.9481201171875,0.333984375,0.42724609375,0,0.18310546875 50 | 251,-0.168212890625,-0.9481201171875,0.333984375,0.42724609375,0,0.18310546875 51 | 251,-0.168212890625,-0.9481201171875,0.333984375,0.30517578125,0.06103515625,0.1220703125 52 | 251,-0.169677734375,-0.94873046875,0.325439453125,0.30517578125,0.06103515625,0.1220703125 53 | 251,-0.169677734375,-0.94873046875,0.325439453125,0.30517578125,0.06103515625,0.1220703125 54 | 251,-0.169677734375,-0.94873046875,0.325439453125,0.30517578125,0.06103515625,0.1220703125 55 | 251,-0.169677734375,-0.94873046875,0.325439453125,0.30517578125,0.06103515625,0.1220703125 56 | 251,-0.169677734375,-0.94873046875,0.325439453125,0.48828125,0.1220703125,0.30517578125 57 | 251,-0.1732177734375,-0.946533203125,0.328857421875,0.48828125,0.1220703125,0.30517578125 58 | 251,-0.1732177734375,-0.946533203125,0.328857421875,0.48828125,0.1220703125,0.30517578125 59 | 251,-0.1732177734375,-0.946533203125,0.328857421875,0.48828125,0.1220703125,0.30517578125 60 | 251,-0.1732177734375,-0.946533203125,0.328857421875,0.48828125,0.1220703125,0.30517578125 61 | 251,-0.1732177734375,-0.946533203125,0.328857421875,0.42724609375,0.06103515625,0.244140625 62 | 251,-0.17138671875,-0.9478759765625,0.3336181640625,0.42724609375,0.06103515625,0.244140625 63 | 251,-0.17138671875,-0.9478759765625,0.3336181640625,0.42724609375,0.06103515625,0.244140625 64 | 251,-0.17138671875,-0.9478759765625,0.3336181640625,0.42724609375,0.06103515625,0.244140625 65 | 251,-0.17138671875,-0.9478759765625,0.3336181640625,0.42724609375,0.06103515625,0.244140625 66 | 251,-0.17138671875,-0.9478759765625,0.3336181640625,0.30517578125,0.06103515625,0.18310546875 67 | 251,-0.167236328125,-0.9503173828125,0.333251953125,0.30517578125,0.06103515625,0.18310546875 68 | 251,-0.167236328125,-0.9503173828125,0.333251953125,0.30517578125,0.06103515625,0.18310546875 69 | 251,-1.70068359375,-0.3507080078125,0.5953369140625,-87.58544921875,130.4931640625,397.88818359375 70 | 251,1.199951171875,3.1763916015625,0.878173828125,-54.5654296875,73.8525390625,316.0400390625 71 | 251,1.199951171875,3.1763916015625,0.878173828125,-54.5654296875,73.8525390625,316.0400390625 72 | 251,1.199951171875,3.1763916015625,0.878173828125,-54.5654296875,73.8525390625,316.0400390625 73 | 251,1.199951171875,3.1763916015625,0.878173828125,-54.5654296875,73.8525390625,316.0400390625 74 | 251,1.199951171875,3.1763916015625,0.878173828125,-54.5654296875,73.8525390625,316.0400390625 75 | 251,3.0721435546875,3.5623779296875,-1.1844482421875,41.50390625,8.30078125,71.96044921875 76 | 251,3.0721435546875,3.5623779296875,-1.1844482421875,41.50390625,8.30078125,71.96044921875 77 | 251,3.0721435546875,3.5623779296875,-1.1844482421875,41.50390625,8.30078125,71.96044921875 78 | 251,3.0721435546875,3.5623779296875,-1.1844482421875,41.50390625,8.30078125,71.96044921875 79 | 251,3.0721435546875,3.5623779296875,-1.1844482421875,41.50390625,8.30078125,71.96044921875 80 | 251,1.68212890625,3.4879150390625,-2.001953125,-31.3720703125,-18.5546875,-148.8037109375 81 | 251,1.68212890625,3.4879150390625,-2.001953125,-31.3720703125,-18.5546875,-148.8037109375 82 | 251,1.68212890625,3.4879150390625,-2.001953125,-31.3720703125,-18.5546875,-148.8037109375 83 | 251,1.68212890625,3.4879150390625,-2.001953125,-31.3720703125,-18.5546875,-148.8037109375 84 | 251,1.68212890625,3.4879150390625,-2.001953125,-31.3720703125,-18.5546875,-148.8037109375 85 | 251,1.822509765625,3.8311767578125,-1.0946044921875,-18.00537109375,-43.3349609375,-239.31884765625 86 | 251,1.822509765625,3.8311767578125,-1.0946044921875,-18.00537109375,-43.3349609375,-239.31884765625 87 | 251,1.822509765625,3.8311767578125,-1.0946044921875,-18.00537109375,-43.3349609375,-239.31884765625 88 | 251,1.822509765625,3.8311767578125,-1.0946044921875,-18.00537109375,-43.3349609375,-239.31884765625 89 | 251,1.822509765625,3.8311767578125,-1.0946044921875,-18.00537109375,-43.3349609375,-239.31884765625 90 | 251,1.5545654296875,3.3427734375,-1.087890625,-0.48828125,-85.75439453125,-340.14892578125 91 | 251,1.5545654296875,3.3427734375,-1.087890625,-0.48828125,-85.75439453125,-340.14892578125 92 | 251,1.5545654296875,3.3427734375,-1.087890625,-0.48828125,-85.75439453125,-340.14892578125 93 | 251,1.5545654296875,3.3427734375,-1.087890625,-0.48828125,-85.75439453125,-340.14892578125 94 | 251,1.5545654296875,3.3427734375,-1.087890625,-0.48828125,-85.75439453125,-340.14892578125 95 | 251,0.0013427734375,0.5113525390625,0.1947021484375,36.7431640625,11.41357421875,16.78466796875 96 | 251,0.0013427734375,0.5113525390625,0.1947021484375,36.7431640625,11.41357421875,16.78466796875 97 | 251,0.0013427734375,0.5113525390625,0.1947021484375,36.7431640625,11.41357421875,16.78466796875 98 | 251,0.7333984375,-0.4385986328125,0.440673828125,13.0615234375,3.60107421875,-7.9345703125 99 | 251,0.7333984375,-0.4385986328125,0.440673828125,13.0615234375,3.60107421875,-7.9345703125 100 | 251,0.7333984375,-0.4385986328125,0.440673828125,13.0615234375,3.60107421875,-7.9345703125 101 | 251,0.7333984375,-0.4385986328125,0.440673828125,13.0615234375,3.60107421875,-7.9345703125 102 | 251,0.7333984375,-0.4385986328125,0.440673828125,13.0615234375,3.60107421875,-7.9345703125 103 | 251,0.7550048828125,-1.5089111328125,0.1597900390625,10.19287109375,-3.662109375,-3.173828125 104 | 251,0.7550048828125,-1.5089111328125,0.1597900390625,10.19287109375,-3.662109375,-3.173828125 105 | 251,0.7550048828125,-1.5089111328125,0.1597900390625,10.19287109375,-3.662109375,-3.173828125 106 | 251,0.7550048828125,-1.5089111328125,0.1597900390625,10.19287109375,-3.662109375,-3.173828125 107 | 251,0.7550048828125,-1.5089111328125,0.1597900390625,10.19287109375,-3.662109375,-3.173828125 108 | 251,-0.547607421875,-0.938232421875,-0.0419921875,13.5498046875,12.63427734375,-1.64794921875 109 | 251,-0.547607421875,-0.938232421875,-0.0419921875,13.5498046875,12.63427734375,-1.64794921875 110 | 251,-0.547607421875,-0.938232421875,-0.0419921875,13.5498046875,12.63427734375,-1.64794921875 111 | 251,-0.547607421875,-0.938232421875,-0.0419921875,13.5498046875,12.63427734375,-1.64794921875 112 | 251,-0.547607421875,-0.938232421875,-0.0419921875,13.5498046875,12.63427734375,-1.64794921875 113 | 251,-0.6788330078125,-0.9530029296875,0.142578125,12.02392578125,-3.90625,-11.962890625 114 | 251,-0.6788330078125,-0.9530029296875,0.142578125,12.02392578125,-3.90625,-11.962890625 115 | 251,-0.6788330078125,-0.9530029296875,0.142578125,12.02392578125,-3.90625,-11.962890625 116 | 251,-0.6788330078125,-0.9530029296875,0.142578125,12.02392578125,-3.90625,-11.962890625 117 | 251,-0.6788330078125,-0.9530029296875,0.142578125,12.02392578125,-3.90625,-11.962890625 118 | 251,0.07958984375,-1.0654296875,0.4964599609375,10.7421875,11.53564453125,-17.02880859375 119 | 251,0.07958984375,-1.0654296875,0.4964599609375,10.7421875,11.53564453125,-17.02880859375 120 | 251,0.07958984375,-1.0654296875,0.4964599609375,10.7421875,11.53564453125,-17.02880859375 121 | 251,-0.181396484375,-1.6334228515625,2.434814453125,-75.25634765625,32.53173828125,150.57373046875 122 | 251,-0.010986328125,-0.98291015625,1.8348388671875,-56.57958984375,-0.06103515625,104.43115234375 123 | 251,-0.010986328125,-0.98291015625,1.8348388671875,-56.57958984375,-0.06103515625,104.43115234375 124 | 251,-0.010986328125,-0.98291015625,1.8348388671875,-56.57958984375,-0.06103515625,104.43115234375 125 | 251,-0.010986328125,-0.98291015625,1.8348388671875,-56.57958984375,-0.06103515625,104.43115234375 126 | 251,-0.010986328125,-0.98291015625,1.8348388671875,-56.57958984375,-0.06103515625,104.43115234375 127 | 251,-0.4288330078125,-0.5791015625,0.8153076171875,-22.8271484375,22.15576171875,78.2470703125 128 | 251,-0.4288330078125,-0.5791015625,0.8153076171875,-22.8271484375,22.15576171875,78.2470703125 129 | 251,-0.4288330078125,-0.5791015625,0.8153076171875,-22.8271484375,22.15576171875,78.2470703125 130 | 251,-0.4288330078125,-0.5791015625,0.8153076171875,-22.8271484375,22.15576171875,78.2470703125 131 | 251,-0.4288330078125,-0.5791015625,0.8153076171875,-22.8271484375,22.15576171875,78.2470703125 132 | 251,-0.7197265625,1.0384521484375,-0.0010986328125,-15.56396484375,27.77099609375,46.9970703125 133 | 251,-0.7197265625,1.0384521484375,-0.0010986328125,-15.56396484375,27.77099609375,46.9970703125 134 | 251,-0.7197265625,1.0384521484375,-0.0010986328125,-15.56396484375,27.77099609375,46.9970703125 135 | 251,-0.7197265625,1.0384521484375,-0.0010986328125,-15.56396484375,27.77099609375,46.9970703125 136 | 251,-0.7197265625,1.0384521484375,-0.0010986328125,-15.56396484375,27.77099609375,46.9970703125 137 | 251,-2.3349609375,2.1214599609375,0.9337158203125,11.8408203125,19.47021484375,54.26025390625 138 | 251,-2.3349609375,2.1214599609375,0.9337158203125,11.8408203125,19.47021484375,54.26025390625 139 | 251,-2.3349609375,2.1214599609375,0.9337158203125,11.8408203125,19.47021484375,54.26025390625 140 | 251,-2.3349609375,2.1214599609375,0.9337158203125,11.8408203125,19.47021484375,54.26025390625 141 | 251,-2.3349609375,2.1214599609375,0.9337158203125,11.8408203125,19.47021484375,54.26025390625 142 | 251,-3.73193359375,2.592041015625,0.8154296875,57.31201171875,29.78515625,164.306640625 143 | 251,-3.73193359375,2.592041015625,0.8154296875,57.31201171875,29.78515625,164.306640625 144 | 251,-3.73193359375,2.592041015625,0.8154296875,57.31201171875,29.78515625,164.306640625 145 | 251,-3.73193359375,2.592041015625,0.8154296875,57.31201171875,29.78515625,164.306640625 146 | 251,-3.73193359375,2.592041015625,0.8154296875,57.31201171875,29.78515625,164.306640625 147 | 251,-2.7869873046875,2.557373046875,-1.1533203125,118.408203125,49.01123046875,290.4052734375 148 | 251,-2.7869873046875,2.557373046875,-1.1533203125,118.408203125,49.01123046875,290.4052734375 149 | 251,2.657958984375,-0.6240234375,-0.017578125,-33.203125,76.84326171875,247.98583984375 150 | 251,3.32470703125,-0.257568359375,0.4693603515625,2.8076171875,36.80419921875,102.05078125 151 | 251,3.32470703125,-0.257568359375,0.4693603515625,2.8076171875,36.80419921875,102.05078125 152 | 251,3.32470703125,-0.257568359375,0.4693603515625,2.8076171875,36.80419921875,102.05078125 153 | 251,3.32470703125,-0.257568359375,0.4693603515625,2.8076171875,36.80419921875,102.05078125 154 | 251,3.32470703125,-0.257568359375,0.4693603515625,2.8076171875,36.80419921875,102.05078125 155 | 251,2.3348388671875,0.2972412109375,0.1082763671875,0.54931640625,16.357421875,-10.498046875 156 | 251,2.3348388671875,0.2972412109375,0.1082763671875,0.54931640625,16.357421875,-10.498046875 157 | 251,2.3348388671875,0.2972412109375,0.1082763671875,0.54931640625,16.357421875,-10.498046875 158 | 251,2.3348388671875,0.2972412109375,0.1082763671875,0.54931640625,16.357421875,-10.498046875 159 | 192,2.3348388671875,0.2972412109375,0.1082763671875,0.54931640625,16.357421875,-10.498046875 160 | 192,2.2645263671875,1.2216796875,-0.053955078125,-2.38037109375,-20.01953125,-94.970703125 161 | 192,2.2645263671875,1.2216796875,-0.053955078125,-2.38037109375,-20.01953125,-94.970703125 162 | 192,2.2645263671875,1.2216796875,-0.053955078125,-2.38037109375,-20.01953125,-94.970703125 163 | 192,2.2645263671875,1.2216796875,-0.053955078125,-2.38037109375,-20.01953125,-94.970703125 164 | 192,2.2645263671875,1.2216796875,-0.053955078125,-2.38037109375,-20.01953125,-94.970703125 165 | 192,2.7203369140625,1.4508056640625,0.378173828125,-6.103515625,-76.416015625,-203.61328125 166 | 192,2.7203369140625,1.4508056640625,0.378173828125,-6.103515625,-76.416015625,-203.61328125 167 | 192,2.7203369140625,1.4508056640625,0.378173828125,-6.103515625,-76.416015625,-203.61328125 168 | 192,2.7203369140625,1.4508056640625,0.378173828125,-6.103515625,-76.416015625,-203.61328125 169 | 44,2.7203369140625,1.4508056640625,0.378173828125,-6.103515625,-76.416015625,-203.61328125 170 | 44,2.0806884765625,0.4630126953125,0.7435302734375,20.08056640625,-106.3232421875,-290.52734375 171 | 44,2.0806884765625,0.4630126953125,0.7435302734375,20.08056640625,-106.3232421875,-290.52734375 172 | 44,2.0806884765625,0.4630126953125,0.7435302734375,20.08056640625,-106.3232421875,-290.52734375 173 | 44,2.0806884765625,0.4630126953125,0.7435302734375,20.08056640625,-106.3232421875,-290.52734375 174 | 44,2.0806884765625,0.4630126953125,0.7435302734375,26.67236328125,-111.87744140625,-337.0361328125 175 | 44,1.1461181640625,-0.3115234375,0.3719482421875,26.67236328125,-111.87744140625,-337.0361328125 176 | 44,-2.225341796875,-2.844970703125,0.9442138671875,-12.39013671875,-40.771484375,-159.912109375 177 | 44,-2.225341796875,-2.844970703125,0.9442138671875,-12.39013671875,-40.771484375,-159.912109375 178 | 44,-2.225341796875,-2.844970703125,0.9442138671875,-12.39013671875,-40.771484375,-159.912109375 179 | 44,-0.44140625,-1.197998046875,1.1614990234375,-48.9501953125,46.7529296875,-13.916015625 180 | 44,-0.44140625,-1.197998046875,1.1614990234375,-48.9501953125,46.7529296875,-13.916015625 181 | 44,-0.44140625,-1.197998046875,1.1614990234375,-48.9501953125,46.7529296875,-13.916015625 182 | 44,-0.44140625,-1.197998046875,1.1614990234375,-48.9501953125,46.7529296875,-13.916015625 183 | 44,-0.44140625,-1.197998046875,1.1614990234375,-48.9501953125,46.7529296875,-13.916015625 184 | 44,-0.5084228515625,-0.382080078125,0.2174072265625,45.83740234375,-18.24951171875,-16.90673828125 185 | 44,-0.5084228515625,-0.382080078125,0.2174072265625,45.83740234375,-18.24951171875,-16.90673828125 186 | 44,-0.5084228515625,-0.382080078125,0.2174072265625,45.83740234375,-18.24951171875,-16.90673828125 187 | 44,-0.5084228515625,-0.382080078125,0.2174072265625,45.83740234375,-18.24951171875,-16.90673828125 188 | 44,-0.5084228515625,-0.382080078125,0.2174072265625,45.83740234375,-18.24951171875,-16.90673828125 189 | 40,0.425537109375,-0.9805908203125,-0.7294921875,8.36181640625,24.96337890625,-26.2451171875 190 | 40,0.425537109375,-0.9805908203125,-0.7294921875,8.36181640625,24.96337890625,-26.2451171875 191 | 40,0.425537109375,-0.9805908203125,-0.7294921875,8.36181640625,24.96337890625,-26.2451171875 192 | 40,0.425537109375,-0.9805908203125,-0.7294921875,8.36181640625,24.96337890625,-26.2451171875 193 | 40,0.425537109375,-0.9805908203125,-0.7294921875,8.36181640625,24.96337890625,-26.2451171875 194 | 40,1.415771484375,-0.9488525390625,-0.15625,14.09912109375,-19.71435546875,-26.611328125 195 | 40,1.415771484375,-0.9488525390625,-0.15625,14.09912109375,-19.71435546875,-26.611328125 196 | 40,1.415771484375,-0.9488525390625,-0.15625,14.09912109375,-19.71435546875,-26.611328125 197 | 40,1.415771484375,-0.9488525390625,-0.15625,14.09912109375,-19.71435546875,-26.611328125 198 | 40,1.415771484375,-0.9488525390625,-0.15625,14.09912109375,-19.71435546875,-26.611328125 199 | 38,-0.3145751953125,-0.6556396484375,0.1182861328125,10.19287109375,-14.0380859375,-50.84228515625 200 | 38,-0.3145751953125,-0.6556396484375,0.1182861328125,10.19287109375,-14.0380859375,-50.84228515625 201 | 38,-0.3145751953125,-0.6556396484375,0.1182861328125,10.19287109375,-14.0380859375,-50.84228515625 202 | 38,-0.3145751953125,-0.6556396484375,0.1182861328125,10.19287109375,-14.0380859375,-50.84228515625 203 | 38,-0.2724609375,-1.268798828125,0.437255859375,-19.59228515625,-8.056640625,-46.7529296875 204 | 38,-0.2724609375,-1.268798828125,0.437255859375,-19.59228515625,-8.056640625,-46.7529296875 205 | 38,-0.2724609375,-1.268798828125,0.437255859375,-19.59228515625,-8.056640625,-46.7529296875 206 | 38,-0.2724609375,-1.268798828125,0.437255859375,-19.59228515625,-8.056640625,-46.7529296875 207 | 38,-0.2724609375,-1.268798828125,0.437255859375,-19.59228515625,-8.056640625,-46.7529296875 208 | 38,-0.07177734375,-1.1781005859375,0.38818359375,-14.09912109375,-15.31982421875,-46.9970703125 209 | 35,-0.07177734375,-1.1781005859375,0.38818359375,-14.09912109375,-15.31982421875,-46.9970703125 210 | 35,-0.07177734375,-1.1781005859375,0.38818359375,-14.09912109375,-15.31982421875,-46.9970703125 211 | 35,-0.07177734375,-1.1781005859375,0.38818359375,-14.09912109375,-15.31982421875,-46.9970703125 212 | 35,-0.07177734375,-1.1781005859375,0.38818359375,-14.09912109375,-15.31982421875,-46.9970703125 213 | 35,-0.1444091796875,-1.02734375,0.2337646484375,-9.27734375,-3.11279296875,-46.2646484375 214 | 35,-0.1444091796875,-1.02734375,0.2337646484375,-9.27734375,-3.11279296875,-46.2646484375 215 | 35,-0.1444091796875,-1.02734375,0.2337646484375,-9.27734375,-3.11279296875,-46.2646484375 216 | 35,-0.1444091796875,-1.02734375,0.2337646484375,-9.27734375,-3.11279296875,-46.2646484375 217 | 35,-0.1444091796875,-1.02734375,0.2337646484375,-9.27734375,-3.11279296875,-46.2646484375 218 | 35,-0.195556640625,-0.9954833984375,0.1109619140625,5.31005859375,-16.357421875,-37.90283203125 219 | 529,-0.195556640625,-0.9954833984375,0.1109619140625,5.31005859375,-16.357421875,-37.90283203125 220 | 529,-0.195556640625,-0.9954833984375,0.1109619140625,5.31005859375,-16.357421875,-37.90283203125 221 | 529,-0.195556640625,-0.9954833984375,0.1109619140625,5.31005859375,-16.357421875,-37.90283203125 222 | 529,-0.195556640625,-0.9954833984375,0.1109619140625,5.31005859375,-16.357421875,-37.90283203125 223 | 529,-0.1171875,-1.0311279296875,0.2606201171875,14.22119140625,-17.08984375,-36.1328125 224 | 529,-0.1171875,-1.0311279296875,0.2606201171875,14.22119140625,-17.08984375,-36.1328125 225 | 529,-0.1171875,-1.0311279296875,0.2606201171875,14.22119140625,-17.08984375,-36.1328125 226 | 529,-0.1171875,-1.0311279296875,0.2606201171875,14.22119140625,-17.08984375,-36.1328125 227 | 529,-0.1171875,-1.0311279296875,0.2606201171875,14.22119140625,-17.08984375,-36.1328125 228 | 529,-0.1221923828125,-1.0538330078125,0.3046875,16.357421875,-18.61572265625,-37.29248046875 229 | 166,-0.1221923828125,-1.0538330078125,0.3046875,16.357421875,-18.61572265625,-37.29248046875 230 | 166,-0.0167236328125,-0.94140625,0.359619140625,-0.67138671875,-16.845703125,-54.87060546875 231 | 166,-0.0167236328125,-0.94140625,0.359619140625,-0.67138671875,-16.845703125,-54.87060546875 232 | 166,-0.0167236328125,-0.94140625,0.359619140625,-0.67138671875,-16.845703125,-54.87060546875 233 | 166,-0.1259765625,-1.010009765625,0.380859375,-1.3427734375,-20.81298828125,-56.396484375 234 | 166,-0.1259765625,-1.010009765625,0.380859375,-1.3427734375,-20.81298828125,-56.396484375 235 | 166,-0.1259765625,-1.010009765625,0.380859375,-1.3427734375,-20.81298828125,-56.396484375 236 | 166,-0.1259765625,-1.010009765625,0.380859375,-1.3427734375,-20.81298828125,-56.396484375 237 | 166,-0.1259765625,-1.010009765625,0.380859375,-1.3427734375,-20.81298828125,-56.396484375 238 | 166,-0.05859375,-0.74072265625,0.357177734375,-5.859375,-19.8974609375,-56.0302734375 239 | 294,-0.05859375,-0.74072265625,0.357177734375,-5.859375,-19.8974609375,-56.0302734375 240 | 294,-0.05859375,-0.74072265625,0.357177734375,-5.859375,-19.8974609375,-56.0302734375 241 | 294,-0.05859375,-0.74072265625,0.357177734375,-5.859375,-19.8974609375,-56.0302734375 242 | 294,-0.05859375,-0.74072265625,0.357177734375,-5.859375,-19.8974609375,-56.0302734375 243 | 294,0.0198974609375,-0.904052734375,0.2867431640625,-13.3056640625,-10.92529296875,-54.26025390625 244 | 294,0.0198974609375,-0.904052734375,0.2867431640625,-13.3056640625,-10.92529296875,-54.26025390625 245 | 294,0.0198974609375,-0.904052734375,0.2867431640625,-13.3056640625,-10.92529296875,-54.26025390625 246 | 294,0.0198974609375,-0.904052734375,0.2867431640625,-13.3056640625,-10.92529296875,-54.26025390625 247 | 294,0.0198974609375,-0.904052734375,0.2867431640625,-13.3056640625,-10.92529296875,-54.26025390625 248 | 294,0.08154296875,-1.11572265625,0.32177734375,-3.41796875,-13.00048828125,-45.83740234375 249 | 352,0.08154296875,-1.11572265625,0.32177734375,-3.41796875,-13.00048828125,-45.83740234375 250 | 352,0.08154296875,-1.11572265625,0.32177734375,-3.41796875,-13.00048828125,-45.83740234375 251 | 352,0.08154296875,-1.11572265625,0.32177734375,-3.41796875,-13.00048828125,-45.83740234375 252 | 352,0.08154296875,-1.11572265625,0.32177734375,-3.41796875,-13.00048828125,-45.83740234375 253 | 352,-0.0279541015625,-0.858642578125,0.258056640625,-0.91552734375,-5.126953125,-39.48974609375 254 | 352,-0.0279541015625,-0.858642578125,0.258056640625,-0.91552734375,-5.126953125,-39.48974609375 255 | 352,-0.0279541015625,-0.858642578125,0.258056640625,-0.91552734375,-5.126953125,-39.48974609375 256 | 352,-0.0279541015625,-0.858642578125,0.258056640625,-0.91552734375,-5.126953125,-39.48974609375 257 | 352,-0.0279541015625,-0.858642578125,0.258056640625,-0.91552734375,-5.126953125,-39.48974609375 258 | 352,0.01123046875,-1.078125,0.279052734375,16.845703125,-10.55908203125,-42.6025390625 259 | 177,0.01123046875,-1.078125,0.279052734375,16.845703125,-10.55908203125,-42.6025390625 260 | 177,0.01123046875,-1.078125,0.279052734375,16.845703125,-10.55908203125,-42.6025390625 261 | 177,0.01123046875,-1.078125,0.279052734375,16.845703125,-10.55908203125,-42.6025390625 262 | 177,0.0093994140625,-1.0220947265625,0.270751953125,23.92578125,-13.427734375,-40.283203125 263 | 177,0.0093994140625,-1.0220947265625,0.270751953125,23.92578125,-13.427734375,-40.283203125 264 | 177,0.0093994140625,-1.0220947265625,0.270751953125,23.92578125,-13.427734375,-40.283203125 265 | 177,0.0093994140625,-1.0220947265625,0.270751953125,23.92578125,-13.427734375,-40.283203125 266 | 177,0.0093994140625,-1.0220947265625,0.270751953125,23.92578125,-13.427734375,-40.283203125 267 | 177,-0.0360107421875,-0.8685302734375,0.330078125,21.42333984375,-11.77978515625,-41.93115234375 268 | 177,-0.0360107421875,-0.8685302734375,0.330078125,21.42333984375,-11.77978515625,-41.93115234375 269 | 36,-0.0360107421875,-0.8685302734375,0.330078125,21.42333984375,-11.77978515625,-41.93115234375 270 | 36,-0.0360107421875,-0.8685302734375,0.330078125,21.42333984375,-11.77978515625,-41.93115234375 271 | 36,-0.0360107421875,-0.8685302734375,0.330078125,21.42333984375,-11.77978515625,-41.93115234375 272 | 36,0.08544921875,-0.9215087890625,0.3941650390625,16.41845703125,-13.12255859375,-42.29736328125 273 | 36,0.08544921875,-0.9215087890625,0.3941650390625,16.41845703125,-13.12255859375,-42.29736328125 274 | 36,0.08544921875,-0.9215087890625,0.3941650390625,16.41845703125,-13.12255859375,-42.29736328125 275 | 36,0.08544921875,-0.9215087890625,0.3941650390625,16.41845703125,-13.12255859375,-42.29736328125 276 | 36,0.08544921875,-0.9215087890625,0.3941650390625,16.41845703125,-13.12255859375,-42.29736328125 277 | 36,0.0380859375,-0.806396484375,0.3770751953125,7.9345703125,-12.26806640625,-42.236328125 278 | 36,0.0380859375,-0.806396484375,0.3770751953125,7.9345703125,-12.26806640625,-42.236328125 279 | 32,0.0380859375,-0.806396484375,0.3770751953125,7.9345703125,-12.26806640625,-42.236328125 280 | 32,0.0380859375,-0.806396484375,0.3770751953125,7.9345703125,-12.26806640625,-42.236328125 281 | 32,0.0380859375,-0.806396484375,0.3770751953125,7.9345703125,-12.26806640625,-42.236328125 282 | 32,0.102783203125,-0.8896484375,0.3795166015625,4.150390625,-9.70458984375,-41.6259765625 283 | 32,0.102783203125,-0.8896484375,0.3795166015625,4.150390625,-9.70458984375,-41.6259765625 284 | 32,0.138427734375,-0.570068359375,0.5374755859375,-27.4658203125,-33.447265625,-56.09130859375 285 | 32,0.1260986328125,-0.435791015625,0.0960693359375,-24.84130859375,-25.0244140625,-58.9599609375 286 | 32,0.1260986328125,-0.435791015625,0.0960693359375,-24.84130859375,-25.0244140625,-58.9599609375 287 | 32,0.1260986328125,-0.435791015625,0.0960693359375,-24.84130859375,-25.0244140625,-58.9599609375 288 | 32,0.1260986328125,-0.435791015625,0.0960693359375,-24.84130859375,-25.0244140625,-58.9599609375 289 | 32,0.1260986328125,-0.435791015625,0.0960693359375,-24.84130859375,-25.0244140625,-58.9599609375 290 | 32,0.1036376953125,-1.5997314453125,0.9993896484375,-15.7470703125,-25.20751953125,-52.55126953125 291 | 32,0.1036376953125,-1.5997314453125,0.9993896484375,-15.7470703125,-25.20751953125,-52.55126953125 292 | 32,0.1036376953125,-1.5997314453125,0.9993896484375,-15.7470703125,-25.20751953125,-52.55126953125 293 | 32,0.1036376953125,-1.5997314453125,0.9993896484375,-15.7470703125,-25.20751953125,-52.55126953125 294 | 32,0.1036376953125,-1.5997314453125,0.9993896484375,-15.7470703125,-25.20751953125,-52.55126953125 295 | 32,1.19140625,-3.2691650390625,-0.0911865234375,-14.09912109375,-37.9638671875,-6.65283203125 296 | 32,1.19140625,-3.2691650390625,-0.0911865234375,-14.09912109375,-37.9638671875,-6.65283203125 297 | 32,1.19140625,-3.2691650390625,-0.0911865234375,-14.09912109375,-37.9638671875,-6.65283203125 298 | 32,1.19140625,-3.2691650390625,-0.0911865234375,-14.09912109375,-37.9638671875,-6.65283203125 299 | 32,1.19140625,-3.2691650390625,-0.0911865234375,-14.09912109375,-37.9638671875,-6.65283203125 300 | 32,1.1788330078125,-3.281982421875,0.8671875,-93.07861328125,12.8173828125,88.8671875 301 | 32,1.1788330078125,-3.281982421875,0.8671875,-93.07861328125,12.8173828125,88.8671875 302 | 32,1.1788330078125,-3.281982421875,0.8671875,-93.07861328125,12.8173828125,88.8671875 303 | 32,1.1788330078125,-3.281982421875,0.8671875,-93.07861328125,12.8173828125,88.8671875 304 | 32,1.1788330078125,-3.281982421875,0.8671875,-93.07861328125,12.8173828125,88.8671875 305 | 32,0.22412109375,-2.820556640625,2.84765625,-41.80908203125,71.2890625,121.27685546875 306 | 32,0.22412109375,-2.820556640625,2.84765625,-41.80908203125,71.2890625,121.27685546875 307 | 32,0.22412109375,-2.820556640625,2.84765625,-41.80908203125,71.2890625,121.27685546875 308 | 32,0.22412109375,-2.820556640625,2.84765625,-41.80908203125,71.2890625,121.27685546875 309 | 29,0.22412109375,-2.820556640625,2.84765625,-41.80908203125,71.2890625,121.27685546875 310 | 29,0.67138671875,-1.9132080078125,1.94775390625,-34.48486328125,33.203125,114.44091796875 311 | 29,-3.955810546875,1.5069580078125,1.330810546875,39.24560546875,49.31640625,147.76611328125 312 | 29,-3.955810546875,1.5069580078125,1.330810546875,39.24560546875,49.31640625,147.76611328125 313 | 29,-3.53564453125,1.5958251953125,-0.2752685546875,86.24267578125,84.53369140625,319.091796875 314 | 29,-3.53564453125,1.5958251953125,-0.2752685546875,86.24267578125,84.53369140625,319.091796875 315 | 29,-3.53564453125,1.5958251953125,-0.2752685546875,86.24267578125,84.53369140625,319.091796875 316 | 29,-3.53564453125,1.5958251953125,-0.2752685546875,86.24267578125,84.53369140625,319.091796875 317 | 29,-3.53564453125,1.5958251953125,-0.2752685546875,46.08154296875,132.32421875,445.068359375 318 | 29,-2.414306640625,0.63134765625,-0.959228515625,46.08154296875,132.32421875,445.068359375 319 | 30,-2.414306640625,0.63134765625,-0.959228515625,46.08154296875,132.32421875,445.068359375 320 | 30,-2.414306640625,0.63134765625,-0.959228515625,46.08154296875,132.32421875,445.068359375 321 | 30,-2.414306640625,0.63134765625,-0.959228515625,46.08154296875,132.32421875,445.068359375 322 | 30,-2.414306640625,0.63134765625,-0.959228515625,20.81298828125,157.1044921875,516.845703125 323 | 30,-1.26123046875,0.5242919921875,-0.853515625,20.81298828125,157.1044921875,516.845703125 324 | 30,-1.26123046875,0.5242919921875,-0.853515625,20.81298828125,157.1044921875,516.845703125 325 | 30,-1.26123046875,0.5242919921875,-0.853515625,20.81298828125,157.1044921875,516.845703125 326 | 30,-1.26123046875,0.5242919921875,-0.853515625,20.81298828125,157.1044921875,516.845703125 327 | 30,-0.3770751953125,0.81103515625,-0.5181884765625,15.68603515625,174.13330078125,568.359375 328 | 30,-0.3770751953125,0.81103515625,-0.5181884765625,15.68603515625,174.13330078125,568.359375 329 | 29,-0.3770751953125,0.81103515625,-0.5181884765625,15.68603515625,174.13330078125,568.359375 330 | 29,-0.3770751953125,0.81103515625,-0.5181884765625,15.68603515625,174.13330078125,568.359375 331 | 29,-0.3770751953125,0.81103515625,-0.5181884765625,15.68603515625,174.13330078125,568.359375 332 | 29,0.5367431640625,0.364990234375,-0.44677734375,-2.9296875,170.95947265625,577.81982421875 333 | 29,0.5367431640625,0.364990234375,-0.44677734375,-2.9296875,170.95947265625,577.81982421875 334 | 29,0.5367431640625,0.364990234375,-0.44677734375,-2.9296875,170.95947265625,577.81982421875 335 | 29,0.5367431640625,0.364990234375,-0.44677734375,-2.9296875,170.95947265625,577.81982421875 336 | 29,0.5367431640625,0.364990234375,-0.44677734375,-2.9296875,170.95947265625,577.81982421875 337 | 29,3.2957763671875,-0.5400390625,0.0924072265625,-24.23095703125,-65.61279296875,-273.193359375 338 | 29,3.2957763671875,-0.5400390625,0.0924072265625,-24.23095703125,-65.61279296875,-273.193359375 339 | 28,3.2957763671875,-0.5400390625,0.0924072265625,-24.23095703125,-65.61279296875,-273.193359375 340 | 28,3.2957763671875,-0.5400390625,0.0924072265625,-17.27294921875,-85.44921875,-348.32763671875 341 | 28,1.79345703125,-1.203857421875,0.436767578125,-17.27294921875,-85.44921875,-348.32763671875 342 | 28,1.79345703125,-1.203857421875,0.436767578125,-17.27294921875,-85.44921875,-348.32763671875 343 | 28,1.79345703125,-1.203857421875,0.436767578125,-17.27294921875,-85.44921875,-348.32763671875 344 | 28,1.79345703125,-1.203857421875,0.436767578125,-17.27294921875,-85.44921875,-348.32763671875 345 | 28,1.79345703125,-1.203857421875,0.436767578125,-13.48876953125,-97.83935546875,-374.57275390625 346 | 28,0.50830078125,-1.2197265625,0.6163330078125,-13.48876953125,-97.83935546875,-374.57275390625 347 | 28,0.50830078125,-1.2197265625,0.6163330078125,-13.48876953125,-97.83935546875,-374.57275390625 348 | 28,0.50830078125,-1.2197265625,0.6163330078125,-13.48876953125,-97.83935546875,-374.57275390625 349 | 28,0.50830078125,-1.2197265625,0.6163330078125,-13.48876953125,-97.83935546875,-374.57275390625 350 | 28,0.50830078125,-1.2197265625,0.6163330078125,-5.859375,-109.375,-380.126953125 351 | 28,-0.120361328125,-0.9625244140625,0.7357177734375,-5.859375,-109.375,-380.126953125 352 | 28,-0.120361328125,-0.9625244140625,0.7357177734375,-5.859375,-109.375,-380.126953125 353 | 28,-0.120361328125,-0.9625244140625,0.7357177734375,-5.859375,-109.375,-380.126953125 354 | 28,-0.120361328125,-0.9625244140625,0.7357177734375,-5.859375,-109.375,-380.126953125 355 | 28,-0.120361328125,-0.9625244140625,0.7357177734375,2.8076171875,-111.083984375,-375.42724609375 356 | 28,-0.6531982421875,-1.4090576171875,0.8975830078125,2.8076171875,-111.083984375,-375.42724609375 357 | 28,-0.6531982421875,-1.4090576171875,0.8975830078125,2.8076171875,-111.083984375,-375.42724609375 358 | 28,-0.6531982421875,-1.4090576171875,0.8975830078125,2.8076171875,-111.083984375,-375.42724609375 359 | 27,-0.6531982421875,-1.4090576171875,0.8975830078125,2.8076171875,-111.083984375,-375.42724609375 360 | 27,-1.839599609375,-2.4306640625,1.093505859375,11.29150390625,-95.0927734375,-325.01220703125 361 | 27,-1.839599609375,-2.4306640625,1.093505859375,11.29150390625,-95.0927734375,-325.01220703125 362 | 27,-1.839599609375,-2.4306640625,1.093505859375,11.29150390625,-95.0927734375,-325.01220703125 363 | 27,-1.839599609375,-2.4306640625,1.093505859375,11.29150390625,-95.0927734375,-325.01220703125 364 | 27,-1.839599609375,-2.4306640625,1.093505859375,11.29150390625,-95.0927734375,-325.01220703125 365 | 27,0.77294921875,-1.35205078125,-0.4632568359375,-26.123046875,-25.45166015625,-13.85498046875 366 | 27,0.77294921875,-1.35205078125,-0.4632568359375,-26.123046875,-25.45166015625,-13.85498046875 367 | 27,0.77294921875,-1.35205078125,-0.4632568359375,-26.123046875,-25.45166015625,-13.85498046875 368 | 27,-0.17138671875,-0.997314453125,0.0980224609375,-1.40380859375,-5.67626953125,-20.8740234375 369 | 26,-0.17138671875,-0.997314453125,0.0980224609375,-1.40380859375,-5.67626953125,-20.8740234375 370 | 26,-0.17138671875,-0.997314453125,0.0980224609375,-1.40380859375,-5.67626953125,-20.8740234375 371 | 26,-0.17138671875,-0.997314453125,0.0980224609375,-1.40380859375,-5.67626953125,-20.8740234375 372 | 26,-0.17138671875,-0.997314453125,0.0980224609375,-1.40380859375,-5.67626953125,-20.8740234375 373 | 26,-0.0084228515625,-0.8988037109375,0.35791015625,27.099609375,14.22119140625,-15.56396484375 374 | 26,-0.0084228515625,-0.8988037109375,0.35791015625,27.099609375,14.22119140625,-15.56396484375 375 | 26,-0.0084228515625,-0.8988037109375,0.35791015625,27.099609375,14.22119140625,-15.56396484375 376 | 26,-0.0084228515625,-0.8988037109375,0.35791015625,27.099609375,14.22119140625,-15.56396484375 377 | 26,-0.0084228515625,-0.8988037109375,0.35791015625,27.099609375,14.22119140625,-15.56396484375 378 | 26,-0.333984375,-0.8519287109375,0.4107666015625,11.77978515625,8.72802734375,-18.5546875 379 | 116,-0.333984375,-0.8519287109375,0.4107666015625,11.77978515625,8.72802734375,-18.5546875 380 | 116,-0.333984375,-0.8519287109375,0.4107666015625,11.77978515625,8.72802734375,-18.5546875 381 | 116,-0.333984375,-0.8519287109375,0.4107666015625,11.77978515625,8.72802734375,-18.5546875 382 | 116,-0.333984375,-0.8519287109375,0.4107666015625,11.77978515625,8.72802734375,-18.5546875 383 | 116,-0.272216796875,-0.6307373046875,0.1947021484375,0.1220703125,-7.9345703125,-24.2919921875 384 | 116,-0.272216796875,-0.6307373046875,0.1947021484375,0.1220703125,-7.9345703125,-24.2919921875 385 | 116,-0.272216796875,-0.6307373046875,0.1947021484375,0.1220703125,-7.9345703125,-24.2919921875 386 | 116,-0.272216796875,-0.6307373046875,0.1947021484375,0.1220703125,-7.9345703125,-24.2919921875 387 | 116,-0.272216796875,-0.6307373046875,0.1947021484375,0.1220703125,-7.9345703125,-24.2919921875 388 | 116,-0.1019287109375,-0.80322265625,0.2779541015625,-10.1318359375,6.04248046875,-26.0009765625 389 | 229,-0.1019287109375,-0.80322265625,0.2779541015625,-10.1318359375,6.04248046875,-26.0009765625 390 | 229,-0.1019287109375,-0.80322265625,0.2779541015625,-10.1318359375,6.04248046875,-26.0009765625 391 | 229,-0.1639404296875,-1.02294921875,0.2647705078125,12.451171875,-16.7236328125,-33.75244140625 392 | 229,-0.1639404296875,-1.02294921875,0.2647705078125,12.451171875,-16.7236328125,-33.75244140625 393 | 229,-0.1639404296875,-1.02294921875,0.2647705078125,12.451171875,-16.7236328125,-33.75244140625 394 | 229,-0.1639404296875,-1.02294921875,0.2647705078125,12.451171875,-16.7236328125,-33.75244140625 395 | 229,-0.1639404296875,-1.02294921875,0.2647705078125,12.451171875,-16.7236328125,-33.75244140625 396 | 229,-0.179931640625,-0.9755859375,0.2196044921875,15.380859375,-24.59716796875,-30.94482421875 397 | 229,-0.179931640625,-0.9755859375,0.2196044921875,15.380859375,-24.59716796875,-30.94482421875 398 | 229,-0.179931640625,-0.9755859375,0.2196044921875,15.380859375,-24.59716796875,-30.94482421875 399 | 289,-0.179931640625,-0.9755859375,0.2196044921875,15.380859375,-24.59716796875,-30.94482421875 400 | 289,-0.179931640625,-0.9755859375,0.2196044921875,15.380859375,-24.59716796875,-30.94482421875 401 | 289,-0.144287109375,-1.0142822265625,0.25390625,15.68603515625,-22.94921875,-32.28759765625 402 | 289,-0.144287109375,-1.0142822265625,0.25390625,15.68603515625,-22.94921875,-32.28759765625 403 | 289,-0.144287109375,-1.0142822265625,0.25390625,15.68603515625,-22.94921875,-32.28759765625 404 | 289,-0.144287109375,-1.0142822265625,0.25390625,15.68603515625,-22.94921875,-32.28759765625 405 | 289,-0.144287109375,-1.0142822265625,0.25390625,15.68603515625,-22.94921875,-32.28759765625 406 | 289,-0.169677734375,-0.8348388671875,0.2984619140625,16.41845703125,-26.85546875,-35.21728515625 407 | 289,-0.169677734375,-0.8348388671875,0.2984619140625,16.41845703125,-26.85546875,-35.21728515625 408 | 289,-0.169677734375,-0.8348388671875,0.2984619140625,16.41845703125,-26.85546875,-35.21728515625 409 | 346,-0.169677734375,-0.8348388671875,0.2984619140625,16.41845703125,-26.85546875,-35.21728515625 410 | 346,-0.169677734375,-0.8348388671875,0.2984619140625,16.41845703125,-26.85546875,-35.21728515625 411 | 346,-0.117431640625,-0.8189697265625,0.34130859375,7.4462890625,-15.19775390625,-41.3818359375 412 | 346,-0.117431640625,-0.8189697265625,0.34130859375,7.4462890625,-15.19775390625,-41.3818359375 413 | 346,-0.117431640625,-0.8189697265625,0.34130859375,7.4462890625,-15.19775390625,-41.3818359375 414 | 346,-0.117431640625,-0.8189697265625,0.34130859375,7.4462890625,-15.19775390625,-41.3818359375 415 | 346,-0.117431640625,-0.8189697265625,0.34130859375,7.4462890625,-15.19775390625,-41.3818359375 416 | 346,-0.1044921875,-0.9295654296875,0.335693359375,2.13623046875,-11.65771484375,-42.54150390625 417 | 346,-0.036865234375,-0.853515625,0.3231201171875,-2.99072265625,-1.89208984375,-29.35791015625 418 | 346,-0.036865234375,-0.853515625,0.3231201171875,-2.99072265625,-1.89208984375,-29.35791015625 419 | 320,-0.036865234375,-0.853515625,0.3231201171875,-2.99072265625,-1.89208984375,-29.35791015625 420 | 320,-0.0628662109375,-0.9365234375,0.2762451171875,-0.6103515625,-3.60107421875,-27.9541015625 421 | 320,-0.0628662109375,-0.9365234375,0.2762451171875,-0.6103515625,-3.60107421875,-27.9541015625 422 | 320,-0.0628662109375,-0.9365234375,0.2762451171875,-0.6103515625,-3.60107421875,-27.9541015625 423 | 320,-0.0628662109375,-0.9365234375,0.2762451171875,-0.6103515625,-3.60107421875,-27.9541015625 424 | 320,-0.0628662109375,-0.9365234375,0.2762451171875,-0.6103515625,-3.60107421875,-27.9541015625 425 | 320,-0.0694580078125,-1.078125,0.245849609375,4.21142578125,3.41796875,-30.09033203125 426 | 320,-0.0694580078125,-1.078125,0.245849609375,4.21142578125,3.41796875,-30.09033203125 427 | 320,-0.0694580078125,-1.078125,0.245849609375,4.21142578125,3.41796875,-30.09033203125 428 | 320,-0.0694580078125,-1.078125,0.245849609375,4.21142578125,3.41796875,-30.09033203125 429 | 469,-0.0694580078125,-1.078125,0.245849609375,4.21142578125,3.41796875,-30.09033203125 430 | 469,-0.1075439453125,-1.1075439453125,0.28466796875,4.69970703125,-0.67138671875,-35.33935546875 431 | 469,-0.1075439453125,-1.1075439453125,0.28466796875,4.69970703125,-0.67138671875,-35.33935546875 432 | 469,-0.1075439453125,-1.1075439453125,0.28466796875,4.69970703125,-0.67138671875,-35.33935546875 433 | 469,-0.1075439453125,-1.1075439453125,0.28466796875,4.69970703125,-0.67138671875,-35.33935546875 434 | 469,-0.1075439453125,-1.1075439453125,0.28466796875,4.69970703125,-0.67138671875,-35.33935546875 435 | 469,-0.1005859375,-1.1229248046875,0.2513427734375,9.1552734375,-8.60595703125,-40.4052734375 436 | 469,-0.1005859375,-1.1229248046875,0.2513427734375,9.1552734375,-8.60595703125,-40.4052734375 437 | 469,-0.1005859375,-1.1229248046875,0.2513427734375,9.1552734375,-8.60595703125,-40.4052734375 438 | 469,-0.1005859375,-1.1229248046875,0.2513427734375,9.1552734375,-8.60595703125,-40.4052734375 439 | 505,-0.1005859375,-1.1229248046875,0.2513427734375,9.1552734375,-8.60595703125,-40.4052734375 440 | 505,-0.048095703125,-1.0992431640625,0.23046875,18.24951171875,-10.19287109375,-42.8466796875 441 | 505,-0.048095703125,-1.0992431640625,0.23046875,18.24951171875,-10.19287109375,-42.8466796875 442 | 505,-0.048095703125,-1.0992431640625,0.23046875,18.24951171875,-10.19287109375,-42.8466796875 443 | 505,0.0938720703125,-0.928955078125,0.451416015625,0.48828125,-6.7138671875,-44.25048828125 444 | 505,0.0697021484375,-0.906494140625,0.2242431640625,0.54931640625,3.35693359375,-41.93115234375 445 | 505,0.0697021484375,-0.906494140625,0.2242431640625,0.54931640625,3.35693359375,-41.93115234375 446 | 505,0.0697021484375,-0.906494140625,0.2242431640625,0.54931640625,3.35693359375,-41.93115234375 447 | 505,0.0697021484375,-0.906494140625,0.2242431640625,0.54931640625,3.35693359375,-41.93115234375 448 | 505,0.0697021484375,-0.906494140625,0.2242431640625,0.54931640625,3.35693359375,-41.93115234375 449 | 488,-0.119873046875,-1.139404296875,0.155517578125,22.64404296875,-8.6669921875,-32.2265625 450 | 488,-0.119873046875,-1.139404296875,0.155517578125,22.64404296875,-8.6669921875,-32.2265625 451 | 488,-0.119873046875,-1.139404296875,0.155517578125,22.64404296875,-8.6669921875,-32.2265625 452 | 488,-0.119873046875,-1.139404296875,0.155517578125,22.64404296875,-8.6669921875,-32.2265625 453 | 488,-0.119873046875,-1.139404296875,0.155517578125,22.64404296875,-8.6669921875,-32.2265625 454 | 488,0.03369140625,-1.046630859375,0.2861328125,22.52197265625,8.48388671875,-38.02490234375 455 | 488,0.03369140625,-1.046630859375,0.2861328125,22.52197265625,8.48388671875,-38.02490234375 456 | 488,0.03369140625,-1.046630859375,0.2861328125,22.52197265625,8.48388671875,-38.02490234375 457 | 488,0.03369140625,-1.046630859375,0.2861328125,22.52197265625,8.48388671875,-38.02490234375 458 | 488,0.03369140625,-1.046630859375,0.2861328125,22.52197265625,8.48388671875,-38.02490234375 459 | 448,0.067138671875,-0.9925537109375,0.3321533203125,24.59716796875,6.65283203125,-28.62548828125 460 | 448,0.067138671875,-0.9925537109375,0.3321533203125,24.59716796875,6.65283203125,-28.62548828125 461 | 448,0.067138671875,-0.9925537109375,0.3321533203125,24.59716796875,6.65283203125,-28.62548828125 462 | 448,0.067138671875,-0.9925537109375,0.3321533203125,24.59716796875,6.65283203125,-28.62548828125 463 | 448,0.067138671875,-0.9925537109375,0.3321533203125,24.59716796875,6.65283203125,-28.62548828125 464 | 448,-0.1129150390625,-1.258544921875,0.3350830078125,26.06201171875,-35.82763671875,-27.7099609375 465 | 448,-0.1129150390625,-1.258544921875,0.3350830078125,26.06201171875,-35.82763671875,-27.7099609375 466 | 448,-0.1129150390625,-1.258544921875,0.3350830078125,26.06201171875,-35.82763671875,-27.7099609375 467 | 448,-0.1129150390625,-1.258544921875,0.3350830078125,26.06201171875,-35.82763671875,-27.7099609375 468 | 448,-0.1129150390625,-1.258544921875,0.3350830078125,26.06201171875,-35.82763671875,-27.7099609375 469 | 397,0.3089599609375,-1.010009765625,-0.7977294921875,-3.23486328125,-28.076171875,-32.71484375 470 | 397,0.3089599609375,-1.010009765625,-0.7977294921875,-3.23486328125,-28.076171875,-32.71484375 471 | 397,-0.3377685546875,-3.0025634765625,2.64697265625,-41.259765625,27.34375,135.92529296875 472 | 397,0.538330078125,-2.095947265625,1.287353515625,-41.259765625,27.34375,135.92529296875 473 | 397,0.538330078125,-2.095947265625,1.287353515625,-41.259765625,27.34375,135.92529296875 474 | 397,0.538330078125,-2.095947265625,1.287353515625,-41.259765625,27.34375,135.92529296875 475 | 397,0.538330078125,-2.095947265625,1.287353515625,-41.259765625,27.34375,135.92529296875 476 | 397,0.538330078125,-2.095947265625,1.287353515625,-41.259765625,27.34375,135.92529296875 477 | 397,0.6976318359375,-1.2784423828125,0.689208984375,-28.74755859375,10.55908203125,91.36962890625 478 | 397,0.6976318359375,-1.2784423828125,0.689208984375,-28.74755859375,10.55908203125,91.36962890625 479 | 325,0.6976318359375,-1.2784423828125,0.689208984375,-28.74755859375,10.55908203125,91.36962890625 480 | 325,0.6976318359375,-1.2784423828125,0.689208984375,-28.74755859375,10.55908203125,91.36962890625 481 | 325,0.6976318359375,-1.2784423828125,0.689208984375,-28.74755859375,10.55908203125,91.36962890625 482 | 325,0.2337646484375,-1.085205078125,0.1241455078125,-26.79443359375,29.47998046875,53.40576171875 483 | 325,0.2337646484375,-1.085205078125,0.1241455078125,-26.79443359375,29.47998046875,53.40576171875 484 | 325,0.2337646484375,-1.085205078125,0.1241455078125,-26.79443359375,29.47998046875,53.40576171875 485 | 325,0.2337646484375,-1.085205078125,0.1241455078125,-26.79443359375,29.47998046875,53.40576171875 486 | 325,0.2337646484375,-1.085205078125,0.1241455078125,-26.79443359375,29.47998046875,53.40576171875 487 | 325,-0.4033203125,-0.0843505859375,0.2147216796875,-26.42822265625,43.51806640625,16.54052734375 488 | 325,-0.4033203125,-0.0843505859375,0.2147216796875,-26.42822265625,43.51806640625,16.54052734375 489 | 294,-0.4033203125,-0.0843505859375,0.2147216796875,-26.42822265625,43.51806640625,16.54052734375 490 | 294,-0.4033203125,-0.0843505859375,0.2147216796875,-26.42822265625,43.51806640625,16.54052734375 491 | 294,-0.4033203125,-0.0843505859375,0.2147216796875,-26.42822265625,43.51806640625,16.54052734375 492 | 294,-2.353515625,1.1363525390625,1.0611572265625,-21.05712890625,26.7333984375,11.962890625 493 | 294,-2.353515625,1.1363525390625,1.0611572265625,-21.05712890625,26.7333984375,11.962890625 494 | 294,-2.353515625,1.1363525390625,1.0611572265625,-21.05712890625,26.7333984375,11.962890625 495 | 294,-2.353515625,1.1363525390625,1.0611572265625,-21.05712890625,26.7333984375,11.962890625 496 | 294,-2.353515625,1.1363525390625,1.0611572265625,26.91650390625,22.5830078125,109.43603515625 497 | 294,0.53662109375,0.4326171875,-0.6522216796875,-5.615234375,146.30126953125,511.90185546875 498 | 294,0.53662109375,0.4326171875,-0.6522216796875,-5.615234375,146.30126953125,511.90185546875 499 | 324,0.53662109375,0.4326171875,-0.6522216796875,-5.615234375,146.30126953125,511.90185546875 500 | 324,1.2611083984375,-0.0477294921875,-0.952880859375,-33.447265625,142.51708984375,470.76416015625 501 | 324,1.2611083984375,-0.0477294921875,-0.952880859375,-33.447265625,142.51708984375,470.76416015625 502 | 324,1.2611083984375,-0.0477294921875,-0.952880859375,-33.447265625,142.51708984375,470.76416015625 503 | 324,1.2611083984375,-0.0477294921875,-0.952880859375,-33.447265625,142.51708984375,470.76416015625 504 | 324,1.2611083984375,-0.0477294921875,-0.952880859375,-33.447265625,142.51708984375,470.76416015625 505 | 324,2.55517578125,0.4542236328125,-0.3438720703125,-56.0302734375,136.23046875,389.22119140625 506 | 324,2.55517578125,0.4542236328125,-0.3438720703125,-56.0302734375,136.23046875,389.22119140625 507 | 324,2.55517578125,0.4542236328125,-0.3438720703125,-56.0302734375,136.23046875,389.22119140625 508 | 324,2.55517578125,0.4542236328125,-0.3438720703125,-56.0302734375,136.23046875,389.22119140625 509 | 376,2.55517578125,0.4542236328125,-0.3438720703125,-56.0302734375,136.23046875,389.22119140625 510 | 376,3.384765625,0.490478515625,0.5352783203125,-29.4189453125,81.4208984375,206.9091796875 511 | 376,3.384765625,0.490478515625,0.5352783203125,-29.4189453125,81.4208984375,206.9091796875 512 | 376,3.384765625,0.490478515625,0.5352783203125,-29.4189453125,81.4208984375,206.9091796875 513 | 376,3.384765625,0.490478515625,0.5352783203125,-29.4189453125,81.4208984375,206.9091796875 514 | 376,3.384765625,0.490478515625,0.5352783203125,-29.4189453125,81.4208984375,206.9091796875 515 | 376,3.0780029296875,0.324951171875,0.0498046875,-12.14599609375,32.958984375,65.24658203125 516 | 376,3.0780029296875,0.324951171875,0.0498046875,-12.14599609375,32.958984375,65.24658203125 517 | 376,3.0780029296875,0.324951171875,0.0498046875,-12.14599609375,32.958984375,65.24658203125 518 | 376,3.0780029296875,0.324951171875,0.0498046875,-12.14599609375,32.958984375,65.24658203125 519 | 479,3.0780029296875,0.324951171875,0.0498046875,-12.14599609375,32.958984375,65.24658203125 520 | 479,3.4088134765625,0.843017578125,-0.2286376953125,-33.447265625,-17.2119140625,-90.88134765625 521 | 479,3.4088134765625,0.843017578125,-0.2286376953125,-33.447265625,-17.2119140625,-90.88134765625 522 | 479,3.4088134765625,0.843017578125,-0.2286376953125,-33.447265625,-17.2119140625,-90.88134765625 523 | 479,-0.5040283203125,-1.3310546875,0.8829345703125,16.7236328125,-119.5068359375,-384.94873046875 524 | 479,-0.5040283203125,-1.3310546875,0.8829345703125,16.7236328125,-119.5068359375,-384.94873046875 525 | 479,-1.8238525390625,-2.4332275390625,1.0526123046875,21.8505859375,-104.1259765625,-339.05029296875 526 | 479,-1.8238525390625,-2.4332275390625,1.0526123046875,21.8505859375,-104.1259765625,-339.05029296875 527 | 479,-1.8238525390625,-2.4332275390625,1.0526123046875,21.8505859375,-104.1259765625,-339.05029296875 528 | 479,-1.8238525390625,-2.4332275390625,1.0526123046875,21.8505859375,-104.1259765625,-339.05029296875 529 | 478,-1.8238525390625,-2.4332275390625,1.0526123046875,21.8505859375,-104.1259765625,-339.05029296875 530 | 478,-2.4498291015625,-2.890625,1.0047607421875,20.3857421875,-79.7119140625,-263.36669921875 531 | 478,-2.4498291015625,-2.890625,1.0047607421875,20.3857421875,-79.7119140625,-263.36669921875 532 | 478,-2.4498291015625,-2.890625,1.0047607421875,20.3857421875,-79.7119140625,-263.36669921875 533 | 478,-2.4498291015625,-2.890625,1.0047607421875,20.3857421875,-79.7119140625,-263.36669921875 534 | 478,-2.4498291015625,-2.890625,1.0047607421875,20.3857421875,-79.7119140625,-263.36669921875 535 | 478,-1.9835205078125,-3.3170166015625,0.83837890625,20.08056640625,-65.36865234375,-194.2138671875 536 | 478,-1.9835205078125,-3.3170166015625,0.83837890625,20.08056640625,-65.36865234375,-194.2138671875 537 | 478,-1.9835205078125,-3.3170166015625,0.83837890625,20.08056640625,-65.36865234375,-194.2138671875 538 | 478,-1.9835205078125,-3.3170166015625,0.83837890625,20.08056640625,-65.36865234375,-194.2138671875 539 | 425,-1.9835205078125,-3.3170166015625,0.83837890625,20.08056640625,-65.36865234375,-194.2138671875 540 | 425,-1.408203125,-3.6033935546875,0.9068603515625,4.2724609375,-38.330078125,-99.365234375 541 | 425,-1.408203125,-3.6033935546875,0.9068603515625,4.2724609375,-38.330078125,-99.365234375 542 | 425,-1.408203125,-3.6033935546875,0.9068603515625,4.2724609375,-38.330078125,-99.365234375 543 | 425,-1.408203125,-3.6033935546875,0.9068603515625,4.2724609375,-38.330078125,-99.365234375 544 | 425,-1.408203125,-3.6033935546875,0.9068603515625,4.2724609375,-38.330078125,-99.365234375 545 | 425,-0.4422607421875,-1.5977783203125,0.6817626953125,-2.38037109375,-3.0517578125,-50.6591796875 546 | 425,-0.4422607421875,-1.5977783203125,0.6817626953125,-2.38037109375,-3.0517578125,-50.6591796875 547 | 425,-0.4422607421875,-1.5977783203125,0.6817626953125,-2.38037109375,-3.0517578125,-50.6591796875 548 | 425,-0.4422607421875,-1.5977783203125,0.6817626953125,-2.38037109375,-3.0517578125,-50.6591796875 549 | 368,-0.4422607421875,-1.5977783203125,0.6817626953125,-2.38037109375,-3.0517578125,-50.6591796875 550 | 368,-0.092041015625,-1.1744384765625,-0.3541259765625,28.564453125,-13.85498046875,-44.00634765625 551 | 368,-0.092041015625,-1.1744384765625,-0.3541259765625,28.564453125,-13.85498046875,-44.00634765625 552 | 368,-0.092041015625,-1.1744384765625,-0.3541259765625,28.564453125,-13.85498046875,-44.00634765625 553 | 368,-0.092041015625,-1.1744384765625,-0.3541259765625,28.564453125,-13.85498046875,-44.00634765625 554 | 368,-0.092041015625,-1.1744384765625,-0.3541259765625,28.564453125,-13.85498046875,-44.00634765625 555 | 368,0.0977783203125,-0.8690185546875,0.5428466796875,47.36328125,-6.34765625,-30.21240234375 556 | 368,0.0977783203125,-0.8690185546875,0.5428466796875,47.36328125,-6.34765625,-30.21240234375 557 | 368,0.0977783203125,-0.8690185546875,0.5428466796875,47.36328125,-6.34765625,-30.21240234375 558 | 368,0.0977783203125,-0.8690185546875,0.5428466796875,47.36328125,-6.34765625,-30.21240234375 559 | 358,0.0977783203125,-0.8690185546875,0.5428466796875,47.36328125,-6.34765625,-30.21240234375 560 | 358,-0.18798828125,-0.9134521484375,0.882080078125,3.96728515625,1.40380859375,-38.39111328125 561 | 358,-0.18798828125,-0.9134521484375,0.882080078125,3.96728515625,1.40380859375,-38.39111328125 562 | 358,-0.18798828125,-0.9134521484375,0.882080078125,3.96728515625,1.40380859375,-38.39111328125 563 | 358,-0.18798828125,-0.9134521484375,0.882080078125,3.96728515625,1.40380859375,-38.39111328125 564 | 358,-0.18798828125,-0.9134521484375,0.882080078125,3.96728515625,1.40380859375,-38.39111328125 565 | 358,-0.2977294921875,-0.779052734375,0.3272705078125,-2.38037109375,-5.859375,-36.19384765625 566 | 358,-0.2977294921875,-0.779052734375,0.3272705078125,-2.38037109375,-5.859375,-36.19384765625 567 | 358,-0.2977294921875,-0.779052734375,0.3272705078125,-2.38037109375,-5.859375,-36.19384765625 568 | 358,-0.2977294921875,-0.779052734375,0.3272705078125,-2.38037109375,-5.859375,-36.19384765625 569 | 289,-0.2977294921875,-0.779052734375,0.3272705078125,-2.38037109375,-5.859375,-36.19384765625 570 | 289,-0.1824951171875,-0.9700927734375,0.2821044921875,-11.41357421875,-8.36181640625,-40.10009765625 571 | 289,-0.1824951171875,-0.9700927734375,0.2821044921875,-11.41357421875,-8.36181640625,-40.10009765625 572 | 289,-0.1824951171875,-0.9700927734375,0.2821044921875,-11.41357421875,-8.36181640625,-40.10009765625 573 | 289,-0.1824951171875,-0.9700927734375,0.2821044921875,-11.41357421875,-8.36181640625,-40.10009765625 574 | 289,-0.1824951171875,-0.9700927734375,0.2821044921875,-11.41357421875,-8.36181640625,-40.10009765625 575 | 289,-0.04443359375,-1.1329345703125,0.1739501953125,-2.74658203125,-12.63427734375,-38.63525390625 576 | 289,-0.2078857421875,-0.778076171875,0.3260498046875,4.69970703125,-22.03369140625,-45.34912109375 577 | 289,-0.2078857421875,-0.778076171875,0.3260498046875,4.69970703125,-22.03369140625,-45.34912109375 578 | 289,-0.2078857421875,-0.778076171875,0.3260498046875,4.69970703125,-22.03369140625,-45.34912109375 579 | 152,-0.0596923828125,-0.9520263671875,0.1578369140625,8.6669921875,-24.4140625,-49.98779296875 580 | 152,-0.0596923828125,-0.9520263671875,0.1578369140625,8.6669921875,-24.4140625,-49.98779296875 581 | 152,-0.0596923828125,-0.9520263671875,0.1578369140625,8.6669921875,-24.4140625,-49.98779296875 582 | 152,-0.0596923828125,-0.9520263671875,0.1578369140625,8.6669921875,-24.4140625,-49.98779296875 583 | 152,-0.0596923828125,-0.9520263671875,0.1578369140625,8.6669921875,-24.4140625,-49.98779296875 584 | 152,0.0159912109375,-1.069580078125,0.2174072265625,7.99560546875,-14.46533203125,-52.06298828125 585 | 152,0.0159912109375,-1.069580078125,0.2174072265625,7.99560546875,-14.46533203125,-52.06298828125 586 | 152,0.0159912109375,-1.069580078125,0.2174072265625,7.99560546875,-14.46533203125,-52.06298828125 587 | 152,0.0159912109375,-1.069580078125,0.2174072265625,7.99560546875,-14.46533203125,-52.06298828125 588 | 152,0.0159912109375,-1.069580078125,0.2174072265625,7.99560546875,-14.46533203125,-52.06298828125 589 | 127,-0.0447998046875,-0.9176025390625,0.2689208984375,12.51220703125,-15.44189453125,-51.26953125 590 | 127,-0.0447998046875,-0.9176025390625,0.2689208984375,12.51220703125,-15.44189453125,-51.26953125 591 | 127,-0.0447998046875,-0.9176025390625,0.2689208984375,12.51220703125,-15.44189453125,-51.26953125 592 | 127,-0.0447998046875,-0.9176025390625,0.2689208984375,12.51220703125,-15.44189453125,-51.26953125 593 | 127,-0.0447998046875,-0.9176025390625,0.2689208984375,12.51220703125,-15.44189453125,-51.26953125 594 | 127,0.0318603515625,-0.90234375,0.3363037109375,1.64794921875,-14.5263671875,-52.79541015625 595 | 127,0.0318603515625,-0.90234375,0.3363037109375,1.64794921875,-14.5263671875,-52.79541015625 596 | 127,0.0318603515625,-0.90234375,0.3363037109375,1.64794921875,-14.5263671875,-52.79541015625 597 | 127,0.0318603515625,-0.90234375,0.3363037109375,1.64794921875,-14.5263671875,-52.79541015625 598 | 127,0.0318603515625,-0.90234375,0.3363037109375,0.732421875,-8.60595703125,-49.9267578125 599 | 33,0.105224609375,-0.9471435546875,0.273193359375,0.732421875,-8.60595703125,-49.9267578125 600 | 33,0.105224609375,-0.9471435546875,0.273193359375,0.732421875,-8.60595703125,-49.9267578125 601 | 33,0.105224609375,-0.9471435546875,0.273193359375,0.732421875,-8.60595703125,-49.9267578125 602 | 33,0.105224609375,-0.9471435546875,0.273193359375,0.732421875,-8.60595703125,-49.9267578125 603 | 33,0.0711669921875,-1.103515625,0.2186279296875,1.708984375,-6.2255859375,-39.0625 604 | 33,0.0711669921875,-1.103515625,0.2186279296875,1.708984375,-6.2255859375,-39.0625 605 | 33,0.0711669921875,-1.103515625,0.2186279296875,1.708984375,-6.2255859375,-39.0625 606 | 33,0.0711669921875,-1.103515625,0.2186279296875,1.708984375,-6.2255859375,-39.0625 607 | 33,0.0711669921875,-1.103515625,0.2186279296875,1.708984375,-6.2255859375,-39.0625 608 | 33,0.0711669921875,-1.103515625,0.2186279296875,1.708984375,-6.2255859375,-39.0625 609 | 29,0.0224609375,-1.093994140625,0.240234375,7.50732421875,-10.92529296875,-42.48046875 610 | 29,0.0224609375,-1.093994140625,0.240234375,7.50732421875,-10.92529296875,-42.48046875 611 | 29,0.0224609375,-1.093994140625,0.240234375,7.50732421875,-10.92529296875,-42.48046875 612 | 29,0.0224609375,-1.093994140625,0.240234375,7.50732421875,-10.92529296875,-42.48046875 613 | 29,0.0224609375,-1.093994140625,0.240234375,7.50732421875,-10.92529296875,-42.48046875 614 | 29,0.0528564453125,-1.021484375,0.2308349609375,11.16943359375,-15.07568359375,-43.3349609375 615 | 29,0.0528564453125,-1.021484375,0.2308349609375,11.16943359375,-15.07568359375,-43.3349609375 616 | 29,0.0528564453125,-1.021484375,0.2308349609375,11.16943359375,-15.07568359375,-43.3349609375 617 | 29,0.0528564453125,-1.021484375,0.2308349609375,11.16943359375,-15.07568359375,-43.3349609375 618 | 29,0.0528564453125,-1.021484375,0.2308349609375,11.16943359375,-15.07568359375,-43.3349609375 619 | 26,0.1368408203125,-1.0155029296875,0.261474609375,14.2822265625,-15.7470703125,-42.48046875 620 | 26,0.1368408203125,-1.0155029296875,0.261474609375,14.2822265625,-15.7470703125,-42.48046875 621 | 26,0.1368408203125,-1.0155029296875,0.261474609375,14.2822265625,-15.7470703125,-42.48046875 622 | 26,0.1368408203125,-1.0155029296875,0.261474609375,14.2822265625,-15.7470703125,-42.48046875 623 | 26,0.1368408203125,-1.0155029296875,0.261474609375,14.2822265625,-15.7470703125,-42.48046875 624 | 26,0.095703125,-0.9466552734375,0.295654296875,14.34326171875,-14.46533203125,-41.50390625 625 | 26,0.095703125,-0.9466552734375,0.295654296875,14.34326171875,-14.46533203125,-41.50390625 626 | 26,0.095703125,-0.9466552734375,0.295654296875,14.34326171875,-14.46533203125,-41.50390625 627 | 26,0.095703125,-0.9466552734375,0.295654296875,14.34326171875,-14.46533203125,-41.50390625 628 | 26,0.095703125,-0.9466552734375,0.295654296875,14.34326171875,-14.46533203125,-41.50390625 629 | 28,0.02880859375,-0.844482421875,0.294189453125,8.48388671875,-14.83154296875,-41.259765625 630 | 28,0.142333984375,-0.9315185546875,0.2989501953125,-18.98193359375,8.6669921875,-56.70166015625 631 | 28,0.2781982421875,-1.3199462890625,0.0152587890625,19.775390625,-14.892578125,-39.794921875 632 | 28,0.2781982421875,-1.3199462890625,0.0152587890625,19.775390625,-14.892578125,-39.794921875 633 | 28,0.2781982421875,-1.3199462890625,0.0152587890625,19.775390625,-14.892578125,-39.794921875 634 | 28,0.2781982421875,-1.3199462890625,0.0152587890625,19.775390625,-14.892578125,-39.794921875 635 | 28,0.2781982421875,-1.3199462890625,0.0152587890625,19.775390625,-14.892578125,-39.794921875 636 | 28,0.089111328125,-1.253662109375,0.416748046875,27.34375,-30.3955078125,-46.5087890625 637 | 28,0.089111328125,-1.253662109375,0.416748046875,27.34375,-30.3955078125,-46.5087890625 638 | 28,0.089111328125,-1.253662109375,0.416748046875,27.34375,-30.3955078125,-46.5087890625 639 | 27,0.089111328125,-1.253662109375,0.416748046875,27.34375,-30.3955078125,-46.5087890625 640 | 27,0.089111328125,-1.253662109375,0.416748046875,27.34375,-30.3955078125,-46.5087890625 641 | 27,0.3687744140625,-0.62744140625,0.2230224609375,-10.3759765625,-42.66357421875,-58.59375 642 | 27,0.3687744140625,-0.62744140625,0.2230224609375,-10.3759765625,-42.66357421875,-58.59375 643 | 27,0.3687744140625,-0.62744140625,0.2230224609375,-10.3759765625,-42.66357421875,-58.59375 644 | 27,0.3687744140625,-0.62744140625,0.2230224609375,-10.3759765625,-42.66357421875,-58.59375 645 | 27,0.3687744140625,-0.62744140625,0.2230224609375,-10.3759765625,-42.66357421875,-58.59375 646 | 27,-0.021484375,-0.56103515625,0.5960693359375,-32.28759765625,-32.89794921875,-69.2138671875 647 | 27,-0.021484375,-0.56103515625,0.5960693359375,-32.28759765625,-32.89794921875,-69.2138671875 648 | 27,-0.021484375,-0.56103515625,0.5960693359375,-32.28759765625,-32.89794921875,-69.2138671875 649 | 27,-0.021484375,-0.56103515625,0.5960693359375,-32.28759765625,-32.89794921875,-69.2138671875 650 | 27,-0.021484375,-0.56103515625,0.5960693359375,-32.28759765625,-32.89794921875,-69.2138671875 651 | 27,1.25390625,-2.3248291015625,0.21484375,-7.8125,-38.330078125,-31.8603515625 652 | 27,1.25390625,-2.3248291015625,0.21484375,-7.8125,-38.330078125,-31.8603515625 653 | 27,1.25390625,-2.3248291015625,0.21484375,-7.8125,-38.330078125,-31.8603515625 654 | 27,1.25390625,-2.3248291015625,0.21484375,-7.8125,-38.330078125,-31.8603515625 655 | 27,1.25390625,-2.3248291015625,0.21484375,-7.8125,-38.330078125,-31.8603515625 656 | 27,1.521240234375,-3.7921142578125,0.51611328125,-84.04541015625,-19.4091796875,36.43798828125 657 | 27,-0.2388916015625,-0.414306640625,-0.289306640625,-18.85986328125,22.705078125,21.66748046875 658 | 27,-2.1630859375,0.3306884765625,0.4857177734375,-18.85986328125,22.705078125,21.66748046875 659 | 26,-2.1630859375,0.3306884765625,0.4857177734375,-18.85986328125,22.705078125,21.66748046875 660 | 26,-2.1630859375,0.3306884765625,0.4857177734375,-18.85986328125,22.705078125,21.66748046875 661 | 26,-2.1630859375,0.3306884765625,0.4857177734375,-18.85986328125,22.705078125,21.66748046875 662 | 26,-2.1630859375,0.3306884765625,0.4857177734375,-18.85986328125,22.705078125,21.66748046875 663 | 26,-3.775146484375,1.2718505859375,1.0655517578125,21.78955078125,48.828125,116.88232421875 664 | 26,-3.775146484375,1.2718505859375,1.0655517578125,21.78955078125,48.828125,116.88232421875 665 | 26,-3.775146484375,1.2718505859375,1.0655517578125,21.78955078125,48.828125,116.88232421875 666 | 26,-3.775146484375,1.2718505859375,1.0655517578125,21.78955078125,48.828125,116.88232421875 667 | 26,-3.775146484375,1.2718505859375,1.0655517578125,21.78955078125,48.828125,116.88232421875 668 | 26,-3.753662109375,0.9744873046875,1.166015625,66.650390625,79.58984375,267.4560546875 669 | 25,-3.753662109375,0.9744873046875,1.166015625,66.650390625,79.58984375,267.4560546875 670 | 25,-3.753662109375,0.9744873046875,1.166015625,66.650390625,79.58984375,267.4560546875 671 | 25,-3.753662109375,0.9744873046875,1.166015625,66.650390625,79.58984375,267.4560546875 672 | 25,-3.753662109375,0.9744873046875,1.166015625,66.650390625,79.58984375,267.4560546875 673 | 25,-2.78662109375,0.4412841796875,-0.6634521484375,92.46826171875,129.45556640625,425.78125 674 | 25,-2.78662109375,0.4412841796875,-0.6634521484375,92.46826171875,129.45556640625,425.78125 675 | 25,-2.78662109375,0.4412841796875,-0.6634521484375,92.46826171875,129.45556640625,425.78125 676 | 25,-2.78662109375,0.4412841796875,-0.6634521484375,92.46826171875,129.45556640625,425.78125 677 | 25,-2.78662109375,0.4412841796875,-0.6634521484375,92.46826171875,129.45556640625,425.78125 678 | 25,-1.5609130859375,0.5447998046875,-1.472412109375,44.98291015625,157.16552734375,510.07080078125 679 | 25,-1.5609130859375,0.5447998046875,-1.472412109375,44.98291015625,157.16552734375,510.07080078125 680 | 25,-1.5609130859375,0.5447998046875,-1.472412109375,44.98291015625,157.16552734375,510.07080078125 681 | 25,-1.5609130859375,0.5447998046875,-1.472412109375,44.98291015625,157.16552734375,510.07080078125 682 | 25,-1.5609130859375,0.5447998046875,-1.472412109375,44.98291015625,157.16552734375,510.07080078125 683 | 25,3.619873046875,-0.0975341796875,0.33056640625,-13.916015625,62.98828125,189.63623046875 684 | 25,3.619873046875,-0.0975341796875,0.33056640625,-13.916015625,62.98828125,189.63623046875 685 | 25,3.619873046875,-0.0975341796875,0.33056640625,-13.916015625,62.98828125,189.63623046875 686 | 25,3.9915771484375,0.6915283203125,0.1251220703125,-6.16455078125,-3.2958984375,-7.9345703125 687 | 25,3.9915771484375,0.6915283203125,0.1251220703125,-6.16455078125,-3.2958984375,-7.9345703125 688 | 25,3.9915771484375,0.6915283203125,0.1251220703125,-6.16455078125,-3.2958984375,-7.9345703125 689 | 25,3.9915771484375,0.6915283203125,0.1251220703125,-6.16455078125,-3.2958984375,-7.9345703125 690 | 25,3.9915771484375,0.6915283203125,0.1251220703125,-6.16455078125,-3.2958984375,-7.9345703125 691 | 25,3.86083984375,0.05078125,0.2161865234375,-12.26806640625,-63.65966796875,-193.66455078125 692 | 25,3.86083984375,0.05078125,0.2161865234375,-12.26806640625,-63.65966796875,-193.66455078125 693 | 25,3.86083984375,0.05078125,0.2161865234375,-12.26806640625,-63.65966796875,-193.66455078125 694 | 25,3.86083984375,0.05078125,0.2161865234375,-12.26806640625,-63.65966796875,-193.66455078125 695 | 25,3.86083984375,0.05078125,0.2161865234375,1.64794921875,-91.6748046875,-318.54248046875 696 | 25,2.7000732421875,-0.7724609375,0.464599609375,1.64794921875,-91.6748046875,-318.54248046875 697 | 25,2.7000732421875,-0.7724609375,0.464599609375,1.64794921875,-91.6748046875,-318.54248046875 698 | 25,2.7000732421875,-0.7724609375,0.464599609375,1.64794921875,-91.6748046875,-318.54248046875 699 | 25,2.7000732421875,-0.7724609375,0.464599609375,1.64794921875,-91.6748046875,-318.54248046875 700 | 25,2.7000732421875,-0.7724609375,0.464599609375,-1.77001953125,-102.5390625,-367.0654296875 701 | 25,1.25390625,-1.267333984375,0.5372314453125,-1.77001953125,-102.5390625,-367.0654296875 702 | 25,1.25390625,-1.267333984375,0.5372314453125,-1.77001953125,-102.5390625,-367.0654296875 703 | 25,1.25390625,-1.267333984375,0.5372314453125,-1.77001953125,-102.5390625,-367.0654296875 704 | 25,1.25390625,-1.267333984375,0.5372314453125,-1.77001953125,-102.5390625,-367.0654296875 705 | 25,1.25390625,-1.267333984375,0.5372314453125,5.37109375,-118.1640625,-386.90185546875 706 | 25,0.3909912109375,-1.0657958984375,0.7342529296875,5.37109375,-118.1640625,-386.90185546875 707 | 25,0.3909912109375,-1.0657958984375,0.7342529296875,5.37109375,-118.1640625,-386.90185546875 708 | 25,0.3909912109375,-1.0657958984375,0.7342529296875,5.37109375,-118.1640625,-386.90185546875 709 | 22,-1.7574462890625,-3.9549560546875,0.8115234375,-14.2822265625,-2.3193359375,-36.865234375 710 | 22,-0.8988037109375,-2.2005615234375,0.6707763671875,-14.2822265625,-2.3193359375,-36.865234375 711 | 22,-0.8988037109375,-2.2005615234375,0.6707763671875,-14.2822265625,-2.3193359375,-36.865234375 712 | 22,-0.8988037109375,-2.2005615234375,0.6707763671875,-14.2822265625,-2.3193359375,-36.865234375 713 | 22,-0.8988037109375,-2.2005615234375,0.6707763671875,-14.2822265625,-2.3193359375,-36.865234375 714 | 22,-0.8988037109375,-2.2005615234375,0.6707763671875,-3.7841796875,13.671875,-67.0166015625 715 | 22,-0.1722412109375,-0.2156982421875,0.6552734375,-3.7841796875,13.671875,-67.0166015625 716 | 22,-0.1722412109375,-0.2156982421875,0.6552734375,-3.7841796875,13.671875,-67.0166015625 717 | 22,-0.1722412109375,-0.2156982421875,0.6552734375,-3.7841796875,13.671875,-67.0166015625 718 | 22,-0.1722412109375,-0.2156982421875,0.6552734375,-3.7841796875,13.671875,-67.0166015625 719 | 163,-0.1722412109375,-0.2156982421875,0.6552734375,-42.66357421875,21.05712890625,-27.099609375 720 | 163,0.50830078125,-0.192626953125,1.076171875,-42.66357421875,21.05712890625,-27.099609375 721 | 163,0.50830078125,-0.192626953125,1.076171875,-42.66357421875,21.05712890625,-27.099609375 722 | 163,0.50830078125,-0.192626953125,1.076171875,-42.66357421875,21.05712890625,-27.099609375 723 | 163,0.50830078125,-0.192626953125,1.076171875,-42.66357421875,21.05712890625,-27.099609375 724 | 163,0.1273193359375,-0.95263671875,0.387939453125,-29.9072265625,-31.55517578125,-47.18017578125 725 | 163,0.1273193359375,-0.95263671875,0.387939453125,-29.9072265625,-31.55517578125,-47.18017578125 726 | 163,0.1273193359375,-0.95263671875,0.387939453125,-29.9072265625,-31.55517578125,-47.18017578125 727 | 163,0.1273193359375,-0.95263671875,0.387939453125,-29.9072265625,-31.55517578125,-47.18017578125 728 | 163,0.1273193359375,-0.95263671875,0.387939453125,-29.9072265625,-31.55517578125,-47.18017578125 729 | 206,0.3974609375,-0.9818115234375,-0.1376953125,19.6533203125,-4.0283203125,-37.109375 730 | 206,0.3974609375,-0.9818115234375,-0.1376953125,19.6533203125,-4.0283203125,-37.109375 731 | 206,0.3974609375,-0.9818115234375,-0.1376953125,19.6533203125,-4.0283203125,-37.109375 732 | 206,0.3974609375,-0.9818115234375,-0.1376953125,19.6533203125,-4.0283203125,-37.109375 733 | 206,0.3974609375,-0.9818115234375,-0.1376953125,19.6533203125,-4.0283203125,-37.109375 734 | 206,0.791259765625,-0.1929931640625,0.757568359375,13.00048828125,13.36669921875,-36.865234375 735 | 206,-0.025390625,-1.1043701171875,0.254638671875,-23.98681640625,-4.5166015625,-43.9453125 736 | 206,-0.025390625,-1.1043701171875,0.254638671875,-23.98681640625,-4.5166015625,-43.9453125 737 | 206,-0.025390625,-1.1043701171875,0.254638671875,7.14111328125,0.732421875,-36.2548828125 738 | 206,0.1314697265625,-1.27294921875,0.085693359375,7.14111328125,0.732421875,-36.2548828125 739 | 356,0.1314697265625,-1.27294921875,0.085693359375,7.14111328125,0.732421875,-36.2548828125 740 | 356,0.1314697265625,-1.27294921875,0.085693359375,7.14111328125,0.732421875,-36.2548828125 741 | 356,0.1314697265625,-1.27294921875,0.085693359375,7.14111328125,0.732421875,-36.2548828125 742 | 356,0.1314697265625,-1.27294921875,0.085693359375,22.8271484375,-2.3193359375,-32.65380859375 743 | 356,-0.1666259765625,-1.07763671875,0.235595703125,22.8271484375,-2.3193359375,-32.65380859375 744 | 356,-0.1666259765625,-1.07763671875,0.235595703125,22.8271484375,-2.3193359375,-32.65380859375 745 | 356,-0.1666259765625,-1.07763671875,0.235595703125,22.8271484375,-2.3193359375,-32.65380859375 746 | 356,-0.1666259765625,-1.07763671875,0.235595703125,22.8271484375,-2.3193359375,-32.65380859375 747 | 356,-0.1666259765625,-1.07763671875,0.235595703125,10.8642578125,-21.91162109375,-37.7197265625 748 | 356,-0.1654052734375,-0.92431640625,0.3326416015625,10.8642578125,-21.91162109375,-37.7197265625 749 | 356,-0.1654052734375,-0.92431640625,0.3326416015625,10.8642578125,-21.91162109375,-37.7197265625 750 | 378,-0.1654052734375,-0.92431640625,0.3326416015625,10.8642578125,-21.91162109375,-37.7197265625 751 | 378,-0.1654052734375,-0.92431640625,0.3326416015625,10.8642578125,-21.91162109375,-37.7197265625 752 | 378,-0.1654052734375,-0.92431640625,0.3326416015625,10.986328125,-20.751953125,-33.75244140625 753 | 378,0.02294921875,-1.0965576171875,0.20068359375,10.986328125,-20.751953125,-33.75244140625 754 | 378,0.02294921875,-1.0965576171875,0.20068359375,10.986328125,-20.751953125,-33.75244140625 755 | 378,0.02294921875,-1.0965576171875,0.20068359375,10.986328125,-20.751953125,-33.75244140625 756 | 378,0.02294921875,-1.0965576171875,0.20068359375,10.986328125,-20.751953125,-33.75244140625 757 | 378,0.02294921875,-1.0965576171875,0.20068359375,23.3154296875,-21.30126953125,-32.958984375 758 | 378,-0.0689697265625,-0.9942626953125,0.30908203125,23.3154296875,-21.30126953125,-32.958984375 759 | 379,-0.0689697265625,-0.9942626953125,0.30908203125,23.3154296875,-21.30126953125,-32.958984375 760 | 379,-0.0689697265625,-0.9942626953125,0.30908203125,23.3154296875,-21.30126953125,-32.958984375 761 | 379,-0.0689697265625,-0.9942626953125,0.30908203125,23.3154296875,-21.30126953125,-32.958984375 762 | 379,0.0372314453125,-1.0318603515625,0.3824462890625,-8.48388671875,-12.26806640625,-50.72021484375 763 | 379,0.0372314453125,-1.0318603515625,0.3824462890625,-8.48388671875,-12.26806640625,-50.72021484375 764 | 379,0.0372314453125,-1.0318603515625,0.3824462890625,-8.48388671875,-12.26806640625,-50.72021484375 765 | 379,0.0372314453125,-1.0318603515625,0.3824462890625,-8.48388671875,-12.26806640625,-50.72021484375 766 | 379,0.00048828125,-0.9693603515625,0.28857421875,-5.31005859375,-14.58740234375,-44.49462890625 767 | 379,0.00048828125,-0.9693603515625,0.28857421875,-5.31005859375,-14.58740234375,-44.49462890625 768 | 379,0.00048828125,-0.9693603515625,0.28857421875,-5.31005859375,-14.58740234375,-44.49462890625 769 | 568,0.00048828125,-0.9693603515625,0.28857421875,-5.31005859375,-14.58740234375,-44.49462890625 770 | 568,0.00048828125,-0.9693603515625,0.28857421875,-5.31005859375,-14.58740234375,-44.49462890625 771 | 568,0.0714111328125,-0.87744140625,0.1663818359375,-1.708984375,-6.53076171875,-37.53662109375 772 | 568,0.0714111328125,-0.87744140625,0.1663818359375,-1.708984375,-6.53076171875,-37.53662109375 773 | 568,0.0714111328125,-0.87744140625,0.1663818359375,-1.708984375,-6.53076171875,-37.53662109375 774 | 568,0.0714111328125,-0.87744140625,0.1663818359375,-1.708984375,-6.53076171875,-37.53662109375 775 | 568,0.0714111328125,-0.87744140625,0.1663818359375,-1.708984375,-6.53076171875,-37.53662109375 776 | 568,0.1376953125,-0.9820556640625,0.175048828125,2.5634765625,5.06591796875,-32.16552734375 777 | 568,0.1376953125,-0.9820556640625,0.175048828125,2.5634765625,5.06591796875,-32.16552734375 778 | 568,0.1376953125,-0.9820556640625,0.175048828125,2.5634765625,5.06591796875,-32.16552734375 779 | 622,0.1376953125,-0.9820556640625,0.175048828125,2.5634765625,5.06591796875,-32.16552734375 780 | 622,0.1376953125,-0.9820556640625,0.175048828125,2.5634765625,5.06591796875,-32.16552734375 781 | 622,0.1094970703125,-0.9844970703125,0.3509521484375,4.69970703125,-1.0986328125,-27.03857421875 782 | 622,0.1094970703125,-0.9844970703125,0.3509521484375,4.69970703125,-1.0986328125,-27.03857421875 783 | 622,0.1094970703125,-0.9844970703125,0.3509521484375,4.69970703125,-1.0986328125,-27.03857421875 784 | 622,0.1094970703125,-0.9844970703125,0.3509521484375,4.69970703125,-1.0986328125,-27.03857421875 785 | 622,0.1094970703125,-0.9844970703125,0.3509521484375,4.69970703125,-1.0986328125,-27.03857421875 786 | 622,0.01318359375,-0.974609375,0.386474609375,-2.8076171875,1.5869140625,-33.0810546875 787 | 622,0.01318359375,-0.974609375,0.386474609375,-2.8076171875,1.5869140625,-33.0810546875 788 | 622,0.01318359375,-0.974609375,0.386474609375,-2.8076171875,1.5869140625,-33.0810546875 789 | 562,0.125244140625,-1.018310546875,0.2919921875,25.634765625,-9.8876953125,-37.78076171875 790 | 562,-0.0074462890625,-0.8863525390625,0.3702392578125,17.08984375,-12.8173828125,-38.51318359375 791 | 562,-0.0074462890625,-0.8863525390625,0.3702392578125,17.08984375,-12.8173828125,-38.51318359375 792 | 562,-0.0074462890625,-0.8863525390625,0.3702392578125,17.08984375,-12.8173828125,-38.51318359375 793 | 562,-0.0074462890625,-0.8863525390625,0.3702392578125,17.08984375,-12.8173828125,-38.51318359375 794 | 562,-0.0074462890625,-0.8863525390625,0.3702392578125,17.08984375,-12.8173828125,-38.51318359375 795 | 562,0.04345703125,-1.047607421875,0.3114013671875,10.986328125,-17.27294921875,-42.90771484375 796 | 562,0.04345703125,-1.047607421875,0.3114013671875,10.986328125,-17.27294921875,-42.90771484375 797 | 562,0.04345703125,-1.047607421875,0.3114013671875,10.986328125,-17.27294921875,-42.90771484375 798 | 562,0.04345703125,-1.047607421875,0.3114013671875,10.986328125,-17.27294921875,-42.90771484375 799 | 450,0.04345703125,-1.047607421875,0.3114013671875,10.986328125,-17.27294921875,-42.90771484375 800 | 450,0.1038818359375,-1.0400390625,0.2841796875,8.544921875,-22.03369140625,-45.5322265625 801 | 450,0.1038818359375,-1.0400390625,0.2841796875,8.544921875,-22.03369140625,-45.5322265625 802 | 450,0.1038818359375,-1.0400390625,0.2841796875,8.544921875,-22.03369140625,-45.5322265625 803 | 450,0.1038818359375,-1.0400390625,0.2841796875,8.544921875,-22.03369140625,-45.5322265625 804 | 450,0.1038818359375,-1.0400390625,0.2841796875,-4.69970703125,-35.82763671875,-49.49951171875 805 | 450,0.314208984375,-0.8157958984375,0.1048583984375,-4.69970703125,-35.82763671875,-49.49951171875 806 | 450,0.314208984375,-0.8157958984375,0.1048583984375,-4.69970703125,-35.82763671875,-49.49951171875 807 | 450,0.314208984375,-0.8157958984375,0.1048583984375,-4.69970703125,-35.82763671875,-49.49951171875 808 | 450,0.314208984375,-0.8157958984375,0.1048583984375,-4.69970703125,-35.82763671875,-49.49951171875 809 | 364,0.314208984375,-0.8157958984375,0.1048583984375,-40.71044921875,-35.94970703125,-65.49072265625 810 | 364,0.3751220703125,-0.989501953125,0.102294921875,-40.71044921875,-35.94970703125,-65.49072265625 811 | 364,0.3751220703125,-0.989501953125,0.102294921875,-40.71044921875,-35.94970703125,-65.49072265625 812 | 364,0.3751220703125,-0.989501953125,0.102294921875,-40.71044921875,-35.94970703125,-65.49072265625 813 | 364,0.3751220703125,-0.989501953125,0.102294921875,-40.71044921875,-35.94970703125,-65.49072265625 814 | 364,0.3751220703125,-0.989501953125,0.102294921875,-43.8232421875,-40.6494140625,-65.0634765625 815 | 364,-0.2242431640625,-0.86083984375,0.626708984375,-43.8232421875,-40.6494140625,-65.0634765625 816 | 364,-0.2242431640625,-0.86083984375,0.626708984375,-43.8232421875,-40.6494140625,-65.0634765625 817 | 364,1.287841796875,-2.6265869140625,0.5916748046875,6.9580078125,-3.35693359375,-29.47998046875 818 | 364,1.287841796875,-2.6265869140625,0.5916748046875,6.9580078125,-3.35693359375,-29.47998046875 819 | 364,0.718994140625,-3.6968994140625,0.7384033203125,-15.56396484375,-36.1328125,57.6171875 820 | 364,0.718994140625,-3.6968994140625,0.7384033203125,-15.56396484375,-36.1328125,57.6171875 821 | 364,0.718994140625,-3.6968994140625,0.7384033203125,-15.56396484375,-36.1328125,57.6171875 822 | 364,0.718994140625,-3.6968994140625,0.7384033203125,-15.56396484375,-36.1328125,57.6171875 823 | 364,0.718994140625,-3.6968994140625,0.7384033203125,-15.56396484375,-36.1328125,57.6171875 824 | 364,1.23193359375,-2.8427734375,0.6729736328125,-49.8046875,39.36767578125,169.677734375 825 | 364,1.23193359375,-2.8427734375,0.6729736328125,-49.8046875,39.36767578125,169.677734375 826 | 364,1.23193359375,-2.8427734375,0.6729736328125,-49.8046875,39.36767578125,169.677734375 827 | 364,1.23193359375,-2.8427734375,0.6729736328125,-49.8046875,39.36767578125,169.677734375 828 | 364,1.23193359375,-2.8427734375,0.6729736328125,-49.8046875,39.36767578125,169.677734375 829 | 398,1.8070068359375,-2.2825927734375,0.5855712890625,-33.02001953125,82.58056640625,157.16552734375 830 | 398,1.8070068359375,-2.2825927734375,0.5855712890625,-33.02001953125,82.58056640625,157.16552734375 831 | 398,1.8070068359375,-2.2825927734375,0.5855712890625,-33.02001953125,82.58056640625,157.16552734375 832 | 398,1.8070068359375,-2.2825927734375,0.5855712890625,-33.02001953125,82.58056640625,157.16552734375 833 | 398,1.8070068359375,-2.2825927734375,0.5855712890625,-33.02001953125,82.58056640625,157.16552734375 834 | 398,1.278564453125,-1.4583740234375,0.8411865234375,-58.28857421875,49.072265625,133.11767578125 835 | 398,1.278564453125,-1.4583740234375,0.8411865234375,-58.28857421875,49.072265625,133.11767578125 836 | 398,1.278564453125,-1.4583740234375,0.8411865234375,-58.28857421875,49.072265625,133.11767578125 837 | 398,1.278564453125,-1.4583740234375,0.8411865234375,-58.28857421875,49.072265625,133.11767578125 838 | 398,1.278564453125,-1.4583740234375,0.8411865234375,-58.28857421875,49.072265625,133.11767578125 839 | 440,0.3616943359375,-0.54150390625,1.604248046875,-35.94970703125,13.7939453125,77.33154296875 840 | 440,0.3616943359375,-0.54150390625,1.604248046875,-35.94970703125,13.7939453125,77.33154296875 841 | 440,0.3616943359375,-0.54150390625,1.604248046875,-35.94970703125,13.7939453125,77.33154296875 842 | 440,0.3616943359375,-0.54150390625,1.604248046875,-35.94970703125,13.7939453125,77.33154296875 843 | 440,0.3616943359375,-0.54150390625,1.604248046875,-35.94970703125,13.7939453125,77.33154296875 844 | 440,-0.4434814453125,-0.4283447265625,0.9073486328125,-19.8974609375,11.3525390625,52.3681640625 845 | 440,-1.845458984375,0.814697265625,-1.323974609375,71.2890625,131.04248046875,468.81103515625 846 | 440,-1.845458984375,0.814697265625,-1.323974609375,71.2890625,131.04248046875,468.81103515625 847 | 440,-1.845458984375,0.814697265625,-1.323974609375,71.2890625,131.04248046875,468.81103515625 848 | 440,-0.864013671875,0.7611083984375,-0.6304931640625,53.03955078125,144.8974609375,521.3623046875 849 | 554,-0.864013671875,0.7611083984375,-0.6304931640625,53.03955078125,144.8974609375,521.3623046875 850 | 554,-0.864013671875,0.7611083984375,-0.6304931640625,53.03955078125,144.8974609375,521.3623046875 851 | 554,-0.864013671875,0.7611083984375,-0.6304931640625,53.03955078125,144.8974609375,521.3623046875 852 | 554,-0.864013671875,0.7611083984375,-0.6304931640625,53.03955078125,144.8974609375,521.3623046875 853 | 554,0.2423095703125,0.60986328125,-0.84521484375,58.4716796875,152.587890625,543.15185546875 854 | 554,0.2423095703125,0.60986328125,-0.84521484375,58.4716796875,152.587890625,543.15185546875 855 | 554,0.2423095703125,0.60986328125,-0.84521484375,58.4716796875,152.587890625,543.15185546875 856 | 554,0.2423095703125,0.60986328125,-0.84521484375,58.4716796875,152.587890625,543.15185546875 857 | 554,0.2423095703125,0.60986328125,-0.84521484375,58.4716796875,152.587890625,543.15185546875 858 | 554,1.13623046875,-0.0859375,-1.0853271484375,20.08056640625,143.85986328125,515.380859375 859 | 560,1.13623046875,-0.0859375,-1.0853271484375,20.08056640625,143.85986328125,515.380859375 860 | 560,1.13623046875,-0.0859375,-1.0853271484375,20.08056640625,143.85986328125,515.380859375 861 | 560,1.13623046875,-0.0859375,-1.0853271484375,20.08056640625,143.85986328125,515.380859375 862 | 560,1.13623046875,-0.0859375,-1.0853271484375,20.08056640625,143.85986328125,515.380859375 863 | 560,2.1378173828125,0.878662109375,-1.172119140625,-7.2021484375,126.40380859375,457.763671875 864 | 560,2.1378173828125,0.878662109375,-1.172119140625,-7.2021484375,126.40380859375,457.763671875 865 | 560,2.1378173828125,0.878662109375,-1.172119140625,-7.2021484375,126.40380859375,457.763671875 866 | 560,2.1378173828125,0.878662109375,-1.172119140625,-7.2021484375,126.40380859375,457.763671875 867 | 560,2.1378173828125,0.878662109375,-1.172119140625,-7.2021484375,126.40380859375,457.763671875 868 | 560,3.473388671875,0.8096923828125,-0.7120361328125,-29.052734375,89.84375,317.3828125 869 | 473,3.473388671875,0.8096923828125,-0.7120361328125,-29.052734375,89.84375,317.3828125 870 | 473,3.473388671875,0.8096923828125,-0.7120361328125,-29.052734375,89.84375,317.3828125 871 | 473,3.473388671875,0.8096923828125,-0.7120361328125,-29.052734375,89.84375,317.3828125 872 | 473,3.473388671875,0.8096923828125,-0.7120361328125,-29.052734375,89.84375,317.3828125 873 | 473,0.5657958984375,-0.9659423828125,0.601806640625,2.685546875,-102.47802734375,-364.74609375 874 | 473,0.5657958984375,-0.9659423828125,0.601806640625,2.685546875,-102.47802734375,-364.74609375 875 | 473,0.5657958984375,-0.9659423828125,0.601806640625,2.685546875,-102.47802734375,-364.74609375 876 | 473,0.5657958984375,-0.9659423828125,0.601806640625,2.685546875,-102.47802734375,-364.74609375 877 | 473,-0.871337890625,-1.8160400390625,1.0736083984375,-0.54931640625,-98.20556640625,-358.0322265625 878 | 473,-0.871337890625,-1.8160400390625,1.0736083984375,-0.54931640625,-98.20556640625,-358.0322265625 879 | 398,-0.871337890625,-1.8160400390625,1.0736083984375,-0.54931640625,-98.20556640625,-358.0322265625 880 | 398,-0.871337890625,-1.8160400390625,1.0736083984375,-0.54931640625,-98.20556640625,-358.0322265625 881 | 398,-0.871337890625,-1.8160400390625,1.0736083984375,-46.56982421875,-24.71923828125,-167.6025390625 882 | 398,-1.1328125,-2.0423583984375,1.9412841796875,-46.56982421875,-24.71923828125,-167.6025390625 883 | 398,-1.1328125,-2.0423583984375,1.9412841796875,-46.56982421875,-24.71923828125,-167.6025390625 884 | 398,-1.1328125,-2.0423583984375,1.9412841796875,-46.56982421875,-24.71923828125,-167.6025390625 885 | 398,-1.1328125,-2.0423583984375,1.9412841796875,-46.56982421875,-24.71923828125,-167.6025390625 886 | 398,-1.1328125,-2.0423583984375,1.9412841796875,-50.29296875,-2.9296875,-105.16357421875 887 | 398,-0.3272705078125,-2.6168212890625,1.88623046875,-50.29296875,-2.9296875,-105.16357421875 888 | 398,-0.3272705078125,-2.6168212890625,1.88623046875,-50.29296875,-2.9296875,-105.16357421875 889 | 398,-0.3272705078125,-2.6168212890625,1.88623046875,-50.29296875,-2.9296875,-105.16357421875 890 | 333,-0.3272705078125,-2.6168212890625,1.88623046875,-50.29296875,-2.9296875,-105.16357421875 891 | 333,-0.3272705078125,-2.6168212890625,1.88623046875,-3.41796875,-6.04248046875,-47.18017578125 892 | 333,-0.4073486328125,-3.088134765625,1.1881103515625,-3.41796875,-6.04248046875,-47.18017578125 893 | 333,-0.4073486328125,-3.088134765625,1.1881103515625,-3.41796875,-6.04248046875,-47.18017578125 894 | 333,-0.4073486328125,-3.088134765625,1.1881103515625,-3.41796875,-6.04248046875,-47.18017578125 895 | 333,-0.4073486328125,-3.088134765625,1.1881103515625,-3.41796875,-6.04248046875,-47.18017578125 896 | 333,-0.4073486328125,-3.088134765625,1.1881103515625,59.87548828125,-14.16015625,-15.56396484375 897 | 333,-0.4222412109375,-1.6051025390625,1.030517578125,59.87548828125,-14.16015625,-15.56396484375 898 | 333,-0.4222412109375,-1.6051025390625,1.030517578125,59.87548828125,-14.16015625,-15.56396484375 899 | 342,-0.4222412109375,-1.6051025390625,1.030517578125,59.87548828125,-14.16015625,-15.56396484375 900 | 342,-2.2392578125,-1.2808837890625,-0.2374267578125,19.8974609375,12.51220703125,-15.07568359375 901 | 342,0.243896484375,-0.0804443359375,-0.215087890625,19.8974609375,12.51220703125,-15.07568359375 902 | 342,0.243896484375,-0.0804443359375,-0.215087890625,19.8974609375,12.51220703125,-15.07568359375 903 | 342,0.243896484375,-0.0804443359375,-0.215087890625,19.8974609375,12.51220703125,-15.07568359375 904 | 342,0.243896484375,-0.0804443359375,-0.215087890625,19.8974609375,12.51220703125,-15.07568359375 905 | 342,0.243896484375,-0.0804443359375,-0.215087890625,19.8974609375,12.51220703125,-15.07568359375 906 | 342,-0.3348388671875,-0.2427978515625,-0.1036376953125,26.85546875,-34.3017578125,-31.6162109375 907 | 342,-0.3348388671875,-0.2427978515625,-0.1036376953125,26.85546875,-34.3017578125,-31.6162109375 908 | 342,-0.3348388671875,-0.2427978515625,-0.1036376953125,26.85546875,-34.3017578125,-31.6162109375 909 | 273,-0.3348388671875,-0.2427978515625,-0.1036376953125,26.85546875,-34.3017578125,-31.6162109375 910 | 273,-0.3348388671875,-0.2427978515625,-0.1036376953125,26.85546875,-34.3017578125,-31.6162109375 911 | 273,-0.721923828125,-0.1190185546875,0.4991455078125,10.1318359375,-17.7001953125,-52.91748046875 912 | 273,-0.721923828125,-0.1190185546875,0.4991455078125,10.1318359375,-17.7001953125,-52.91748046875 913 | 273,-0.721923828125,-0.1190185546875,0.4991455078125,10.1318359375,-17.7001953125,-52.91748046875 914 | 273,-0.721923828125,-0.1190185546875,0.4991455078125,10.1318359375,-17.7001953125,-52.91748046875 915 | 273,-0.721923828125,-0.1190185546875,0.4991455078125,10.1318359375,-17.7001953125,-52.91748046875 916 | 273,0.1138916015625,-0.4366455078125,0.400390625,-3.0517578125,13.36669921875,-66.650390625 917 | 273,0.1138916015625,-0.4366455078125,0.400390625,-3.0517578125,13.36669921875,-66.650390625 918 | 273,0.1138916015625,-0.4366455078125,0.400390625,-3.0517578125,13.36669921875,-66.650390625 919 | 119,0.1138916015625,-0.4366455078125,0.400390625,-3.0517578125,13.36669921875,-66.650390625 920 | 119,0.1138916015625,-0.4366455078125,0.400390625,-3.0517578125,13.36669921875,-66.650390625 921 | 119,-0.5428466796875,-1.8466796875,0.3909912109375,-22.216796875,-12.02392578125,-57.80029296875 922 | 119,-0.5428466796875,-1.8466796875,0.3909912109375,-22.216796875,-12.02392578125,-57.80029296875 923 | 119,-0.5428466796875,-1.8466796875,0.3909912109375,-22.216796875,-12.02392578125,-57.80029296875 924 | 119,-0.5428466796875,-1.8466796875,0.3909912109375,-22.216796875,-12.02392578125,-57.80029296875 925 | 119,-0.5428466796875,-1.8466796875,0.3909912109375,-22.216796875,-12.02392578125,-57.80029296875 926 | 119,0.087646484375,-1.0777587890625,0.2562255859375,14.83154296875,-18.798828125,-31.982421875 927 | 119,0.087646484375,-1.0777587890625,0.2562255859375,14.83154296875,-18.798828125,-31.982421875 928 | 119,0.087646484375,-1.0777587890625,0.2562255859375,14.83154296875,-18.798828125,-31.982421875 929 | 53,-0.2220458984375,-0.8858642578125,0.1951904296875,10.8642578125,-15.869140625,-33.99658203125 930 | 53,-0.2220458984375,-0.8858642578125,0.1951904296875,10.8642578125,-15.869140625,-33.99658203125 931 | 53,-0.2220458984375,-0.8858642578125,0.1951904296875,10.8642578125,-15.869140625,-33.99658203125 932 | 53,-0.2220458984375,-0.8858642578125,0.1951904296875,10.8642578125,-15.869140625,-33.99658203125 933 | 53,-0.2220458984375,-0.8858642578125,0.1951904296875,10.8642578125,-15.869140625,-33.99658203125 934 | 53,-0.368896484375,-0.86669921875,0.2750244140625,10.68115234375,-32.77587890625,-40.58837890625 935 | 53,-0.368896484375,-0.86669921875,0.2750244140625,10.68115234375,-32.77587890625,-40.58837890625 936 | 53,-0.368896484375,-0.86669921875,0.2750244140625,10.68115234375,-32.77587890625,-40.58837890625 937 | 53,-0.368896484375,-0.86669921875,0.2750244140625,10.68115234375,-32.77587890625,-40.58837890625 938 | 53,-0.368896484375,-0.86669921875,0.2750244140625,10.68115234375,-32.77587890625,-40.58837890625 939 | 28,0.005126953125,-0.8294677734375,0.389892578125,9.33837890625,-17.51708984375,-42.17529296875 940 | 28,0.005126953125,-0.8294677734375,0.389892578125,9.33837890625,-17.51708984375,-42.17529296875 941 | 28,0.005126953125,-0.8294677734375,0.389892578125,9.33837890625,-17.51708984375,-42.17529296875 942 | 28,0.005126953125,-0.8294677734375,0.389892578125,9.33837890625,-17.51708984375,-42.17529296875 943 | 28,0.005126953125,-0.8294677734375,0.389892578125,9.33837890625,-17.51708984375,-42.17529296875 944 | 28,-0.14599609375,-0.954345703125,0.258544921875,14.34326171875,-15.31982421875,-43.212890625 945 | 28,-0.14599609375,-0.954345703125,0.258544921875,14.34326171875,-15.31982421875,-43.212890625 946 | 28,-0.14599609375,-0.954345703125,0.258544921875,14.34326171875,-15.31982421875,-43.212890625 947 | 28,-0.14599609375,-0.954345703125,0.258544921875,14.34326171875,-15.31982421875,-43.212890625 948 | 28,-0.14599609375,-0.954345703125,0.258544921875,14.34326171875,-15.31982421875,-43.212890625 949 | 27,-0.1373291015625,-0.9979248046875,0.407470703125,7.080078125,-18.61572265625,-39.9169921875 950 | 27,-0.1373291015625,-0.9979248046875,0.407470703125,7.080078125,-18.61572265625,-39.9169921875 951 | 27,-0.1373291015625,-0.9979248046875,0.407470703125,7.080078125,-18.61572265625,-39.9169921875 952 | 27,-0.1099853515625,-0.8001708984375,0.2789306640625,2.9296875,2.3193359375,-22.03369140625 953 | 27,0.0615234375,-1.0882568359375,0.422607421875,2.9296875,2.3193359375,-22.03369140625 954 | 27,0.0615234375,-1.0882568359375,0.422607421875,2.9296875,2.3193359375,-22.03369140625 955 | 27,0.0615234375,-1.0882568359375,0.422607421875,2.9296875,2.3193359375,-22.03369140625 956 | 27,0.0615234375,-1.0882568359375,0.422607421875,2.9296875,2.3193359375,-22.03369140625 957 | 27,0.0615234375,-1.0882568359375,0.422607421875,2.9296875,2.3193359375,-22.03369140625 958 | 27,-0.0325927734375,-1.1419677734375,0.2940673828125,5.7373046875,1.03759765625,-23.37646484375 959 | 27,-0.0325927734375,-1.1419677734375,0.2940673828125,5.7373046875,1.03759765625,-23.37646484375 960 | 27,-0.0325927734375,-1.1419677734375,0.2940673828125,5.7373046875,1.03759765625,-23.37646484375 961 | 27,-0.0325927734375,-1.1419677734375,0.2940673828125,5.7373046875,1.03759765625,-23.37646484375 962 | 27,-0.0325927734375,-1.1419677734375,0.2940673828125,5.7373046875,1.03759765625,-23.37646484375 963 | 27,0.010986328125,-1.2547607421875,0.3397216796875,15.869140625,0,-23.92578125 964 | 27,0.010986328125,-1.2547607421875,0.3397216796875,15.869140625,0,-23.92578125 965 | 27,0.010986328125,-1.2547607421875,0.3397216796875,15.869140625,0,-23.92578125 966 | 27,0.010986328125,-1.2547607421875,0.3397216796875,15.869140625,0,-23.92578125 967 | 27,0.010986328125,-1.2547607421875,0.3397216796875,15.869140625,0,-23.92578125 968 | 27,-0.0888671875,-1.1434326171875,0.3507080078125,17.4560546875,-3.7841796875,-26.123046875 969 | 27,-0.0888671875,-1.1434326171875,0.3507080078125,17.4560546875,-3.7841796875,-26.123046875 970 | 27,-0.0888671875,-1.1434326171875,0.3507080078125,17.4560546875,-3.7841796875,-26.123046875 971 | 27,-0.0888671875,-1.1434326171875,0.3507080078125,17.4560546875,-3.7841796875,-26.123046875 972 | 27,-0.0888671875,-1.1434326171875,0.3507080078125,17.4560546875,-3.7841796875,-26.123046875 973 | 27,-0.123046875,-1.1422119140625,0.2574462890625,21.97265625,-9.8876953125,-26.7333984375 974 | 27,-0.123046875,-1.1422119140625,0.2574462890625,21.97265625,-9.8876953125,-26.7333984375 975 | 27,-0.123046875,-1.1422119140625,0.2574462890625,21.97265625,-9.8876953125,-26.7333984375 976 | 27,-0.123046875,-1.1422119140625,0.2574462890625,21.97265625,-9.8876953125,-26.7333984375 977 | 27,-0.123046875,-1.1422119140625,0.2574462890625,21.97265625,-9.8876953125,-26.7333984375 978 | 27,0.05078125,-1.313720703125,0.6124267578125,14.70947265625,-14.46533203125,-27.77099609375 979 | 27,0.05078125,-1.313720703125,0.6124267578125,14.70947265625,-14.46533203125,-27.77099609375 980 | 27,0.05078125,-1.313720703125,0.6124267578125,14.70947265625,-14.46533203125,-27.77099609375 981 | 27,0.1883544921875,-1.26171875,0.517822265625,2.197265625,-25.2685546875,-31.005859375 982 | 27,0.1883544921875,-1.26171875,0.517822265625,2.197265625,-25.2685546875,-31.005859375 983 | 27,0.1883544921875,-1.26171875,0.517822265625,2.197265625,-25.2685546875,-31.005859375 984 | 27,0.1883544921875,-1.26171875,0.517822265625,2.197265625,-25.2685546875,-31.005859375 985 | 27,0.1883544921875,-1.26171875,0.517822265625,2.197265625,-25.2685546875,-31.005859375 986 | 27,-0.02001953125,-0.8216552734375,0.259521484375,-8.85009765625,-27.40478515625,-33.69140625 987 | 27,-0.02001953125,-0.8216552734375,0.259521484375,-8.85009765625,-27.40478515625,-33.69140625 988 | 27,-0.02001953125,-0.8216552734375,0.259521484375,-8.85009765625,-27.40478515625,-33.69140625 989 | 26,-0.02001953125,-0.8216552734375,0.259521484375,-8.85009765625,-27.40478515625,-33.69140625 990 | 26,-0.02001953125,-0.8216552734375,0.259521484375,-5.126953125,-22.8271484375,-37.90283203125 991 | 26,-0.35205078125,-0.5010986328125,0.3524169921875,-5.126953125,-22.8271484375,-37.90283203125 992 | 26,-0.35205078125,-0.5010986328125,0.3524169921875,-5.126953125,-22.8271484375,-37.90283203125 993 | 26,-0.35205078125,-0.5010986328125,0.3524169921875,-5.126953125,-22.8271484375,-37.90283203125 994 | 26,-0.35205078125,-0.5010986328125,0.3524169921875,-5.126953125,-22.8271484375,-37.90283203125 995 | 26,-0.35205078125,-0.5010986328125,0.3524169921875,-9.6435546875,-8.60595703125,-40.46630859375 996 | 26,-0.064697265625,-0.6636962890625,0.468017578125,-9.6435546875,-8.60595703125,-40.46630859375 997 | 26,-0.064697265625,-0.6636962890625,0.468017578125,-9.6435546875,-8.60595703125,-40.46630859375 998 | 26,-0.064697265625,-0.6636962890625,0.468017578125,-9.6435546875,-8.60595703125,-40.46630859375 999 | 25,-0.064697265625,-0.6636962890625,0.468017578125,-9.6435546875,-8.60595703125,-40.46630859375 1000 | 25,-0.064697265625,-0.6636962890625,0.468017578125,-15.93017578125,-18.49365234375,-44.43359375 1001 | 25,0.0125732421875,-0.60595703125,0.374755859375,-15.93017578125,-18.49365234375,-44.43359375 1002 | 25,0.0125732421875,-0.60595703125,0.374755859375,-15.93017578125,-18.49365234375,-44.43359375 1003 | 25,0.0125732421875,-0.60595703125,0.374755859375,-15.93017578125,-18.49365234375,-44.43359375 1004 | 25,0.0125732421875,-0.60595703125,0.374755859375,-15.93017578125,-18.49365234375,-44.43359375 1005 | 25,0.5135498046875,-1.1295166015625,1.3912353515625,-11.04736328125,13.36669921875,53.955078125 1006 | 25,0.5135498046875,-1.1295166015625,1.3912353515625,-11.04736328125,13.36669921875,53.955078125 1007 | 25,0.5135498046875,-1.1295166015625,1.3912353515625,-11.04736328125,13.36669921875,53.955078125 1008 | 25,0.5135498046875,-1.1295166015625,1.3912353515625,-11.04736328125,13.36669921875,53.955078125 1009 | 26,0.5135498046875,-1.1295166015625,1.3912353515625,-11.04736328125,13.36669921875,53.955078125 1010 | 26,0.5135498046875,-1.1295166015625,1.3912353515625,7.01904296875,13.7939453125,21.54541015625 1011 | 26,-0.2283935546875,-0.6624755859375,0.78955078125,7.01904296875,13.7939453125,21.54541015625 1012 | 26,-0.2283935546875,-0.6624755859375,0.78955078125,7.01904296875,13.7939453125,21.54541015625 1013 | 26,-0.2283935546875,-0.6624755859375,0.78955078125,7.01904296875,13.7939453125,21.54541015625 1014 | 26,-0.2283935546875,-0.6624755859375,0.78955078125,7.01904296875,13.7939453125,21.54541015625 1015 | 26,-0.2283935546875,-0.6624755859375,0.78955078125,14.404296875,24.4140625,-1.0986328125 1016 | 26,-1.19580078125,0.327392578125,-0.5155029296875,14.404296875,24.4140625,-1.0986328125 1017 | 26,-1.19580078125,0.327392578125,-0.5155029296875,14.404296875,24.4140625,-1.0986328125 1018 | 26,-1.19580078125,0.327392578125,-0.5155029296875,14.404296875,24.4140625,-1.0986328125 1019 | 25,-1.19580078125,0.327392578125,-0.5155029296875,14.404296875,24.4140625,-1.0986328125 1020 | 25,-1.19580078125,0.327392578125,-0.5155029296875,-2.62451171875,35.400390625,30.517578125 1021 | 25,-2.9451904296875,1.201416015625,0.026123046875,-2.62451171875,35.400390625,30.517578125 1022 | 25,-2.9451904296875,1.201416015625,0.026123046875,-2.62451171875,35.400390625,30.517578125 1023 | 25,-2.9451904296875,1.201416015625,0.026123046875,-2.62451171875,35.400390625,30.517578125 1024 | 25,-2.9451904296875,1.201416015625,0.026123046875,-2.62451171875,35.400390625,30.517578125 1025 | 25,-3.9744873046875,1.909912109375,1.3822021484375,31.79931640625,49.072265625,146.484375 1026 | 25,-3.9744873046875,1.909912109375,1.3822021484375,31.79931640625,49.072265625,146.484375 1027 | 25,-3.9744873046875,1.909912109375,1.3822021484375,31.79931640625,49.072265625,146.484375 1028 | 25,-3.9744873046875,1.909912109375,1.3822021484375,31.79931640625,49.072265625,146.484375 1029 | 25,-3.9744873046875,1.909912109375,1.3822021484375,31.79931640625,49.072265625,146.484375 1030 | 25,-3.29296875,1.974365234375,-0.303955078125,84.53369140625,87.0361328125,323.8525390625 1031 | 25,-3.29296875,1.974365234375,-0.303955078125,84.53369140625,87.0361328125,323.8525390625 1032 | 25,1.4866943359375,0.017578125,-0.8095703125,-37.90283203125,140.9912109375,472.22900390625 1033 | 25,1.4866943359375,0.017578125,-0.8095703125,-37.90283203125,140.9912109375,472.22900390625 1034 | 25,1.4866943359375,0.017578125,-0.8095703125,-37.90283203125,140.9912109375,472.22900390625 1035 | 25,2.9422607421875,0.66552734375,-0.36669921875,-64.5751953125,113.46435546875,349.06005859375 1036 | 25,2.9422607421875,0.66552734375,-0.36669921875,-64.5751953125,113.46435546875,349.06005859375 1037 | 25,2.9422607421875,0.66552734375,-0.36669921875,-64.5751953125,113.46435546875,349.06005859375 1038 | 25,2.9422607421875,0.66552734375,-0.36669921875,-64.5751953125,113.46435546875,349.06005859375 1039 | 24,2.9422607421875,0.66552734375,-0.36669921875,-64.5751953125,113.46435546875,349.06005859375 1040 | 24,3.18896484375,0.134033203125,0.0408935546875,-39.1845703125,62.98828125,140.7470703125 1041 | 24,3.18896484375,0.134033203125,0.0408935546875,-39.1845703125,62.98828125,140.7470703125 1042 | 24,3.18896484375,0.134033203125,0.0408935546875,-39.1845703125,62.98828125,140.7470703125 1043 | 24,3.18896484375,0.134033203125,0.0408935546875,-39.1845703125,62.98828125,140.7470703125 1044 | 24,3.18896484375,0.134033203125,0.0408935546875,-39.1845703125,62.98828125,140.7470703125 1045 | 24,3.1505126953125,0.125,-0.459716796875,-46.2646484375,44.73876953125,11.41357421875 1046 | 24,3.1505126953125,0.125,-0.459716796875,-46.2646484375,44.73876953125,11.41357421875 1047 | 24,3.1505126953125,0.125,-0.459716796875,-46.2646484375,44.73876953125,11.41357421875 1048 | 24,3.1505126953125,0.125,-0.459716796875,-46.2646484375,44.73876953125,11.41357421875 1049 | 23,3.1505126953125,0.125,-0.459716796875,-46.2646484375,44.73876953125,11.41357421875 1050 | 23,3.5390625,0.63720703125,-0.0201416015625,-56.2744140625,-17.7001953125,-167.6025390625 1051 | 23,3.5390625,0.63720703125,-0.0201416015625,-56.2744140625,-17.7001953125,-167.6025390625 1052 | 23,3.5390625,0.63720703125,-0.0201416015625,-56.2744140625,-17.7001953125,-167.6025390625 1053 | 23,3.5390625,0.63720703125,-0.0201416015625,-56.2744140625,-17.7001953125,-167.6025390625 1054 | 23,3.5390625,0.63720703125,-0.0201416015625,-56.2744140625,-17.7001953125,-167.6025390625 1055 | 23,2.675537109375,-0.3670654296875,0.55224609375,-42.8466796875,-66.46728515625,-285.15625 1056 | 23,2.675537109375,-0.3670654296875,0.55224609375,-42.8466796875,-66.46728515625,-285.15625 1057 | 23,2.675537109375,-0.3670654296875,0.55224609375,-42.8466796875,-66.46728515625,-285.15625 1058 | 23,2.675537109375,-0.3670654296875,0.55224609375,-42.8466796875,-66.46728515625,-285.15625 1059 | 22,-2.2547607421875,-3.0211181640625,1.17724609375,2.197265625,-90.51513671875,-323.1201171875 1060 | 22,-1.8056640625,-2.626708984375,1.7454833984375,-22.15576171875,-34.0576171875,-155.029296875 1061 | 22,-1.8056640625,-2.626708984375,1.7454833984375,-22.15576171875,-34.0576171875,-155.029296875 1062 | 22,-1.8056640625,-2.626708984375,1.7454833984375,-22.15576171875,-34.0576171875,-155.029296875 1063 | 22,-1.8056640625,-2.626708984375,1.7454833984375,-22.15576171875,-34.0576171875,-155.029296875 1064 | 22,-1.8056640625,-2.626708984375,1.7454833984375,-22.15576171875,-34.0576171875,-155.029296875 1065 | 22,-0.231201171875,-2.48828125,1.704833984375,-39.306640625,3.96728515625,-77.5146484375 1066 | 22,-0.231201171875,-2.48828125,1.704833984375,-39.306640625,3.96728515625,-77.5146484375 1067 | 22,-0.231201171875,-2.48828125,1.704833984375,-39.306640625,3.96728515625,-77.5146484375 1068 | 22,-0.231201171875,-2.48828125,1.704833984375,-39.306640625,3.96728515625,-77.5146484375 1069 | 433,-0.231201171875,-2.48828125,1.704833984375,-39.306640625,3.96728515625,-77.5146484375 1070 | 433,-0.2734375,-2.244873046875,1.349365234375,7.2021484375,-2.685546875,-9.27734375 1071 | 433,-0.2734375,-2.244873046875,1.349365234375,7.2021484375,-2.685546875,-9.27734375 1072 | 433,-0.2734375,-2.244873046875,1.349365234375,7.2021484375,-2.685546875,-9.27734375 1073 | 433,-0.2734375,-2.244873046875,1.349365234375,7.2021484375,-2.685546875,-9.27734375 1074 | 433,-0.2734375,-2.244873046875,1.349365234375,33.87451171875,6.591796875,-29.60205078125 1075 | 433,-0.5838623046875,-0.833740234375,0.0013427734375,33.87451171875,6.591796875,-29.60205078125 1076 | 433,-0.5838623046875,-0.833740234375,0.0013427734375,33.87451171875,6.591796875,-29.60205078125 1077 | 433,-0.5838623046875,-0.833740234375,0.0013427734375,33.87451171875,6.591796875,-29.60205078125 1078 | 433,-0.5838623046875,-0.833740234375,0.0013427734375,33.87451171875,6.591796875,-29.60205078125 1079 | 252,-0.5838623046875,-0.833740234375,0.0013427734375,13.3056640625,-10.986328125,-32.89794921875 1080 | 252,0.95703125,-0.3466796875,-0.459716796875,13.3056640625,-10.986328125,-32.89794921875 1081 | 252,0.95703125,-0.3466796875,-0.459716796875,13.3056640625,-10.986328125,-32.89794921875 1082 | 252,0.95703125,-0.3466796875,-0.459716796875,13.3056640625,-10.986328125,-32.89794921875 1083 | 252,0.95703125,-0.3466796875,-0.459716796875,13.3056640625,-10.986328125,-32.89794921875 1084 | 252,0.95703125,-0.3466796875,-0.459716796875,-9.3994140625,-19.10400390625,-59.99755859375 1085 | 252,0.6575927734375,-0.4522705078125,0.4249267578125,-9.3994140625,-19.10400390625,-59.99755859375 1086 | 252,0.025390625,-0.36474609375,0.547119140625,13.97705078125,-6.591796875,-55.0537109375 1087 | 252,0.025390625,-0.36474609375,0.547119140625,-4.638671875,-4.150390625,-51.8798828125 1088 | 252,-0.3511962890625,-1.1845703125,0.5703125,-4.638671875,-4.150390625,-51.8798828125 1089 | 297,-0.3511962890625,-1.1845703125,0.5703125,-4.638671875,-4.150390625,-51.8798828125 1090 | 297,-0.3511962890625,-1.1845703125,0.5703125,-4.638671875,-4.150390625,-51.8798828125 1091 | 297,-0.3511962890625,-1.1845703125,0.5703125,-4.638671875,-4.150390625,-51.8798828125 1092 | 297,-0.3511962890625,-1.1845703125,0.5703125,-15.0146484375,-4.94384765625,-41.19873046875 1093 | 297,-0.3104248046875,-1.6123046875,0.41796875,-15.0146484375,-4.94384765625,-41.19873046875 1094 | 297,-0.3104248046875,-1.6123046875,0.41796875,-15.0146484375,-4.94384765625,-41.19873046875 1095 | 297,-0.3104248046875,-1.6123046875,0.41796875,-15.0146484375,-4.94384765625,-41.19873046875 1096 | 297,-0.3104248046875,-1.6123046875,0.41796875,-15.0146484375,-4.94384765625,-41.19873046875 1097 | 297,-0.3104248046875,-1.6123046875,0.41796875,-13.916015625,-2.25830078125,-35.7666015625 1098 | 297,-0.268310546875,-1.130615234375,0.2093505859375,-13.916015625,-2.25830078125,-35.7666015625 1099 | 297,-0.268310546875,-1.130615234375,0.2093505859375,-13.916015625,-2.25830078125,-35.7666015625 1100 | 463,-0.268310546875,-1.130615234375,0.2093505859375,-13.916015625,-2.25830078125,-35.7666015625 1101 | 463,-0.268310546875,-1.130615234375,0.2093505859375,-13.916015625,-2.25830078125,-35.7666015625 1102 | 463,-0.077880859375,-1.099853515625,0.1768798828125,2.5634765625,-7.2021484375,-31.55517578125 1103 | 463,-0.077880859375,-1.099853515625,0.1768798828125,2.5634765625,-7.2021484375,-31.55517578125 1104 | 463,-0.077880859375,-1.099853515625,0.1768798828125,2.5634765625,-7.2021484375,-31.55517578125 1105 | 463,-0.077880859375,-1.099853515625,0.1768798828125,2.5634765625,-7.2021484375,-31.55517578125 1106 | 463,-0.077880859375,-1.099853515625,0.1768798828125,2.5634765625,-7.2021484375,-31.55517578125 1107 | 463,-0.096435546875,-1.251708984375,0.2337646484375,8.11767578125,-9.82666015625,-29.4189453125 1108 | 463,-0.096435546875,-1.251708984375,0.2337646484375,8.11767578125,-9.82666015625,-29.4189453125 1109 | 517,-0.096435546875,-1.251708984375,0.2337646484375,8.11767578125,-9.82666015625,-29.4189453125 1110 | 517,-0.096435546875,-1.251708984375,0.2337646484375,8.11767578125,-9.82666015625,-29.4189453125 1111 | 517,-0.096435546875,-1.251708984375,0.2337646484375,8.11767578125,-9.82666015625,-29.4189453125 1112 | 517,-0.10107421875,-1.2850341796875,0.2635498046875,13.61083984375,-15.2587890625,-28.50341796875 1113 | 517,-0.1136474609375,-0.7996826171875,0.2547607421875,13.916015625,-9.8876953125,-36.92626953125 1114 | 517,-0.1136474609375,-0.7996826171875,0.2547607421875,3.23486328125,-14.404296875,-37.90283203125 1115 | 517,-0.17822265625,-0.6708984375,0.4150390625,3.23486328125,-14.404296875,-37.90283203125 1116 | 517,-0.17822265625,-0.6708984375,0.4150390625,3.23486328125,-14.404296875,-37.90283203125 1117 | 517,-0.17822265625,-0.6708984375,0.4150390625,3.23486328125,-14.404296875,-37.90283203125 1118 | 517,-0.17822265625,-0.6708984375,0.4150390625,3.23486328125,-14.404296875,-37.90283203125 1119 | 532,-0.05224609375,-0.688720703125,0.4051513671875,-5.92041015625,-10.43701171875,-40.10009765625 1120 | 532,-0.05224609375,-0.688720703125,0.4051513671875,-5.92041015625,-10.43701171875,-40.10009765625 1121 | 532,-0.05224609375,-0.688720703125,0.4051513671875,-5.92041015625,-10.43701171875,-40.10009765625 1122 | 532,-0.05224609375,-0.688720703125,0.4051513671875,-5.92041015625,-10.43701171875,-40.10009765625 1123 | 532,-0.05224609375,-0.688720703125,0.4051513671875,-5.92041015625,-10.43701171875,-40.10009765625 1124 | 532,-0.0079345703125,-0.9400634765625,0.2950439453125,-9.3994140625,-3.72314453125,-37.17041015625 1125 | 532,-0.0079345703125,-0.9400634765625,0.2950439453125,-9.3994140625,-3.72314453125,-37.17041015625 1126 | 532,-0.0079345703125,-0.9400634765625,0.2950439453125,-9.3994140625,-3.72314453125,-37.17041015625 1127 | 532,-0.0079345703125,-0.9400634765625,0.2950439453125,-9.3994140625,-3.72314453125,-37.17041015625 1128 | 532,-0.0079345703125,-0.9400634765625,0.2950439453125,-9.3994140625,-3.72314453125,-37.17041015625 1129 | 466,-0.0224609375,-0.8612060546875,0.232666015625,-7.38525390625,-1.0986328125,-28.6865234375 1130 | 466,-0.0224609375,-0.8612060546875,0.232666015625,-7.38525390625,-1.0986328125,-28.6865234375 1131 | 466,-0.0224609375,-0.8612060546875,0.232666015625,-7.38525390625,-1.0986328125,-28.6865234375 1132 | 466,-0.0224609375,-0.8612060546875,0.232666015625,-7.38525390625,-1.0986328125,-28.6865234375 1133 | 466,-0.0224609375,-0.8612060546875,0.232666015625,-7.38525390625,-1.0986328125,-28.6865234375 1134 | 466,-0.0665283203125,-0.7337646484375,0.21533203125,-5.92041015625,0.42724609375,-27.52685546875 1135 | 466,-0.0665283203125,-0.7337646484375,0.21533203125,-5.92041015625,0.42724609375,-27.52685546875 1136 | 466,-0.0665283203125,-0.7337646484375,0.21533203125,-5.92041015625,0.42724609375,-27.52685546875 1137 | 466,-0.0665283203125,-0.7337646484375,0.21533203125,-5.92041015625,0.42724609375,-27.52685546875 1138 | 466,-0.0665283203125,-0.7337646484375,0.21533203125,-5.92041015625,0.42724609375,-27.52685546875 1139 | 370,-0.0860595703125,-0.945556640625,0.2537841796875,-6.4697265625,3.173828125,-26.18408203125 1140 | 370,-0.084228515625,-1.1795654296875,0.3262939453125,18.1884765625,-11.3525390625,-31.494140625 1141 | 370,-0.084228515625,-1.1795654296875,0.3262939453125,18.1884765625,-11.3525390625,-31.494140625 1142 | 370,-0.084228515625,-1.1795654296875,0.3262939453125,18.1884765625,-11.3525390625,-31.494140625 1143 | 370,-0.084228515625,-1.1795654296875,0.3262939453125,20.99609375,-9.765625,-31.494140625 1144 | 370,-0.0252685546875,-1.10205078125,0.3031005859375,20.99609375,-9.765625,-31.494140625 1145 | 370,-0.0252685546875,-1.10205078125,0.3031005859375,20.99609375,-9.765625,-31.494140625 1146 | 370,-0.0252685546875,-1.10205078125,0.3031005859375,20.99609375,-9.765625,-31.494140625 1147 | 370,-0.0252685546875,-1.10205078125,0.3031005859375,20.99609375,-9.765625,-31.494140625 1148 | 370,-0.0252685546875,-1.10205078125,0.3031005859375,23.8037109375,-8.9111328125,-31.73828125 1149 | 331,-0.052978515625,-0.9378662109375,0.270751953125,23.8037109375,-8.9111328125,-31.73828125 1150 | 331,-0.052978515625,-0.9378662109375,0.270751953125,23.8037109375,-8.9111328125,-31.73828125 1151 | 331,-0.052978515625,-0.9378662109375,0.270751953125,23.8037109375,-8.9111328125,-31.73828125 1152 | 331,-0.052978515625,-0.9378662109375,0.270751953125,23.8037109375,-8.9111328125,-31.73828125 1153 | 331,-0.052978515625,-0.9378662109375,0.270751953125,17.51708984375,-10.80322265625,-31.1279296875 1154 | 331,-0.072998046875,-0.8369140625,0.2705078125,17.51708984375,-10.80322265625,-31.1279296875 1155 | 331,-0.072998046875,-0.8369140625,0.2705078125,17.51708984375,-10.80322265625,-31.1279296875 1156 | 331,-0.072998046875,-0.8369140625,0.2705078125,17.51708984375,-10.80322265625,-31.1279296875 1157 | 331,-0.072998046875,-0.8369140625,0.2705078125,17.51708984375,-10.80322265625,-31.1279296875 1158 | 331,-0.072998046875,-0.8369140625,0.2705078125,12.39013671875,-11.5966796875,-29.9072265625 1159 | 309,-0.0025634765625,-0.8319091796875,0.25048828125,12.39013671875,-11.5966796875,-29.9072265625 1160 | 309,-0.0025634765625,-0.8319091796875,0.25048828125,12.39013671875,-11.5966796875,-29.9072265625 1161 | 309,-0.0025634765625,-0.8319091796875,0.25048828125,12.39013671875,-11.5966796875,-29.9072265625 1162 | 309,-0.0025634765625,-0.8319091796875,0.25048828125,12.39013671875,-11.5966796875,-29.9072265625 1163 | 309,-0.0025634765625,-0.8319091796875,0.25048828125,15.07568359375,-10.80322265625,-28.6865234375 1164 | 309,0.0361328125,-0.9959716796875,0.4429931640625,15.07568359375,-10.80322265625,-28.6865234375 1165 | 309,0.0361328125,-0.9959716796875,0.4429931640625,15.07568359375,-10.80322265625,-28.6865234375 1166 | 309,0.0361328125,-0.9959716796875,0.4429931640625,15.07568359375,-10.80322265625,-28.6865234375 1167 | 309,0.153564453125,-0.4483642578125,-0.0479736328125,-4.08935546875,-7.8125,-47.18017578125 1168 | 309,0.0533447265625,-0.661865234375,0.140380859375,0.732421875,-13.61083984375,-42.1142578125 1169 | 309,0.0533447265625,-0.661865234375,0.140380859375,0.732421875,-13.61083984375,-42.1142578125 1170 | 324,0.0533447265625,-0.661865234375,0.140380859375,0.732421875,-13.61083984375,-42.1142578125 1171 | 324,0.0533447265625,-0.661865234375,0.140380859375,0.732421875,-13.61083984375,-42.1142578125 1172 | 324,0.0533447265625,-0.661865234375,0.140380859375,-11.90185546875,-22.216796875,-40.52734375 1173 | 324,-0.2073974609375,-1.5909423828125,0.946044921875,-11.90185546875,-22.216796875,-40.52734375 1174 | 324,-0.2073974609375,-1.5909423828125,0.946044921875,-11.90185546875,-22.216796875,-40.52734375 1175 | 324,-0.2073974609375,-1.5909423828125,0.946044921875,-11.90185546875,-22.216796875,-40.52734375 1176 | 324,-0.2073974609375,-1.5909423828125,0.946044921875,-11.90185546875,-22.216796875,-40.52734375 1177 | 324,-0.2073974609375,-1.5909423828125,0.946044921875,-3.23486328125,-31.18896484375,19.1650390625 1178 | 324,1.210693359375,-3.2718505859375,0.0791015625,-3.23486328125,-31.18896484375,19.1650390625 1179 | 397,1.210693359375,-3.2718505859375,0.0791015625,-3.23486328125,-31.18896484375,19.1650390625 1180 | 397,1.210693359375,-3.2718505859375,0.0791015625,-3.23486328125,-31.18896484375,19.1650390625 1181 | 397,1.210693359375,-3.2718505859375,0.0791015625,-3.23486328125,-31.18896484375,19.1650390625 1182 | 397,1.210693359375,-3.2718505859375,0.0791015625,-78.18603515625,19.775390625,77.08740234375 1183 | 397,1.006591796875,-3.559814453125,0.6142578125,-78.18603515625,19.775390625,77.08740234375 1184 | 397,1.006591796875,-3.559814453125,0.6142578125,-78.18603515625,19.775390625,77.08740234375 1185 | 397,1.006591796875,-3.559814453125,0.6142578125,-78.18603515625,19.775390625,77.08740234375 1186 | 397,1.006591796875,-3.559814453125,0.6142578125,-78.18603515625,19.775390625,77.08740234375 1187 | 397,1.006591796875,-3.559814453125,0.6142578125,-35.888671875,81.1767578125,125.30517578125 1188 | 397,0.0933837890625,-2.941162109375,2.182861328125,-35.888671875,81.1767578125,125.30517578125 1189 | 488,0.0933837890625,-2.941162109375,2.182861328125,-35.888671875,81.1767578125,125.30517578125 1190 | 488,0.0933837890625,-2.941162109375,2.182861328125,-35.888671875,81.1767578125,125.30517578125 1191 | 488,0.0933837890625,-2.941162109375,2.182861328125,-35.888671875,81.1767578125,125.30517578125 1192 | 488,0.0933837890625,-2.941162109375,2.182861328125,-34.48486328125,35.0341796875,101.13525390625 1193 | 488,0.7093505859375,-1.820556640625,1.8167724609375,-34.48486328125,35.0341796875,101.13525390625 1194 | 488,-3.9671630859375,2.0101318359375,0.9407958984375,27.28271484375,40.10009765625,139.5263671875 1195 | 488,-3.9671630859375,2.0101318359375,0.9407958984375,27.28271484375,40.10009765625,139.5263671875 1196 | 488,-3.564453125,1.947998046875,-0.279296875,77.45361328125,70.556640625,315.85693359375 1197 | 488,-3.564453125,1.947998046875,-0.279296875,77.45361328125,70.556640625,315.85693359375 1198 | 488,-3.564453125,1.947998046875,-0.279296875,77.45361328125,70.556640625,315.85693359375 1199 | 460,-3.564453125,1.947998046875,-0.279296875,77.45361328125,70.556640625,315.85693359375 1200 | 460,-3.564453125,1.947998046875,-0.279296875,77.45361328125,70.556640625,315.85693359375 1201 | 460,-2.414794921875,0.859619140625,-0.9644775390625,58.349609375,115.8447265625,447.20458984375 1202 | 460,-2.414794921875,0.859619140625,-0.9644775390625,58.349609375,115.8447265625,447.20458984375 1203 | 460,-2.414794921875,0.859619140625,-0.9644775390625,58.349609375,115.8447265625,447.20458984375 1204 | 460,-2.414794921875,0.859619140625,-0.9644775390625,58.349609375,115.8447265625,447.20458984375 1205 | 460,-2.414794921875,0.859619140625,-0.9644775390625,58.349609375,115.8447265625,447.20458984375 1206 | 460,-1.188720703125,0.78173828125,-0.990478515625,32.40966796875,146.66748046875,518.798828125 1207 | 460,-1.188720703125,0.78173828125,-0.990478515625,32.40966796875,146.66748046875,518.798828125 1208 | 460,-1.188720703125,0.78173828125,-0.990478515625,32.40966796875,146.66748046875,518.798828125 1209 | 383,-1.188720703125,0.78173828125,-0.990478515625,32.40966796875,146.66748046875,518.798828125 1210 | 383,-1.188720703125,0.78173828125,-0.990478515625,32.40966796875,146.66748046875,518.798828125 1211 | 383,-0.18701171875,0.9354248046875,-0.80078125,35.33935546875,162.2314453125,562.744140625 1212 | 383,-0.18701171875,0.9354248046875,-0.80078125,35.33935546875,162.2314453125,562.744140625 1213 | 383,-0.18701171875,0.9354248046875,-0.80078125,35.33935546875,162.2314453125,562.744140625 1214 | 383,-0.18701171875,0.9354248046875,-0.80078125,35.33935546875,162.2314453125,562.744140625 1215 | 383,-0.18701171875,0.9354248046875,-0.80078125,35.33935546875,162.2314453125,562.744140625 1216 | 383,0.6666259765625,0.38671875,-0.806884765625,0.8544921875,158.50830078125,555.17578125 1217 | 383,0.6666259765625,0.38671875,-0.806884765625,0.8544921875,158.50830078125,555.17578125 1218 | 383,0.6666259765625,0.38671875,-0.806884765625,0.8544921875,158.50830078125,555.17578125 1219 | 337,0.6666259765625,0.38671875,-0.806884765625,0.8544921875,158.50830078125,555.17578125 1220 | 337,0.6666259765625,0.38671875,-0.806884765625,0.8544921875,158.50830078125,555.17578125 1221 | 337,3.326171875,-0.210693359375,0.688232421875,-24.23095703125,-73.3642578125,-274.84130859375 1222 | 337,3.326171875,-0.210693359375,0.688232421875,-24.23095703125,-73.3642578125,-274.84130859375 1223 | 337,3.326171875,-0.210693359375,0.688232421875,-24.23095703125,-73.3642578125,-274.84130859375 1224 | 337,3.326171875,-0.210693359375,0.688232421875,-24.23095703125,-73.3642578125,-274.84130859375 1225 | 337,3.326171875,-0.210693359375,0.688232421875,-24.23095703125,-73.3642578125,-274.84130859375 1226 | 337,2.0472412109375,-1.070556640625,0.529541015625,-7.14111328125,-87.09716796875,-357.23876953125 1227 | 337,2.0472412109375,-1.070556640625,0.529541015625,-7.14111328125,-87.09716796875,-357.23876953125 1228 | 337,2.0472412109375,-1.070556640625,0.529541015625,-7.14111328125,-87.09716796875,-357.23876953125 1229 | 365,2.0472412109375,-1.070556640625,0.529541015625,-7.14111328125,-87.09716796875,-357.23876953125 1230 | 365,2.0472412109375,-1.070556640625,0.529541015625,-7.14111328125,-87.09716796875,-357.23876953125 1231 | 365,0.724609375,-1.1143798828125,0.610595703125,-6.9580078125,-101.806640625,-395.751953125 1232 | 365,0.724609375,-1.1143798828125,0.610595703125,-6.9580078125,-101.806640625,-395.751953125 1233 | 365,0.724609375,-1.1143798828125,0.610595703125,-6.9580078125,-101.806640625,-395.751953125 1234 | 365,0.724609375,-1.1143798828125,0.610595703125,-6.9580078125,-101.806640625,-395.751953125 1235 | 365,0.724609375,-1.1143798828125,0.610595703125,-6.9580078125,-101.806640625,-395.751953125 1236 | 365,-0.181640625,-1.0712890625,0.840087890625,0.67138671875,-115.90576171875,-401.67236328125 1237 | 365,-0.181640625,-1.0712890625,0.840087890625,0.67138671875,-115.90576171875,-401.67236328125 1238 | 365,-0.181640625,-1.0712890625,0.840087890625,0.67138671875,-115.90576171875,-401.67236328125 1239 | 365,,,,,, 1240 | 344,,,,,, 1241 | 344,,,,,, 1242 | 344,,,,,, 1243 | 344,,,,,, 1244 | 344,,,,,, 1245 | 344,,,,,, 1246 | 344,,,,,, 1247 | 344,,,,,, 1248 | 344,,,,,, 1249 | 273,,,,,, 1250 | 273,,,,,, 1251 | 273,,,,,, 1252 | 273,,,,,, 1253 | 273,,,,,, 1254 | 273,,,,,, 1255 | 273,,,,,, 1256 | 273,,,,,, 1257 | 273,,,,,, 1258 | 273,,,,,, 1259 | 132,,,,,, 1260 | 132,,,,,, 1261 | 132,,,,,, 1262 | 132,,,,,, 1263 | 132,,,,,, 1264 | 132,,,,,, 1265 | 132,,,,,, 1266 | 132,,,,,, 1267 | 132,,,,,, 1268 | 132,,,,,, 1269 | 35,,,,,, 1270 | 35,,,,,, 1271 | 35,,,,,, 1272 | 35,,,,,, 1273 | 35,,,,,, 1274 | 35,,,,,, 1275 | 35,,,,,, 1276 | 35,,,,,, 1277 | 35,,,,,, 1278 | 35,,,,,, 1279 | 25,,,,,, 1280 | 25,,,,,, 1281 | 25,,,,,, 1282 | 25,,,,,, 1283 | 25,,,,,, 1284 | 25,,,,,, 1285 | 25,,,,,, 1286 | 25,,,,,, 1287 | 25,,,,,, 1288 | 25,,,,,, 1289 | 24,,,,,, 1290 | 24,,,,,, 1291 | 24,,,,,, 1292 | 24,,,,,, 1293 | 24,,,,,, 1294 | 24,,,,,, 1295 | 24,,,,,, 1296 | 24,,,,,, 1297 | 24,,,,,, 1298 | 24,,,,,, 1299 | 25,,,,,, 1300 | 25,,,,,, 1301 | 25,,,,,, 1302 | 25,,,,,, 1303 | 25,,,,,, 1304 | 25,,,,,, 1305 | 25,,,,,, 1306 | 25,,,,,, 1307 | 25,,,,,, 1308 | 25,,,,,, 1309 | 25,,,,,, 1310 | 24,,,,,, 1311 | 24,,,,,, 1312 | 24,,,,,, 1313 | 24,,,,,, 1314 | 24,,,,,, 1315 | 24,,,,,, 1316 | 24,,,,,, 1317 | 24,,,,,, 1318 | 24,,,,,, 1319 | 24,,,,,, 1320 | 24,,,,,, 1321 | 24,,,,,, 1322 | 24,,,,,, 1323 | 24,,,,,, 1324 | 24,,,,,, 1325 | 24,,,,,, 1326 | 24,,,,,, 1327 | 24,,,,,, 1328 | 24,,,,,, 1329 | 24,,,,,, 1330 | 24,,,,,, 1331 | 24,,,,,, 1332 | 24,,,,,, 1333 | 24,,,,,, 1334 | 24,,,,,, 1335 | 24,,,,,, 1336 | 24,,,,,, 1337 | 24,,,,,, 1338 | 24,,,,,, 1339 | 24,,,,,, 1340 | 24,,,,,, 1341 | 24,,,,,, 1342 | 24,,,,,, 1343 | 24,,,,,, 1344 | 24,,,,,, 1345 | 24,,,,,, 1346 | 24,,,,,, 1347 | 24,,,,,, 1348 | 24,,,,,, 1349 | 24,,,,,, 1350 | 24,,,,,, 1351 | 24,,,,,, 1352 | 24,,,,,, 1353 | 24,,,,,, 1354 | 24,,,,,, 1355 | 24,,,,,, 1356 | 24,,,,,, 1357 | 24,,,,,, 1358 | 24,,,,,, 1359 | 23,,,,,, 1360 | 23,,,,,, 1361 | 23,,,,,, 1362 | 23,,,,,, 1363 | 23,,,,,, 1364 | 23,,,,,, 1365 | 23,,,,,, 1366 | 23,,,,,, 1367 | 23,,,,,, 1368 | 23,,,,,, 1369 | 23,,,,,, 1370 | 23,,,,,, 1371 | 23,,,,,, 1372 | 23,,,,,, 1373 | 23,,,,,, 1374 | 23,,,,,, 1375 | 23,,,,,, 1376 | 23,,,,,, 1377 | 23,,,,,, 1378 | 23,,,,,, 1379 | 23,,,,,, 1380 | 22,,,,,, 1381 | 22,,,,,, 1382 | 22,,,,,, 1383 | 22,,,,,, 1384 | 22,,,,,, 1385 | 22,,,,,, 1386 | 22,,,,,, 1387 | 22,,,,,, 1388 | 22,,,,,, 1389 | 21,,,,,, 1390 | 21,,,,,, 1391 | 21,,,,,, 1392 | 21,,,,,, 1393 | 21,,,,,, 1394 | 21,,,,,, 1395 | 21,,,,,, 1396 | 21,,,,,, 1397 | 21,,,,,, 1398 | 21,,,,,, 1399 | 21,,,,,, 1400 | 21,,,,,, 1401 | 21,,,,,, 1402 | 21,,,,,, 1403 | 21,,,,,, 1404 | 21,,,,,, 1405 | 21,,,,,, 1406 | 21,,,,,, 1407 | 21,,,,,, 1408 | 21,,,,,, 1409 | 416,,,,,, 1410 | 416,,,,,, 1411 | 416,,,,,, 1412 | 416,,,,,, 1413 | 416,,,,,, 1414 | 416,,,,,, 1415 | 416,,,,,, 1416 | 416,,,,,, 1417 | 416,,,,,, 1418 | 416,,,,,, 1419 | 294,,,,,, 1420 | 294,,,,,, 1421 | 294,,,,,, 1422 | 294,,,,,, 1423 | 294,,,,,, 1424 | 294,,,,,, 1425 | 294,,,,,, 1426 | 294,,,,,, 1427 | 294,,,,,, 1428 | 294,,,,,, 1429 | 420,,,,,, 1430 | 420,,,,,, 1431 | 420,,,,,, 1432 | 420,,,,,, 1433 | 420,,,,,, 1434 | 420,,,,,, 1435 | 420,,,,,, 1436 | 420,,,,,, 1437 | 420,,,,,, 1438 | 420,,,,,, 1439 | 548,,,,,, 1440 | 548,,,,,, 1441 | 548,,,,,, 1442 | 548,,,,,, 1443 | 548,,,,,, 1444 | 548,,,,,, 1445 | 548,,,,,, 1446 | 548,,,,,, 1447 | 548,,,,,, 1448 | 548,,,,,, 1449 | 548,,,,,, 1450 | 598,,,,,, 1451 | 598,,,,,, 1452 | 598,,,,,, 1453 | 598,,,,,, 1454 | 598,,,,,, 1455 | 598,,,,,, 1456 | 598,,,,,, 1457 | 598,,,,,, 1458 | 598,,,,,, 1459 | 557,,,,,, 1460 | 557,,,,,, 1461 | 557,,,,,, 1462 | 557,,,,,, 1463 | 557,,,,,, 1464 | 557,,,,,, 1465 | 557,,,,,, 1466 | 557,,,,,, 1467 | 557,,,,,, 1468 | 557,,,,,, 1469 | 470,,,,,, 1470 | 470,,,,,, 1471 | 470,,,,,, 1472 | 470,,,,,, 1473 | 470,,,,,, 1474 | 470,,,,,, 1475 | 470,,,,,, 1476 | 470,,,,,, 1477 | 470,,,,,, 1478 | 470,,,,,, 1479 | 374,,,,,, 1480 | 374,,,,,, 1481 | 374,,,,,, 1482 | 374,,,,,, 1483 | 374,,,,,, 1484 | 374,,,,,, 1485 | 374,,,,,, 1486 | 374,,,,,, 1487 | 374,,,,,, 1488 | 374,,,,,, 1489 | 352,,,,,, 1490 | 352,,,,,, 1491 | 352,,,,,, 1492 | 352,,,,,, 1493 | 352,,,,,, 1494 | 352,,,,,, 1495 | 352,,,,,, 1496 | 352,,,,,, 1497 | 352,,,,,, 1498 | 352,,,,,, 1499 | 364,,,,,, 1500 | 364,,,,,, 1501 | 364,,,,,, 1502 | 364,,,,,, 1503 | 364,,,,,, 1504 | 364,,,,,, 1505 | 364,,,,,, 1506 | 364,,,,,, 1507 | 364,,,,,, 1508 | 364,,,,,, 1509 | 363,,,,,, 1510 | 363,,,,,, 1511 | 363,,,,,, 1512 | 363,,,,,, 1513 | 363,,,,,, 1514 | 363,,,,,, 1515 | 363,,,,,, 1516 | 363,,,,,, 1517 | 363,,,,,, 1518 | 363,,,,,, 1519 | 363,,,,,, 1520 | 462,,,,,, 1521 | 462,,,,,, 1522 | 462,,,,,, 1523 | 462,,,,,, 1524 | 462,,,,,, 1525 | 462,,,,,, 1526 | 462,,,,,, 1527 | 462,,,,,, 1528 | 462,,,,,, 1529 | 526,,,,,, 1530 | 526,,,,,, 1531 | 526,,,,,, 1532 | 526,,,,,, 1533 | 526,,,,,, 1534 | 526,,,,,, 1535 | 526,,,,,, 1536 | 526,,,,,, 1537 | 526,,,,,, 1538 | 526,,,,,, 1539 | 477,,,,,, 1540 | 477,,,,,, 1541 | 477,,,,,, 1542 | 477,,,,,, 1543 | 477,,,,,, 1544 | 477,,,,,, 1545 | 477,,,,,, 1546 | 477,,,,,, 1547 | 477,,,,,, 1548 | 477,,,,,, 1549 | 411,,,,,, 1550 | 411,,,,,, 1551 | 411,,,,,, 1552 | 411,,,,,, 1553 | 411,,,,,, 1554 | 411,,,,,, 1555 | 411,,,,,, 1556 | 411,,,,,, 1557 | 411,,,,,, 1558 | 411,,,,,, 1559 | 341,,,,,, 1560 | 341,,,,,, 1561 | 341,,,,,, 1562 | 341,,,,,, 1563 | 341,,,,,, 1564 | 341,,,,,, 1565 | 341,,,,,, 1566 | 341,,,,,, 1567 | 341,,,,,, 1568 | 341,,,,,, 1569 | 230,,,,,, 1570 | 230,,,,,, 1571 | 230,,,,,, 1572 | 230,,,,,, 1573 | 230,,,,,, 1574 | 230,,,,,, 1575 | 230,,,,,, 1576 | 230,,,,,, 1577 | 230,,,,,, 1578 | 230,,,,,, 1579 | 144,,,,,, 1580 | 144,,,,,, 1581 | 144,,,,,, 1582 | 144,,,,,, 1583 | 144,,,,,, 1584 | 144,,,,,, 1585 | 144,,,,,, 1586 | 144,,,,,, 1587 | 144,,,,,, 1588 | 144,,,,,, 1589 | 144,,,,,, 1590 | 169,,,,,, 1591 | 169,,,,,, 1592 | 169,,,,,, 1593 | 169,,,,,, 1594 | 169,,,,,, 1595 | 169,,,,,, 1596 | 169,,,,,, 1597 | 169,,,,,, 1598 | 169,,,,,, 1599 | 188,,,,,, 1600 | 188,,,,,, 1601 | 188,,,,,, 1602 | 188,,,,,, 1603 | 188,,,,,, 1604 | 188,,,,,, 1605 | 188,,,,,, 1606 | 188,,,,,, 1607 | 188,,,,,, 1608 | 188,,,,,, 1609 | 31,,,,,, 1610 | 31,,,,,, 1611 | 31,,,,,, 1612 | 31,,,,,, 1613 | 31,,,,,, 1614 | 31,,,,,, 1615 | 31,,,,,, 1616 | 31,,,,,, 1617 | 31,,,,,, 1618 | 31,,,,,, 1619 | 26,,,,,, 1620 | 26,,,,,, 1621 | 26,,,,,, 1622 | 26,,,,,, 1623 | 26,,,,,, 1624 | 26,,,,,, 1625 | 26,,,,,, 1626 | 26,,,,,, 1627 | 26,,,,,, 1628 | 26,,,,,, 1629 | 24,,,,,, 1630 | 24,,,,,, 1631 | 24,,,,,, 1632 | 24,,,,,, 1633 | 24,,,,,, 1634 | 24,,,,,, 1635 | 24,,,,,, 1636 | 24,,,,,, 1637 | 24,,,,,, 1638 | 24,,,,,, 1639 | 24,,,,,, 1640 | 24,,,,,, 1641 | 24,,,,,, 1642 | 24,,,,,, 1643 | 24,,,,,, 1644 | 24,,,,,, 1645 | 24,,,,,, 1646 | 24,,,,,, 1647 | 24,,,,,, 1648 | 24,,,,,, 1649 | 24,,,,,, 1650 | 24,,,,,, 1651 | 24,,,,,, 1652 | 24,,,,,, 1653 | 24,,,,,, 1654 | 24,,,,,, 1655 | 24,,,,,, 1656 | 24,,,,,, 1657 | 24,,,,,, 1658 | 24,,,,,, 1659 | 24,,,,,, 1660 | 25,,,,,, 1661 | 25,,,,,, 1662 | 25,,,,,, 1663 | 25,,,,,, 1664 | 25,,,,,, 1665 | 25,,,,,, 1666 | 25,,,,,, 1667 | 25,,,,,, 1668 | 25,,,,,, 1669 | 24,,,,,, 1670 | 24,,,,,, 1671 | 24,,,,,, 1672 | 24,,,,,, 1673 | 24,,,,,, 1674 | 24,,,,,, 1675 | 24,,,,,, 1676 | 24,,,,,, 1677 | 24,,,,,, 1678 | 24,,,,,, 1679 | 23,,,,,, 1680 | 23,,,,,, 1681 | 23,,,,,, 1682 | 23,,,,,, 1683 | 23,,,,,, 1684 | 23,,,,,, 1685 | 23,,,,,, 1686 | 23,,,,,, 1687 | 23,,,,,, 1688 | 23,,,,,, 1689 | 23,,,,,, 1690 | 23,,,,,, 1691 | 23,,,,,, 1692 | 23,,,,,, 1693 | 23,,,,,, 1694 | 23,,,,,, 1695 | 23,,,,,, 1696 | 23,,,,,, 1697 | 23,,,,,, 1698 | 23,,,,,, 1699 | 23,,,,,, 1700 | 23,,,,,, 1701 | 23,,,,,, 1702 | 23,,,,,, 1703 | 23,,,,,, 1704 | 23,,,,,, 1705 | 23,,,,,, 1706 | 23,,,,,, 1707 | 23,,,,,, 1708 | 23,,,,,, 1709 | 23,,,,,, 1710 | 23,,,,,, 1711 | 23,,,,,, 1712 | 23,,,,,, 1713 | 23,,,,,, 1714 | 23,,,,,, 1715 | 23,,,,,, 1716 | 23,,,,,, 1717 | 23,,,,,, 1718 | 23,,,,,, 1719 | 307,,,,,, 1720 | 307,,,,,, 1721 | 307,,,,,, 1722 | 307,,,,,, 1723 | 307,,,,,, 1724 | 307,,,,,, 1725 | 307,,,,,, 1726 | 307,,,,,, 1727 | 307,,,,,, 1728 | 307,,,,,, 1729 | 229,,,,,, 1730 | 229,,,,,, 1731 | 229,,,,,, 1732 | 229,,,,,, 1733 | 229,,,,,, 1734 | 229,,,,,, 1735 | 229,,,,,, 1736 | 229,,,,,, 1737 | 229,,,,,, 1738 | 229,,,,,, 1739 | 71,,,,,, 1740 | 71,,,,,, 1741 | 71,,,,,, 1742 | 71,,,,,, 1743 | 71,,,,,, 1744 | 71,,,,,, 1745 | 71,,,,,, 1746 | 71,,,,,, 1747 | 71,,,,,, 1748 | 71,,,,,, 1749 | 203,,,,,, 1750 | 203,,,,,, 1751 | 203,,,,,, 1752 | 203,,,,,, 1753 | 203,,,,,, 1754 | 203,,,,,, 1755 | 203,,,,,, 1756 | 203,,,,,, 1757 | 203,,,,,, 1758 | 203,,,,,, 1759 | 219,,,,,, 1760 | 219,,,,,, 1761 | 219,,,,,, 1762 | 219,,,,,, 1763 | 219,,,,,, 1764 | 219,,,,,, 1765 | 219,,,,,, 1766 | 219,,,,,, 1767 | 219,,,,,, 1768 | 219,,,,,, 1769 | 293,,,,,, 1770 | 293,,,,,, 1771 | 293,,,,,, 1772 | 293,,,,,, 1773 | 293,,,,,, 1774 | 293,,,,,, 1775 | 293,,,,,, 1776 | 293,,,,,, 1777 | 293,,,,,, 1778 | 293,,,,,, 1779 | 363,,,,,, 1780 | 363,,,,,, 1781 | 363,,,,,, 1782 | 363,,,,,, 1783 | 363,,,,,, 1784 | 363,,,,,, 1785 | 363,,,,,, 1786 | 363,,,,,, 1787 | 363,,,,,, 1788 | 363,,,,,, 1789 | 355,,,,,, 1790 | 355,,,,,, 1791 | 355,,,,,, 1792 | 355,,,,,, 1793 | 355,,,,,, 1794 | 355,,,,,, 1795 | 355,,,,,, 1796 | 355,,,,,, 1797 | 355,,,,,, 1798 | 355,,,,,, 1799 | 342,,,,,, 1800 | 342,,,,,, 1801 | 342,,,,,, 1802 | 342,,,,,, 1803 | 342,,,,,, 1804 | 342,,,,,, 1805 | 342,,,,,, 1806 | 342,,,,,, 1807 | 342,,,,,, 1808 | 342,,,,,, 1809 | 288,,,,,, 1810 | 288,,,,,, 1811 | 288,,,,,, 1812 | 288,,,,,, 1813 | 288,,,,,, 1814 | 288,,,,,, 1815 | 288,,,,,, 1816 | 288,,,,,, 1817 | 288,,,,,, 1818 | 288,,,,,, 1819 | 253,,,,,, 1820 | 253,,,,,, 1821 | 253,,,,,, 1822 | 253,,,,,, 1823 | 253,,,,,, 1824 | 253,,,,,, 1825 | 253,,,,,, 1826 | 253,,,,,, 1827 | 253,,,,,, 1828 | 253,,,,,, 1829 | 239,,,,,, 1830 | 239,,,,,, 1831 | 239,,,,,, 1832 | 239,,,,,, 1833 | 239,,,,,, 1834 | 239,,,,,, 1835 | 239,,,,,, 1836 | 239,,,,,, 1837 | 239,,,,,, 1838 | 239,,,,,, 1839 | 238,,,,,, 1840 | 238,,,,,, 1841 | 238,,,,,, 1842 | 238,,,,,, 1843 | 238,,,,,, 1844 | 238,,,,,, 1845 | 238,,,,,, 1846 | 238,,,,,, 1847 | 238,,,,,, 1848 | 238,,,,,, 1849 | 271,,,,,, 1850 | 271,,,,,, 1851 | 271,,,,,, 1852 | 271,,,,,, 1853 | 271,,,,,, 1854 | 271,,,,,, 1855 | 271,,,,,, 1856 | 271,,,,,, 1857 | 271,,,,,, 1858 | 271,,,,,, 1859 | 320,,,,,, 1860 | 320,,,,,, 1861 | 320,,,,,, 1862 | 320,,,,,, 1863 | 320,,,,,, 1864 | 320,,,,,, 1865 | 320,,,,,, 1866 | 320,,,,,, 1867 | 320,,,,,, 1868 | 344,,,,,, 1869 | 344,,,,,, 1870 | 344,,,,,, 1871 | 344,,,,,, 1872 | 344,,,,,, 1873 | 344,,,,,, 1874 | 344,,,,,, 1875 | 344,,,,,, 1876 | 344,,,,,, 1877 | 344,,,,,, 1878 | 344,,,,,, 1879 | 331,,,,,, 1880 | 331,,,,,, 1881 | 331,,,,,, 1882 | 331,,,,,, 1883 | 331,,,,,, 1884 | 331,,,,,, 1885 | 331,,,,,, 1886 | 331,,,,,, 1887 | 331,,,,,, 1888 | 331,,,,,, 1889 | 300,,,,,, 1890 | 300,,,,,, 1891 | 300,,,,,, 1892 | 300,,,,,, 1893 | 300,,,,,, 1894 | 300,,,,,, 1895 | 300,,,,,, 1896 | 300,,,,,, 1897 | 300,,,,,, 1898 | 300,,,,,, 1899 | 280,,,,,, 1900 | 280,,,,,, 1901 | 280,,,,,, 1902 | 280,,,,,, 1903 | 280,,,,,, 1904 | 280,,,,,, 1905 | 280,,,,,, 1906 | 280,,,,,, 1907 | 280,,,,,, 1908 | 280,,,,,, 1909 | 246,,,,,, 1910 | 246,,,,,, 1911 | 246,,,,,, 1912 | 246,,,,,, 1913 | 246,,,,,, 1914 | 246,,,,,, 1915 | 246,,,,,, 1916 | 246,,,,,, 1917 | 246,,,,,, 1918 | 246,,,,,, 1919 | 169,,,,,, 1920 | 169,,,,,, 1921 | 169,,,,,, 1922 | 169,,,,,, 1923 | 169,,,,,, 1924 | 169,,,,,, 1925 | 169,,,,,, 1926 | 169,,,,,, 1927 | 169,,,,,, 1928 | 169,,,,,, 1929 | 153,,,,,, 1930 | 153,,,,,, 1931 | 153,,,,,, 1932 | 153,,,,,, 1933 | 153,,,,,, 1934 | 153,,,,,, 1935 | 153,,,,,, 1936 | 153,,,,,, 1937 | 153,,,,,, 1938 | 153,,,,,, 1939 | 153,,,,,, 1940 | 76,,,,,, 1941 | 76,,,,,, 1942 | 76,,,,,, 1943 | 76,,,,,, 1944 | 76,,,,,, 1945 | 76,,,,,, 1946 | 76,,,,,, 1947 | 76,,,,,, 1948 | 76,,,,,, 1949 | 38,,,,,, 1950 | 38,,,,,, 1951 | 38,,,,,, 1952 | 38,,,,,, 1953 | 38,,,,,, 1954 | 38,,,,,, 1955 | 38,,,,,, 1956 | 38,,,,,, 1957 | 38,,,,,, 1958 | 38,,,,,, 1959 | 33,,,,,, 1960 | 33,,,,,, 1961 | 33,,,,,, 1962 | 33,,,,,, 1963 | 33,,,,,, 1964 | 33,,,,,, 1965 | 33,,,,,, 1966 | 33,,,,,, 1967 | 33,,,,,, 1968 | 33,,,,,, 1969 | 33,,,,,, 1970 | 33,,,,,, 1971 | 33,,,,,, 1972 | 33,,,,,, 1973 | 33,,,,,, 1974 | 33,,,,,, 1975 | 33,,,,,, 1976 | 33,,,,,, 1977 | 33,,,,,, 1978 | 33,,,,,, 1979 | 32,,,,,, 1980 | 32,,,,,, 1981 | 32,,,,,, 1982 | 32,,,,,, 1983 | 32,,,,,, 1984 | 32,,,,,, 1985 | 32,,,,,, 1986 | 32,,,,,, 1987 | 32,,,,,, 1988 | 32,,,,,, 1989 | 30,,,,,, 1990 | 30,,,,,, 1991 | 30,,,,,, 1992 | 30,,,,,, 1993 | 30,,,,,, 1994 | 30,,,,,, 1995 | 30,,,,,, 1996 | 30,,,,,, 1997 | 30,,,,,, 1998 | 30,,,,,, 1999 | 30,,,,,, 2000 | 30,,,,,, 2001 | 30,,,,,, 2002 | 30,,,,,, 2003 | 30,,,,,, 2004 | 30,,,,,, 2005 | 30,,,,,, 2006 | 30,,,,,, 2007 | 30,,,,,, 2008 | 30,,,,,, 2009 | 30,,,,,, 2010 | 29,,,,,, 2011 | 29,,,,,, 2012 | 29,,,,,, 2013 | 29,,,,,, 2014 | 29,,,,,, 2015 | 29,,,,,, 2016 | 29,,,,,, 2017 | 29,,,,,, 2018 | 29,,,,,, 2019 | 28,,,,,, 2020 | 28,,,,,, 2021 | 28,,,,,, 2022 | 28,,,,,, 2023 | 28,,,,,, 2024 | 28,,,,,, 2025 | 28,,,,,, 2026 | 28,,,,,, 2027 | 28,,,,,, 2028 | 28,,,,,, 2029 | 27,,,,,, 2030 | 27,,,,,, 2031 | 27,,,,,, 2032 | 27,,,,,, 2033 | 27,,,,,, 2034 | 27,,,,,, 2035 | 27,,,,,, 2036 | 27,,,,,, 2037 | 27,,,,,, 2038 | 27,,,,,, 2039 | 27,,,,,, 2040 | 27,,,,,, 2041 | 27,,,,,, 2042 | 27,,,,,, 2043 | 27,,,,,, 2044 | 27,,,,,, 2045 | 27,,,,,, 2046 | 27,,,,,, 2047 | 27,,,,,, 2048 | 27,,,,,, 2049 | 26,,,,,, 2050 | 26,,,,,, 2051 | 26,,,,,, 2052 | 26,,,,,, 2053 | 26,,,,,, 2054 | 26,,,,,, 2055 | 26,,,,,, 2056 | 26,,,,,, 2057 | 26,,,,,, 2058 | 26,,,,,, 2059 | 100,,,,,, 2060 | 100,,,,,, 2061 | 100,,,,,, 2062 | 100,,,,,, 2063 | 100,,,,,, 2064 | 100,,,,,, 2065 | 100,,,,,, 2066 | 100,,,,,, 2067 | 100,,,,,, 2068 | 100,,,,,, 2069 | 151,,,,,, 2070 | 151,,,,,, 2071 | 151,,,,,, 2072 | 151,,,,,, 2073 | 151,,,,,, 2074 | 151,,,,,, 2075 | 151,,,,,, 2076 | 151,,,,,, 2077 | 151,,,,,, 2078 | 151,,,,,, 2079 | 151,,,,,, 2080 | 130,,,,,, 2081 | 130,,,,,, 2082 | 130,,,,,, 2083 | 130,,,,,, 2084 | 130,,,,,, 2085 | 130,,,,,, 2086 | 130,,,,,, 2087 | 130,,,,,, 2088 | 130,,,,,, 2089 | 225,,,,,, 2090 | 225,,,,,, 2091 | 225,,,,,, 2092 | 225,,,,,, 2093 | 225,,,,,, 2094 | 225,,,,,, 2095 | 225,,,,,, 2096 | 225,,,,,, 2097 | 225,,,,,, 2098 | 225,,,,,, 2099 | 262,,,,,, 2100 | 262,,,,,, 2101 | 262,,,,,, 2102 | 262,,,,,, 2103 | 262,,,,,, 2104 | 262,,,,,, 2105 | 262,,,,,, 2106 | 262,,,,,, 2107 | 262,,,,,, 2108 | 262,,,,,, 2109 | 303,,,,,, 2110 | 303,,,,,, 2111 | 303,,,,,, 2112 | 303,,,,,, 2113 | 303,,,,,, 2114 | 303,,,,,, 2115 | 303,,,,,, 2116 | 303,,,,,, 2117 | 303,,,,,, 2118 | 303,,,,,, 2119 | 342,,,,,, 2120 | 342,,,,,, 2121 | 342,,,,,, 2122 | 342,,,,,, 2123 | 342,,,,,, 2124 | 342,,,,,, 2125 | 342,,,,,, 2126 | 342,,,,,, 2127 | 342,,,,,, 2128 | 342,,,,,, 2129 | 354,,,,,, 2130 | 354,,,,,, 2131 | 354,,,,,, 2132 | 354,,,,,, 2133 | 354,,,,,, 2134 | 354,,,,,, 2135 | 354,,,,,, 2136 | 354,,,,,, 2137 | 354,,,,,, 2138 | 354,,,,,, 2139 | 338,,,,,, 2140 | 338,,,,,, 2141 | 338,,,,,, 2142 | 338,,,,,, 2143 | 338,,,,,, 2144 | 338,,,,,, 2145 | 338,,,,,, 2146 | 338,,,,,, 2147 | 338,,,,,, 2148 | 338,,,,,, 2149 | 338,,,,,, 2150 | 287,,,,,, 2151 | 287,,,,,, 2152 | 287,,,,,, 2153 | 287,,,,,, 2154 | 287,,,,,, 2155 | 287,,,,,, 2156 | 287,,,,,, 2157 | 287,,,,,, 2158 | 287,,,,,, 2159 | 241,,,,,, 2160 | 241,,,,,, 2161 | 241,,,,,, 2162 | 241,,,,,, 2163 | 241,,,,,, 2164 | 241,,,,,, 2165 | 241,,,,,, 2166 | 241,,,,,, 2167 | 241,,,,,, 2168 | 241,,,,,, 2169 | 238,,,,,, 2170 | 238,,,,,, 2171 | 238,,,,,, 2172 | 238,,,,,, 2173 | 238,,,,,, 2174 | 238,,,,,, 2175 | 238,,,,,, 2176 | 238,,,,,, 2177 | 238,,,,,, 2178 | 238,,,,,, 2179 | 258,,,,,, 2180 | 258,,,,,, 2181 | 258,,,,,, 2182 | 258,,,,,, 2183 | 258,,,,,, 2184 | 258,,,,,, 2185 | 258,,,,,, 2186 | 258,,,,,, 2187 | 258,,,,,, 2188 | 258,,,,,, 2189 | 313,,,,,, 2190 | 313,,,,,, 2191 | 313,,,,,, 2192 | 313,,,,,, 2193 | 313,,,,,, 2194 | 313,,,,,, 2195 | 313,,,,,, 2196 | 313,,,,,, 2197 | 313,,,,,, 2198 | 313,,,,,, 2199 | 358,,,,,, 2200 | 358,,,,,, 2201 | 358,,,,,, 2202 | 358,,,,,, 2203 | 358,,,,,, 2204 | 358,,,,,, 2205 | 358,,,,,, 2206 | 358,,,,,, 2207 | 358,,,,,, 2208 | 358,,,,,, 2209 | 358,,,,,, 2210 | 358,,,,,, 2211 | 358,,,,,, 2212 | 358,,,,,, 2213 | 358,,,,,, 2214 | 358,,,,,, 2215 | 358,,,,,, 2216 | 358,,,,,, 2217 | 358,,,,,, 2218 | 358,,,,,, 2219 | 358,,,,,, 2220 | 323,,,,,, 2221 | 323,,,,,, 2222 | 323,,,,,, 2223 | 323,,,,,, 2224 | 323,,,,,, 2225 | 323,,,,,, 2226 | 323,,,,,, 2227 | 323,,,,,, 2228 | 323,,,,,, 2229 | 290,,,,,, 2230 | 290,,,,,, 2231 | 290,,,,,, 2232 | 290,,,,,, 2233 | 290,,,,,, 2234 | 290,,,,,, 2235 | 290,,,,,, 2236 | 290,,,,,, 2237 | 290,,,,,, 2238 | 290,,,,,, 2239 | 280,,,,,, 2240 | 280,,,,,, 2241 | 280,,,,,, 2242 | 280,,,,,, 2243 | 280,,,,,, 2244 | 280,,,,,, 2245 | 280,,,,,, 2246 | 280,,,,,, 2247 | 280,,,,,, 2248 | 280,,,,,, 2249 | 218,,,,,, 2250 | 218,,,,,, 2251 | 218,,,,,, 2252 | 218,,,,,, 2253 | 218,,,,,, 2254 | 218,,,,,, 2255 | 218,,,,,, 2256 | 218,,,,,, 2257 | 218,,,,,, 2258 | 218,,,,,, 2259 | 155,,,,,, 2260 | 155,,,,,, 2261 | 155,,,,,, 2262 | 155,,,,,, 2263 | 155,,,,,, 2264 | 155,,,,,, 2265 | 155,,,,,, 2266 | 155,,,,,, 2267 | 155,,,,,, 2268 | 155,,,,,, 2269 | 166,,,,,, 2270 | 166,,,,,, 2271 | 166,,,,,, 2272 | 166,,,,,, 2273 | 166,,,,,, 2274 | 166,,,,,, 2275 | 166,,,,,, 2276 | 166,,,,,, 2277 | 166,,,,,, 2278 | 166,,,,,, 2279 | 50,,,,,, 2280 | 50,,,,,, 2281 | 50,,,,,, 2282 | 50,,,,,, 2283 | 50,,,,,, 2284 | 50,,,,,, 2285 | 50,,,,,, 2286 | 50,,,,,, 2287 | 50,,,,,, 2288 | 50,,,,,, 2289 | 50,,,,,, 2290 | 36,,,,,, 2291 | 36,,,,,, 2292 | 36,,,,,, 2293 | 36,,,,,, 2294 | 36,,,,,, 2295 | 36,,,,,, 2296 | 36,,,,,, 2297 | 36,,,,,, 2298 | 36,,,,,, 2299 | 33,,,,,, 2300 | 33,,,,,, 2301 | 33,,,,,, 2302 | 33,,,,,, 2303 | 33,,,,,, 2304 | 33,,,,,, 2305 | 33,,,,,, 2306 | 33,,,,,, 2307 | 33,,,,,, 2308 | 33,,,,,, 2309 | 33,,,,,, 2310 | 33,,,,,, 2311 | 33,,,,,, 2312 | 33,,,,,, 2313 | 33,,,,,, 2314 | 33,,,,,, 2315 | 33,,,,,, 2316 | 33,,,,,, 2317 | 33,,,,,, 2318 | 33,,,,,, 2319 | 32,,,,,, 2320 | 32,,,,,, 2321 | 32,,,,,, 2322 | 32,,,,,, 2323 | 32,,,,,, 2324 | 32,,,,,, 2325 | 32,,,,,, 2326 | 32,,,,,, 2327 | 32,,,,,, 2328 | 32,,,,,, 2329 | 30,,,,,, 2330 | 30,,,,,, 2331 | 30,,,,,, 2332 | 30,,,,,, 2333 | 30,,,,,, 2334 | 30,,,,,, 2335 | 30,,,,,, 2336 | 30,,,,,, 2337 | 30,,,,,, 2338 | 30,,,,,, 2339 | 30,,,,,, 2340 | 30,,,,,, 2341 | -------------------------------------------------------------------------------- /offline/data/info.txt: -------------------------------------------------------------------------------- 1 | dataset collected from raisim, 2 | ATLAS robot locomotion using LIPM locomotion 3 | 4 | Labels for stable contact are produced using coulomb friction model 5 | 6 | ---------------------------------------------- 7 | 8 | GO1_* 9 | 10 | datasets collected for a GO1 quadrupedal robot with IMU measurements moutned on the foot 11 | + force measurement (default sensor) 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /offline/src/atlas_contact_estimation.py: -------------------------------------------------------------------------------- 1 | #! /usr/bin/env python3 2 | ''' 3 | * PCE - Probabilistic Contact Estimator 4 | * 5 | * Copyright 2022-2023 Michael Maravgakis and Despina-Ekaterini Argyropoulos, Foundation for Research and Technology Hellas (FORTH) 6 | * License: BSD 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above copyright 14 | * notice, this list of conditions and the following disclaimer in the 15 | * documentation and/or other materials provided with the distribution. 16 | * * Neither the name of the Foundation for Research and Technology Hellas (FORTH) 17 | * nor the names of its contributors may be used to endorse or promote products derived from 18 | * this software without specific prior written permission. 19 | * 20 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 23 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 24 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 25 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 26 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 27 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 28 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 29 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 30 | * POSSIBILITY OF SUCH DAMAGE. 31 | ''' 32 | 33 | import numpy as np 34 | from numpy import genfromtxt 35 | import matplotlib.pyplot as plt 36 | from sklearn.neighbors import KernelDensity 37 | import time 38 | 39 | 40 | prefix = "../data/" 41 | data_filenames= [prefix+'ATLAS_1000hz_01ground.csv',prefix+"ATLAS_01ground_3steps.csv",prefix+"ATLAS_01ground_003slip.csv" ] 42 | 43 | 44 | class pce: 45 | ''' 46 | Description: 47 | Initializes the contact estimator object 48 | Parameters: 49 | * batch_size (int): The size of the batch of data that the contact probability will be estimated 50 | * eval_samples (int): The number of points to use in order to estimate 51 | * [blank]_std (float): The standard deviation of the error of the measurements 52 | ''' 53 | 54 | def __init__(self): 55 | self.filename = data_filenames[2] 56 | self.batch_size = 50 57 | self.eval_samples = 50 58 | 59 | # Standard deviations 60 | self.ax_std = 0.02467 61 | self.ay_std = 0.02467 62 | self.az_std = 0.02467 63 | self.wx_std = 0.01653 64 | self.wy_std = 0.01653 65 | self.wz_std = 0.01653 66 | 67 | 68 | self.data_batch = np.empty((self.batch_size,6)) # Batch of data to made predictions on 69 | 70 | 71 | def read_data(self): 72 | data = np.genfromtxt(self.filename,delimiter=",") 73 | return data[:,2],data[:,6], data[:,7], data[:,8], data[:,9] ,data[:,10], data[:,11],data[:,12] 74 | 75 | 76 | 77 | ''' 78 | Description: 79 | Calculates the probability in an interval [start_value, end_value] by integrating the PDF 80 | -- Input -- 81 | * start_value (float): small limit of interval 82 | * end_value (float): large limit of interval 83 | * eval_points (int): How many points should be used to approximate the integral 84 | * kd (KernelDensity): A kernel density object by sklearn 85 | 86 | -- Output -- 87 | * The probability of the PDF in the interval, rounded to 4 digits 88 | ''' 89 | def get_axis_probability(self,start_value, end_value, kd): 90 | # Number of evaluation points 91 | N = self.eval_samples 92 | step = (end_value - start_value) / (N - 1) # Step size 93 | 94 | x = np.linspace(start_value, end_value, N)[:, np.newaxis] # Generate values in the range 95 | kd_vals = np.exp(kd.score_samples(x)) # Get PDF values for each x 96 | probability = np.sum(kd_vals * step) # Approximate the integral of the PDF 97 | 98 | return probability.round(4) 99 | 100 | 101 | 102 | ''' 103 | Description: 104 | Employs KDE to estimate the PDF over a batch of data 105 | -- Input -- 106 | * force_msg (HighState/footForce:): Force message 107 | * imu_msg (sensor_msgs/Imu) : Linear acceleration and angular velocity message 108 | -- Output -- 109 | * Probability of stable contact 110 | ''' 111 | 112 | def stable_contact_detection(self,ax,ay,az,wx,wy,wz): 113 | 114 | N_samples = ax.shape[0] 115 | # Parameters (These are estimated experimentally ONCE during normal gait with stable contact) 116 | thres_ax = 0.4 # In g-scale of IMU 117 | thres_ay = 0.4 118 | thres_az = 0.4 119 | thres_wx = 0.04 120 | thres_wy = 0.04 121 | thres_wz = 0.04 122 | 123 | probs = np.empty((N_samples,)) 124 | 125 | 126 | print("[INFO]: Beginning Contact Estimation ") 127 | 128 | start = time.time() # Start time 129 | 130 | # First batch 131 | ax_batch = ax[0:self.batch_size] 132 | ay_batch = ay[0:self.batch_size] 133 | az_batch = az[0:self.batch_size] 134 | 135 | wx_batch = wx[0:self.batch_size] 136 | wy_batch = wy[0:self.batch_size] 137 | wz_batch = wz[0:self.batch_size] 138 | 139 | kde_ax = KernelDensity(bandwidth=self.ax_std, kernel='gaussian').fit(ax_batch.reshape((self.batch_size,1))) 140 | kde_ay = KernelDensity(bandwidth=self.ay_std, kernel='gaussian').fit(ay_batch.reshape((self.batch_size,1))) 141 | kde_az = KernelDensity(bandwidth=self.az_std, kernel='gaussian').fit(az_batch.reshape((self.batch_size,1))) 142 | 143 | kde_wx = KernelDensity(bandwidth=self.wx_std, kernel='gaussian').fit(wx_batch.reshape((self.batch_size,1))) 144 | kde_wy = KernelDensity(bandwidth=self.wy_std, kernel='gaussian').fit(wy_batch.reshape((self.batch_size,1))) 145 | kde_wz = KernelDensity(bandwidth=self.wz_std, kernel='gaussian').fit(wz_batch.reshape((self.batch_size,1))) 146 | 147 | 148 | prob_ax = self.get_axis_probability(-thres_ax,thres_ax,kde_ax) 149 | prob_ay = self.get_axis_probability(-thres_ay,thres_ay,kde_ay) 150 | prob_az = self.get_axis_probability(-thres_az,thres_az,kde_az) 151 | 152 | prob_wx = self.get_axis_probability(-thres_wx,thres_wx,kde_wx) 153 | prob_wy = self.get_axis_probability(-thres_wy,thres_wy,kde_wy) 154 | prob_wz = self.get_axis_probability(-thres_wz,thres_wz,kde_wz) 155 | 156 | probs[0:self.batch_size] = prob_ax*prob_ay*prob_az*prob_wx*prob_wy*prob_wz # First batch contact probabilities 157 | 158 | for i in range(self.batch_size,N_samples-self.batch_size): 159 | ax_batch = ax[i:(i+self.batch_size)] 160 | ay_batch = ay[i:(i+self.batch_size)] 161 | az_batch = az[i:(i+self.batch_size)] 162 | wx_batch = wx[i:(i+self.batch_size)] 163 | wy_batch = wy[i:(i+self.batch_size)] 164 | wz_batch = wz[i:(i+self.batch_size)] 165 | 166 | kde_ax = KernelDensity(bandwidth=self.ax_std, kernel='gaussian').fit(ax_batch.reshape((self.batch_size,1))) 167 | kde_ay = KernelDensity(bandwidth=self.ay_std, kernel='gaussian').fit(ay_batch.reshape((self.batch_size,1))) 168 | kde_az = KernelDensity(bandwidth=self.az_std, kernel='gaussian').fit(az_batch.reshape((self.batch_size,1))) 169 | 170 | kde_wx = KernelDensity(bandwidth=self.wx_std, kernel='gaussian').fit(wx_batch.reshape((self.batch_size,1))) 171 | kde_wy = KernelDensity(bandwidth=self.wy_std, kernel='gaussian').fit(wy_batch.reshape((self.batch_size,1))) 172 | kde_wz = KernelDensity(bandwidth=self.wz_std, kernel='gaussian').fit(wz_batch.reshape((self.batch_size,1))) 173 | 174 | 175 | prob_ax = self.get_axis_probability(-thres_ax,thres_ax,kde_ax) 176 | prob_ay = self.get_axis_probability(-thres_ay,thres_ay,kde_ay) 177 | prob_az = self.get_axis_probability(-thres_az,thres_az,kde_az) 178 | 179 | prob_wx = self.get_axis_probability(-thres_wx,thres_wx,kde_wx) 180 | prob_wy = self.get_axis_probability(-thres_wy,thres_wy,kde_wy) 181 | prob_wz = self.get_axis_probability(-thres_wz,thres_wz,kde_wz) 182 | 183 | probs[i] = prob_ax*prob_ay*prob_az*prob_wx*prob_wy*prob_wz 184 | 185 | end = time.time() 186 | 187 | elapsed_time = end - start 188 | 189 | print("[INFO]: Contact Estimation Complete! ") 190 | print(" 1) Number of estimated samples = " ,N_samples ,"Total time elapsed (s) = " ,elapsed_time) 191 | print(" 2) Refresh rate: ", N_samples/elapsed_time) 192 | 193 | 194 | return probs 195 | 196 | 197 | def plot_results(self,probs,labels,fz): 198 | time = np.arange(probs.shape[0]) 199 | fig, axs = plt.subplots(2) 200 | axs[0].plot(time,fz) 201 | axs[1].scatter(time,probs,c='g',s=5) 202 | axs[1].scatter(time,labels,c='r',s=5) 203 | plt.show() 204 | return 205 | 206 | 207 | 208 | if __name__ == "__main__": 209 | 210 | 211 | 212 | contact_estimator = pce() 213 | 214 | fz,ax,ay,az,wx,wy,wz,labels = contact_estimator.read_data() 215 | print("[INFO]: Data loaded successfully") 216 | 217 | 218 | probs = contact_estimator.stable_contact_detection(ax,ay,az,wx,wy,wz) 219 | 220 | contact_estimator.plot_results(probs,labels,fz) 221 | 222 | -------------------------------------------------------------------------------- /offline/src/go1_contact_estimation.py: -------------------------------------------------------------------------------- 1 | #! /usr/bin/env python3 2 | 3 | ''' 4 | * PCE - Probabilistic Contact Estimator 5 | * 6 | * Copyright 2022-2023 Michael Maravgakis and Despina-Ekaterini Argyropoulos, Foundation for Research and Technology Hellas (FORTH) 7 | * License: BSD 8 | * 9 | * Redistribution and use in source and binary forms, with or without 10 | * modification, are permitted provided that the following conditions are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above copyright 15 | * notice, this list of conditions and the following disclaimer in the 16 | * documentation and/or other materials provided with the distribution. 17 | * * Neither the name of the Foundation for Research and Technology Hellas (FORTH) 18 | * nor the names of its contributors may be used to endorse or promote products derived from 19 | * this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 24 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 25 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 26 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 27 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 28 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 29 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 30 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 31 | * POSSIBILITY OF SUCH DAMAGE. 32 | ''' 33 | 34 | import numpy as np 35 | from numpy import genfromtxt 36 | import matplotlib.pyplot as plt 37 | from sklearn.neighbors import KernelDensity 38 | import time 39 | 40 | 41 | data_filenames = ["../data/GO1_normal_surface.csv","../data/GO1_matress.csv","../data/GO1_slippery_surface.csv"] 42 | 43 | class pce: 44 | ''' 45 | Description: 46 | Initializes the contact estimator object 47 | Parameters: 48 | * batch_size (int): The size of the batch of data that the contact probability will be estimated 49 | * eval_samples (int): The number of points to use in order to estimate 50 | * [blank]_std (float): The standard deviation of the error of the measurements 51 | ''' 52 | 53 | def __init__(self): 54 | self.filename = data_filenames[2] 55 | self.batch_size = 50 56 | self.eval_samples = 500 57 | 58 | # Standard deviations 59 | self.ax_std = 0.02467 60 | self.ay_std = 0.02467 61 | self.az_std = 0.02467 62 | self.wx_std = 1 63 | self.wy_std = 1 64 | self.wz_std = 1 65 | 66 | 67 | self.data_batch = np.empty((self.batch_size,6)) # Batch of data to made predictions on 68 | 69 | 70 | def read_data(self): 71 | data = np.genfromtxt(self.filename,delimiter=",") 72 | f = data[:,0] 73 | foot_ax = data[:,1] 74 | foot_ay = data[:,2] 75 | foot_az = data[:,3] 76 | 77 | foot_wx = data[:,4] 78 | foot_wy = data[:,5] 79 | foot_wz = data[:,6] 80 | 81 | # Because the force measurement frame rate is different than 82 | # the IMU refresh rate 83 | for i in range(foot_ax.shape[0]): 84 | if (np.isnan(foot_ax[i])): 85 | break_point = i 86 | break 87 | foot_ax = foot_ax[0:break_point] 88 | foot_ay = foot_ay[0:break_point] 89 | foot_az = foot_az[0:break_point] 90 | foot_wx = foot_wx[0:break_point] 91 | foot_wy = foot_wy[0:break_point] 92 | foot_wz = foot_wz[0:break_point] 93 | 94 | bias_ax = 0.2 95 | bias_az = -0.32 96 | bias_ay = 1 97 | 98 | foot_ax += bias_ax 99 | foot_ay += bias_ay 100 | foot_az += bias_az 101 | 102 | return f, foot_ax,foot_ay,foot_az,foot_wx,foot_wy,foot_wz 103 | 104 | 105 | 106 | ''' 107 | Description: 108 | Calculates the probability in an interval [start_value, end_value] by integrating the PDF 109 | -- Input -- 110 | * start_value (float): small limit of interval 111 | * end_value (float): large limit of interval 112 | * eval_points (int): How many points should be used to approximate the integral 113 | * kd (KernelDensity): A kernel density object by sklearn 114 | 115 | -- Output -- 116 | * The probability of the PDF in the interval, rounded to 4 digits 117 | ''' 118 | def get_axis_probability(self,start_value, end_value, kd): 119 | # Number of evaluation points 120 | N = self.eval_samples 121 | step = (end_value - start_value) / (N - 1) # Step size 122 | 123 | x = np.linspace(start_value, end_value, N)[:, np.newaxis] # Generate values in the range 124 | kd_vals = np.exp(kd.score_samples(x)) # Get PDF values for each x 125 | probability = np.sum(kd_vals * step) # Approximate the integral of the PDF 126 | 127 | return probability.round(4) 128 | 129 | 130 | 131 | ''' 132 | Description: 133 | Employs KDE to estimate the PDF over a batch of data 134 | -- Input -- 135 | * force_msg (HighState/footForce:): Force message 136 | * imu_msg (sensor_msgs/Imu) : Linear acceleration and angular velocity message 137 | -- Output -- 138 | * Probability of stable contact 139 | ''' 140 | 141 | def stable_contact_detection(self,ax,ay,az,wx,wy,wz): 142 | 143 | N_samples = ax.shape[0] 144 | # Parameters (These are estimated experimentally ONCE during normal gait with stable contact) 145 | thres_ax = 0.9 # In g-scale of IMU 146 | thres_ay = 0.5 147 | thres_az = 0.3 148 | thres_wx = 56 149 | thres_wy = 50 150 | thres_wz = 100 151 | 152 | probs = np.empty((N_samples,)) 153 | 154 | 155 | print("[INFO]: Beginning Contact Estimation ") 156 | 157 | start = time.time() # Start time 158 | 159 | # First batch 160 | ax_batch = ax[0:self.batch_size] 161 | ay_batch = ay[0:self.batch_size] 162 | az_batch = az[0:self.batch_size] 163 | 164 | wx_batch = wx[0:self.batch_size] 165 | wy_batch = wy[0:self.batch_size] 166 | wz_batch = wz[0:self.batch_size] 167 | 168 | kde_ax = KernelDensity(bandwidth=self.ax_std, kernel='gaussian').fit(ax_batch.reshape((self.batch_size,1))) 169 | kde_ay = KernelDensity(bandwidth=self.ay_std, kernel='gaussian').fit(ay_batch.reshape((self.batch_size,1))) 170 | kde_az = KernelDensity(bandwidth=self.az_std, kernel='gaussian').fit(az_batch.reshape((self.batch_size,1))) 171 | 172 | kde_wx = KernelDensity(bandwidth=self.wx_std, kernel='gaussian').fit(wx_batch.reshape((self.batch_size,1))) 173 | kde_wy = KernelDensity(bandwidth=self.wy_std, kernel='gaussian').fit(wy_batch.reshape((self.batch_size,1))) 174 | kde_wz = KernelDensity(bandwidth=self.wz_std, kernel='gaussian').fit(wz_batch.reshape((self.batch_size,1))) 175 | 176 | 177 | prob_ax = self.get_axis_probability(-thres_ax,thres_ax,kde_ax) 178 | prob_ay = self.get_axis_probability(-thres_ay,thres_ay,kde_ay) 179 | prob_az = self.get_axis_probability(-thres_az,thres_az,kde_az) 180 | 181 | prob_wx = self.get_axis_probability(-thres_wx,thres_wx,kde_wx) 182 | prob_wy = self.get_axis_probability(-thres_wy,thres_wy,kde_wy) 183 | prob_wz = self.get_axis_probability(-thres_wz,thres_wz,kde_wz) 184 | 185 | probs[0:self.batch_size] = prob_ax*prob_ay*prob_az*prob_wx*prob_wy*prob_wz # First batch contact probabilities 186 | 187 | for i in range(self.batch_size,N_samples): 188 | ax_batch = ax[(i-self.batch_size):i] 189 | ay_batch = ay[(i-self.batch_size):i] 190 | az_batch = az[(i-self.batch_size):i] 191 | wx_batch = wx[(i-self.batch_size):i] 192 | wy_batch = wy[(i-self.batch_size):i] 193 | wz_batch = wz[(i-self.batch_size):i] 194 | 195 | kde_ax = KernelDensity(bandwidth=self.ax_std, kernel='gaussian').fit(ax_batch.reshape((self.batch_size,1))) 196 | kde_ay = KernelDensity(bandwidth=self.ay_std, kernel='gaussian').fit(ay_batch.reshape((self.batch_size,1))) 197 | kde_az = KernelDensity(bandwidth=self.az_std, kernel='gaussian').fit(az_batch.reshape((self.batch_size,1))) 198 | 199 | kde_wx = KernelDensity(bandwidth=self.wx_std, kernel='gaussian').fit(wx_batch.reshape((self.batch_size,1))) 200 | kde_wy = KernelDensity(bandwidth=self.wy_std, kernel='gaussian').fit(wy_batch.reshape((self.batch_size,1))) 201 | kde_wz = KernelDensity(bandwidth=self.wz_std, kernel='gaussian').fit(wz_batch.reshape((self.batch_size,1))) 202 | 203 | 204 | prob_ax = self.get_axis_probability(-thres_ax,thres_ax,kde_ax) 205 | prob_ay = self.get_axis_probability(-thres_ay,thres_ay,kde_ay) 206 | prob_az = self.get_axis_probability(-thres_az,thres_az,kde_az) 207 | 208 | prob_wx = self.get_axis_probability(-thres_wx,thres_wx,kde_wx) 209 | prob_wy = self.get_axis_probability(-thres_wy,thres_wy,kde_wy) 210 | prob_wz = self.get_axis_probability(-thres_wz,thres_wz,kde_wz) 211 | 212 | probs[i] = prob_ax*prob_ay*prob_az*prob_wx*prob_wy*prob_wz 213 | 214 | end = time.time() 215 | 216 | elapsed_time = end - start 217 | 218 | print("[INFO]: Contact Estimation Complete! ") 219 | print(" 1) Number of estimated samples = " ,N_samples ,"Total time elapsed (s) = " ,elapsed_time) 220 | print(" 2) Refresh rate: ", N_samples/elapsed_time) 221 | 222 | 223 | return probs 224 | 225 | 226 | def plot_results(self,probs,fz): 227 | 228 | time_imu = np.arange(0,probs.shape[0]*0.004,0.004) 229 | time_f = np.arange(0,fz.shape[0]*0.002,0.002) 230 | 231 | 232 | fig, axs = plt.subplots(2) 233 | axs[0].plot(time_f,fz) 234 | axs[0].set_ylabel(r'$F_z(N)$ ',fontsize=20) 235 | 236 | 237 | axs[1].scatter(time_imu,probs,c='g',s=5) 238 | axs[1].set_ylabel(r'$P_{tot}(stable)$',fontsize=20) 239 | axs[1].set_xlabel(r'Time (s)',fontsize=16) 240 | # axs[0].axvspan(3.326, 4.673, facecolor='purple', alpha=0.2)#,label = r"$\mu_s = 0.03$") 241 | # axs[1].axvspan(3.525, 4.960, facecolor='purple', alpha=0.2) 242 | 243 | axs[0].tick_params( 244 | axis='x', # changes apply to the x-axis 245 | which='both', # both major and minor ticks are affected 246 | bottom=False, # ticks along the bottom edge are off 247 | top=False, # ticks along the top edge are off 248 | labelbottom=False) # labels along the bottom edge are off 249 | 250 | fig.subplots_adjust(wspace=0, hspace=0) 251 | plt.show() 252 | return 253 | 254 | 255 | 256 | if __name__ == "__main__": 257 | 258 | 259 | 260 | contact_estimator = pce() 261 | 262 | fz,ax,ay,az,wx,wy,wz = contact_estimator.read_data() 263 | print("[INFO]: Data loaded successfully") 264 | 265 | 266 | probs = contact_estimator.stable_contact_detection(ax,ay,az,wx,wy,wz) 267 | 268 | contact_estimator.plot_results(probs,fz) 269 | 270 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | pce 4 | 0.0.0 5 | Probabilistic Contact Estimation for Legged Robots in Real-time (~500HZ) + Offline data for ATLAS simulated and real GO1 quadrupedal robot 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | BSD 17 | 18 | 19 | catkin 20 | roscpp 21 | rospy 22 | std_msgs 23 | roscpp 24 | rospy 25 | std_msgs 26 | roscpp 27 | rospy 28 | std_msgs 29 | unitree_legged_msgs 30 | eigen 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /src/check_forces.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | // #include "convert.h" 5 | 6 | int main(int argc, char **argv) 7 | { 8 | ros::init(argc, argv, "example_walk_without_lcm"); 9 | 10 | std::cout << "WARNING: Control level is set to HIGH-level." << std::endl 11 | << "Make sure the robot is standing on the ground." << std::endl 12 | << "Press Enter to continue..." << std::endl; 13 | std::cin.ignore(); 14 | 15 | ros::NodeHandle nh; 16 | 17 | ros::Rate loop_rate(500); 18 | 19 | long motiontime = 0; 20 | 21 | unitree_legged_msgs::HighCmd high_cmd_ros; 22 | 23 | ros::Publisher pub = nh.advertise("high_cmd", 1000); 24 | 25 | while (ros::ok()) 26 | { 27 | 28 | motiontime += 2; 29 | 30 | high_cmd_ros.head[0] = 0xFE; 31 | high_cmd_ros.head[1] = 0xEF; 32 | high_cmd_ros.levelFlag = 0xee; //HIGHLEVEL; 33 | high_cmd_ros.mode = 0; 34 | high_cmd_ros.gaitType = 0; 35 | high_cmd_ros.speedLevel = 0; 36 | high_cmd_ros.footRaiseHeight = 0; 37 | high_cmd_ros.bodyHeight = 0; 38 | high_cmd_ros.euler[0] = 0; 39 | high_cmd_ros.euler[1] = 0; 40 | high_cmd_ros.euler[2] = 0; 41 | high_cmd_ros.velocity[0] = 0.0f; 42 | high_cmd_ros.velocity[1] = 0.0f; 43 | high_cmd_ros.yawSpeed = 0.0f; 44 | high_cmd_ros.reserve = 0; 45 | 46 | if (motiontime > 0 ) 47 | { 48 | high_cmd_ros.mode = 0; 49 | high_cmd_ros.gaitType = 0; 50 | } 51 | 52 | pub.publish(high_cmd_ros); 53 | 54 | ros::spinOnce(); 55 | loop_rate.sleep(); 56 | } 57 | 58 | return 0; 59 | } -------------------------------------------------------------------------------- /src/go1_pce.py: -------------------------------------------------------------------------------- 1 | #! /usr/bin/env python3 2 | 3 | # ROS libraries 4 | import rospy 5 | 6 | # DESPINA : add the correct IMU and FORCE rosmsgs 7 | from sensor_msgs.msg import Imu # IMU msg 8 | from unitree_legged_msgs.msg import HighState # force msg Unitree 9 | 10 | from std_msgs.msg import Float32 # Contact probability msg 11 | # Generic libraries 12 | import numpy as np 13 | from numpy import genfromtxt 14 | import matplotlib.pyplot as plt 15 | from sklearn.neighbors import KernelDensity 16 | 17 | FOOT_ID = 1 18 | 19 | class pce: 20 | def __init__(self,force_topic_name,imu_topic_name,params_filename,batch_size,eval_samples): 21 | self.force_topic= force_topic_name 22 | self.imu_topic = imu_topic_name 23 | self.batch_size = batch_size 24 | self.eval_samples = eval_samples 25 | self.mytimer = 0 26 | 27 | # Get params from file and distribute them to variables # DESPINA : change params to go to the right variable 28 | self.params = genfromtxt(params_filename,delimiter=',') # Bias and std, for each axis 29 | self.ax_bias = self.params[0] 30 | self.ay_bias = self.params[1] 31 | self.az_bias = self.params[2] 32 | self.wx_bias = self.params[3] 33 | self.wy_bias = self.params[4] 34 | self.wz_bias = self.params[5] 35 | 36 | self.fz_bias = self.params[6] 37 | 38 | self.ax_std = self.params[7] 39 | self.ay_std = self.params[8] 40 | self.az_std = self.params[9] 41 | self.wx_std = self.params[10] 42 | self.wy_std = self.params[11] 43 | self.wz_std = self.params[12] 44 | 45 | print(self.ax_bias, self.wz_std) 46 | 47 | self.data_batch = np.empty((self.batch_size,7)) # Batch of data to made predictions on 48 | 49 | 50 | rospy.init_node('ProbabilisticContactEstimation', anonymous=True) 51 | 52 | self.rate = rospy.Rate(250) 53 | self.initialize_batch() 54 | 55 | pub = rospy.Publisher('/contact_probability', Float32, queue_size=10) 56 | 57 | stable_probability = Float32() 58 | 59 | while not rospy.is_shutdown(): 60 | self.mytimer = self.mytimer + 2 61 | # DESPINA: Fix msg , also maybe add condition to check if msg actually arrived 62 | force_msg = rospy.wait_for_message(self.force_topic, HighState , timeout=None) 63 | imu_msg = rospy.wait_for_message(self.imu_topic, Imu , timeout=None) 64 | 65 | stable_probability.data = self.stable_contact_detection(force_msg,imu_msg) 66 | # if self.mytimer > 3500: 67 | # stable_probability.data = 0.3 68 | print(stable_probability.data,"\n") 69 | pub.publish(stable_probability) 70 | self.rate.sleep() 71 | 72 | 73 | ''' 74 | Description: 75 | Initializes the first batch of data to avoid seg faults 76 | ''' 77 | def initialize_batch(self): 78 | 79 | print("In initialize_batch START") 80 | 81 | for i in range(self.batch_size): 82 | force_msg = rospy.wait_for_message(self.force_topic, HighState, timeout=None) 83 | imu_msg = rospy.wait_for_message(self.imu_topic, Imu, timeout=None) 84 | 85 | self.data_batch[i,0] = force_msg.footForce[FOOT_ID] 86 | self.data_batch[i,1] = imu_msg.linear_acceleration.x 87 | self.data_batch[i,2] = imu_msg.linear_acceleration.y 88 | self.data_batch[i,3] = imu_msg.linear_acceleration.z 89 | self.data_batch[i,4] = imu_msg.angular_velocity.x 90 | self.data_batch[i,5] = imu_msg.angular_velocity.y 91 | self.data_batch[i,6] = imu_msg.angular_velocity.z 92 | self.rate.sleep() 93 | 94 | print("In initialize_batch END") 95 | 96 | 97 | ''' 98 | Description: 99 | Calculates the probability in an interval [start_value, end_value] by integrating the PDF 100 | -- Input -- 101 | * start_value (float): small limit of interval 102 | * end_value (float): large limit of interval 103 | * eval_points (int): How many points should be used to approximate the integral 104 | * kd (KernelDensity): A kernel density object by sklearn 105 | 106 | -- Output -- 107 | * The probability of the PDF in the interval, rounded to 4 digits 108 | ''' 109 | def get_axis_probability(self,start_value, end_value, kd): 110 | # Number of evaluation points 111 | N = self.eval_samples 112 | step = (end_value - start_value) / (N - 1) # Step size 113 | 114 | x = np.linspace(start_value, end_value, N)[:, np.newaxis] # Generate values in the range 115 | kd_vals = np.exp(kd.score_samples(x)) # Get PDF values for each x 116 | probability = np.sum(kd_vals * step) # Approximate the integral of the PDF 117 | 118 | return probability.round(4) 119 | 120 | 121 | 122 | ''' 123 | Description: 124 | Employs KDE to estimate the PDF over a batch of data 125 | -- Input -- 126 | * force_msg (HighState/footForce:): Force message 127 | * imu_msg (sensor_msgs/Imu) : Linear acceleration and angular velocity message 128 | -- Output -- 129 | * Probability of stable contact 130 | ''' 131 | 132 | def stable_contact_detection(self,force_msg,imu_msg): 133 | # DESPINA TODO: assign msg values to f and IMU measurements 134 | f = force_msg.footForce[FOOT_ID] + self.fz_bias # TODO select foot 135 | 136 | ax = imu_msg.linear_acceleration.x - self.ax_bias 137 | ay = imu_msg.linear_acceleration.y - self.ay_bias 138 | az = imu_msg.linear_acceleration.z - self.az_bias 139 | 140 | wx = imu_msg.angular_velocity.x - self.wx_bias 141 | wy = imu_msg.angular_velocity.y - self.wy_bias 142 | wz = imu_msg.angular_velocity.z - self.wz_bias 143 | 144 | 145 | # Parameters (These are estimated experimentally ONCE during normal gait with stable contact) 146 | thres_ax = 0.6 # In g-scale of IMU 147 | thres_ay = 0.5 148 | thres_az = 0.6 149 | thres_wx = 60 150 | thres_wy = 35 151 | thres_wz = 70 152 | 153 | # print(self.data_batch.shape) 154 | self.data_batch = np.delete(self.data_batch,0,axis = 0) # Delete first element 155 | 156 | self.data_batch = np.vstack( [self.data_batch, np.array([f,ax,ay,az,wx,wy,wz]) ] ) # Append the new measurement 157 | # print(self.data_batch.shape) 158 | ax_batch = self.data_batch[:,1] 159 | ay_batch = self.data_batch[:,2] 160 | az_batch = self.data_batch[:,3] 161 | wx_batch = self.data_batch[:,4] 162 | wy_batch = self.data_batch[:,5] 163 | wz_batch = self.data_batch[:,6] 164 | 165 | 166 | 167 | 168 | kde_ax = KernelDensity(bandwidth=self.ax_std, kernel='gaussian').fit(ax_batch.reshape((self.batch_size,1))) 169 | kde_ay = KernelDensity(bandwidth=self.ay_std, kernel='gaussian').fit(ay_batch.reshape((self.batch_size,1))) 170 | kde_az = KernelDensity(bandwidth=self.az_std, kernel='gaussian').fit(az_batch.reshape((self.batch_size,1))) 171 | kde_wx = KernelDensity(bandwidth=self.wx_std, kernel='gaussian').fit(wx_batch.reshape((self.batch_size,1))) 172 | kde_wy = KernelDensity(bandwidth=self.wy_std, kernel='gaussian').fit(wy_batch.reshape((self.batch_size,1))) 173 | kde_wz = KernelDensity(bandwidth=self.wz_std, kernel='gaussian').fit(wz_batch.reshape((self.batch_size,1))) 174 | 175 | 176 | prob_ax = self.get_axis_probability(-thres_ax,thres_ax,kde_ax) 177 | prob_ay = self.get_axis_probability(-thres_ay,thres_ay,kde_ay) 178 | prob_az = self.get_axis_probability(-thres_az,thres_az,kde_az) 179 | 180 | 181 | 182 | prob_wx = self.get_axis_probability(-thres_wx,thres_wx,kde_wx) 183 | prob_wy = self.get_axis_probability(-thres_wy,thres_wy,kde_wy) 184 | prob_wz = self.get_axis_probability(-thres_wz,thres_wz,kde_wz) 185 | 186 | return prob_ax*prob_ay*prob_az*prob_wx*prob_wy*prob_wz 187 | 188 | 189 | 190 | 191 | if __name__ == "__main__": 192 | try: 193 | # DESPINA: add the topic names for force + imu, the params filename with bias and stds 194 | force_topic_name = "/high_state" 195 | imu_topic_name = "/imu" 196 | params_filename = 'imuBias.txt' 197 | 198 | batch_size = 50 199 | eval_samples = 500 200 | pce(force_topic_name,imu_topic_name,params_filename,batch_size,eval_samples) 201 | 202 | 203 | except rospy.ROSInterruptException: 204 | print("Fail with ROS.") 205 | -------------------------------------------------------------------------------- /src/imuBias.txt: -------------------------------------------------------------------------------- 1 | -0.15052,0.926221,0.364554,0.386715,0.20504,0.176271,65,0.00216147,0.00196253,0.00390694,0.056809,0.0608287,0.029905 -------------------------------------------------------------------------------- /src/init_imu_force.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | using namespace boost::accumulators; 13 | using namespace std; 14 | 15 | std::vector< double > arr_ax, arr_ay, arr_az; 16 | std::vector< double > arr_wx, arr_wy, arr_wz; 17 | std::vector< double > arr_f; 18 | 19 | void initimuCallback(const sensor_msgs::Imu::ConstPtr &msg) 20 | { 21 | 22 | // linear_acceleration 23 | arr_ax.push_back(msg->linear_acceleration.x); 24 | arr_ay.push_back(msg->linear_acceleration.y); 25 | arr_az.push_back(msg->linear_acceleration.z); 26 | 27 | // angular_velocity 28 | arr_wx.push_back(msg->angular_velocity.x); 29 | arr_wy.push_back(msg->angular_velocity.y); 30 | arr_wz.push_back(msg->angular_velocity.z); 31 | 32 | 33 | } 34 | 35 | void initforceCallback(const unitree_legged_msgs::HighState::ConstPtr &msg) 36 | { 37 | 38 | // force 39 | arr_f.push_back(msg->footForce[2]); // TODO which foot 40 | 41 | } 42 | 43 | // void calc_mean_std() 44 | // { 45 | // // mean of angular_velocity vectors 46 | // double mean_wx = std::accumulate(arr_wx.begin(), arr_wx.end(), decltype(arr_wx)::value_type(0)); 47 | // mean_wx /= num_collect; 48 | // double mean_wy = std::accumulate(arr_wy.begin(), arr_wy.end(), decltype(arr_wy)::value_type(0)); 49 | // mean_wy /= num_collect; 50 | // double mean_wz = std::accumulate(arr_wz.begin(), arr_wz.end(), decltype(arr_wz)::value_type(0)); 51 | // mean_wz /= num_collect; 52 | 53 | // // mean of linear_acceleration vectors 54 | // double mean_ax = std::accumulate(arr_ax.begin(), arr_ax.end(), decltype(arr_ax)::value_type(0)); 55 | // mean_ax /= num_collect; 56 | // double mean_ay = std::accumulate(arr_ay.begin(), arr_ay.end(), decltype(arr_ay)::value_type(0)); 57 | // mean_ay /= num_collect; 58 | // double mean_az = std::accumulate(arr_az.begin(), arr_az.end(), decltype(arr_az)::value_type(0)); 59 | // mean_az /= num_collect; 60 | // } 61 | 62 | int main(int argc, char **argv) 63 | { 64 | ros::init(argc, argv, "init_imu_things"); 65 | 66 | std::cout << "This will store data for Imu sensor Bias at imuBias.txt" << std::endl 67 | << "Press Enter to continue..." << std::endl; 68 | std::cin.ignore(); 69 | 70 | printf("Wait for 4sec...\n"); 71 | 72 | ros::NodeHandle nh; 73 | 74 | ros::Rate loop_rate(250); 75 | 76 | ros::Subscriber imu_sub = nh.subscribe("imu", 1, initimuCallback); 77 | ros::Subscriber force_sub = nh.subscribe("high_state", 1, initforceCallback); 78 | 79 | long num_collect = 0; 80 | 81 | std::string bias_file; 82 | if (!nh.getParam("/imu_bias_txt",bias_file)) 83 | { 84 | ROS_ERROR("Param /imu_bias_txt missing"); 85 | } 86 | std::cout< > acc_ax; 100 | for_each(arr_ax.begin(), arr_ax.end(), bind(ref(acc_ax), _1)); 101 | double mean_ax = mean(acc_ax); 102 | double std_ax = sqrt(variance(acc_ax)) ; 103 | 104 | // Mean and std for Ay 105 | accumulator_set > acc_ay; 106 | for_each(arr_ay.begin(), arr_ay.end(), bind(ref(acc_ay), _1)); 107 | double mean_ay = mean(acc_ay); 108 | double std_ay = sqrt(variance(acc_ay)) ; 109 | 110 | // Mean and std for Ay 111 | accumulator_set > acc_az; 112 | for_each(arr_az.begin(), arr_az.end(), bind(ref(acc_az), _1)); 113 | double mean_az = mean(acc_az); 114 | double std_az = sqrt(variance(acc_az)) ; 115 | 116 | // Mean for F 117 | accumulator_set > acc_f; 118 | for_each(arr_f.begin(), arr_f.end(), bind(ref(acc_f), _1)); 119 | double mean_f = mean(acc_f); 120 | 121 | // Mean and std for Wx 122 | accumulator_set > acc_wx; 123 | for_each(arr_wx.begin(), arr_wx.end(), bind(ref(acc_wx), _1)); 124 | double mean_wx = mean(acc_wx); 125 | double std_wx = sqrt(variance(acc_wx)) ; 126 | 127 | // Mean and std for Wy 128 | accumulator_set > acc_wy; 129 | for_each(arr_wy.begin(), arr_wy.end(), bind(ref(acc_wy), _1)); 130 | double mean_wy = mean(acc_wy); 131 | double std_wy = sqrt(variance(acc_wy)) ; 132 | 133 | // Mean and std for Wy 134 | accumulator_set > acc_wz; 135 | for_each(arr_wz.begin(), arr_wz.end(), bind(ref(acc_wz), _1)); 136 | double mean_wz = mean(acc_wz); 137 | double std_wz = sqrt(variance(acc_wz)) ; 138 | 139 | 140 | 141 | ofstream myfile; // file for imu sensor things 142 | myfile.open (bias_file); 143 | 144 | myfile << mean_ax << ',' << mean_ay << ',' << mean_az << ','; 145 | myfile << mean_wx << ',' << mean_wy << ','<< mean_wz << ','; 146 | 147 | // TODO fz_bias 148 | myfile << mean_f << ','; 149 | 150 | myfile << std_ax << ',' << std_ay << ',' << std_az << ','; 151 | myfile << std_wx << ',' << std_wy << ',' << std_wz ; 152 | 153 | // close file 154 | myfile.close(); 155 | 156 | printf("Bias and std at your service!\t"); 157 | 158 | return 0; 159 | } -------------------------------------------------------------------------------- /src/slip_recovery.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include "convert.h" 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | using namespace boost::accumulators; 12 | 13 | 14 | ros::Publisher pub ; 15 | ros::Subscriber slip_sub ; 16 | ros::Subscriber high_sub ; 17 | 18 | // Define them 19 | int SIZEQ = 70; 20 | double Thres_Prob = 0.7 ; 21 | int TIMES_OF_STABILITY = 4000; 22 | 23 | std::deque mydeque; 24 | long stable_count = 0; 25 | int STATE_CASE = 0; 26 | double PATAEI; 27 | 28 | void slipDetectCallback(const std_msgs::Float32::ConstPtr &msg) 29 | { 30 | // printf("slipDetectCallback is running!\t%ld\n", stable_count++); 31 | stable_count += 1; 32 | 33 | if (PATAEI > 65) 34 | { 35 | // add new value, pop the latest FIFO 36 | mydeque.push_back (msg->data); 37 | mydeque.pop_front(); 38 | 39 | // calc mean of deque 40 | accumulator_set > acc_Q; 41 | for_each(mydeque.begin(), mydeque.end(), bind(ref(acc_Q), _1)); 42 | 43 | if (mean(acc_Q) < Thres_Prob ) 44 | { 45 | // slip detected, change case 46 | STATE_CASE = 1; 47 | 48 | ROS_INFO("%f", msg->data); 49 | 50 | // reset the stable moments 51 | stable_count = 0; 52 | } 53 | } 54 | 55 | 56 | 57 | } 58 | 59 | void highCallback(const unitree_legged_msgs::HighState::ConstPtr &msg) 60 | { 61 | PATAEI = msg->footForce[1] ; 62 | } 63 | 64 | int main(int argc, char **argv) 65 | { 66 | ros::init(argc, argv, "example_walk_without_lcm"); 67 | 68 | std::cout << "WARNING: Control level is set to HIGH-level." << std::endl 69 | << "Make sure the robot is standing on the ground." << std::endl 70 | << "Press Enter to continue..." << std::endl; 71 | std::cin.ignore(); 72 | 73 | ros::NodeHandle nh; 74 | 75 | ros::Rate loop_rate(500); 76 | 77 | 78 | // init queue 79 | for (int i = 0 ; i < SIZEQ ; i++) mydeque.push_back(1); // init with stale prob 80 | 81 | pub = nh.advertise("high_cmd", 1000); 82 | slip_sub = nh.subscribe("contact_probability", 1, slipDetectCallback); 83 | high_sub = nh.subscribe("high_state", 1, highCallback); 84 | 85 | long motiontime = 0; 86 | long recoverytime = 0; 87 | 88 | unitree_legged_msgs::HighCmd high_cmd_ros; 89 | 90 | while (ros::ok()) 91 | { 92 | 93 | high_cmd_ros.head[0] = 0xFE; 94 | high_cmd_ros.head[1] = 0xEF; 95 | high_cmd_ros.levelFlag = 0xee; //HIGHLEVEL; 96 | high_cmd_ros.mode = 0; 97 | high_cmd_ros.gaitType = 0; 98 | high_cmd_ros.speedLevel = 0; 99 | high_cmd_ros.footRaiseHeight = 0; 100 | high_cmd_ros.bodyHeight = 0; 101 | high_cmd_ros.euler[0] = 0; 102 | high_cmd_ros.euler[1] = 0; 103 | high_cmd_ros.euler[2] = 0; 104 | high_cmd_ros.velocity[0] = 0.0f; 105 | high_cmd_ros.velocity[1] = 0.0f; 106 | high_cmd_ros.yawSpeed = 0.0f; 107 | high_cmd_ros.reserve = 0; 108 | 109 | switch (STATE_CASE) 110 | { 111 | case 1: // slip detected 112 | /* code */ 113 | recoverytime += 2; 114 | if (recoverytime > 0 ) //&& recoverytime < 3000 115 | { 116 | // 1. force stand 117 | high_cmd_ros.mode = 1; 118 | } 119 | 120 | break; 121 | 122 | default: // normal mode 0 123 | motiontime += 2; 124 | if (motiontime > 0 && motiontime < 3000) 125 | { 126 | high_cmd_ros.mode = 1; 127 | } 128 | if (motiontime > 3000 && motiontime < 10000) 129 | { 130 | high_cmd_ros.mode = 2; 131 | high_cmd_ros.gaitType = 3; 132 | high_cmd_ros.velocity[0] = 0.2f; // -1 ~ +1 133 | high_cmd_ros.footRaiseHeight = 0.08; 134 | printf("walk\n"); 135 | } 136 | break; 137 | } 138 | 139 | pub.publish(high_cmd_ros); 140 | 141 | ros::spinOnce(); 142 | loop_rate.sleep(); 143 | } 144 | 145 | return 0; 146 | } --------------------------------------------------------------------------------